diff --git a/apriltag/src/dev/native/cpp/main.cpp b/apriltag/src/dev/native/cpp/main.cpp index 346b591d44..10aad9b24a 100644 --- a/apriltag/src/dev/native/cpp/main.cpp +++ b/apriltag/src/dev/native/cpp/main.cpp @@ -5,7 +5,7 @@ #include "wpi/apriltag/AprilTagDetector.hpp" int main() { - frc::AprilTagDetector detector; + wpi::apriltag::AprilTagDetector detector; detector.AddFamily("tag16h5"); detector.SetConfig({.refineEdges = false}); } diff --git a/apriltag/src/main/native/cpp/AprilTag.cpp b/apriltag/src/main/native/cpp/AprilTag.cpp index 8c8309bcb8..adcbe68fb5 100644 --- a/apriltag/src/main/native/cpp/AprilTag.cpp +++ b/apriltag/src/main/native/cpp/AprilTag.cpp @@ -20,9 +20,9 @@ #include "tag16h5.h" #include "tag36h11.h" -using namespace frc; +using namespace wpi::apriltag; -static bool FamilyToImage(wpi::RawFrame* frame, apriltag_family_t* family, +static bool FamilyToImage(wpi::util::RawFrame* frame, apriltag_family_t* family, int id) { image_u8_t* image = apriltag_to_image(family, id); size_t totalDataSize = image->height * image->stride; @@ -37,25 +37,25 @@ static bool FamilyToImage(wpi::RawFrame* frame, apriltag_family_t* family, return rv; } -bool AprilTag::Generate36h11AprilTagImage(wpi::RawFrame* frame, int id) { +bool AprilTag::Generate36h11AprilTagImage(wpi::util::RawFrame* frame, int id) { apriltag_family_t* tagFamily = tag36h11_create(); bool rv = FamilyToImage(frame, tagFamily, id); tag36h11_destroy(tagFamily); return rv; } -bool AprilTag::Generate16h5AprilTagImage(wpi::RawFrame* frame, int id) { +bool AprilTag::Generate16h5AprilTagImage(wpi::util::RawFrame* frame, int id) { apriltag_family_t* tagFamily = tag16h5_create(); bool rv = FamilyToImage(frame, tagFamily, id); tag16h5_destroy(tagFamily); return rv; } -void frc::to_json(wpi::json& json, const AprilTag& apriltag) { - json = wpi::json{{"ID", apriltag.ID}, {"pose", apriltag.pose}}; +void wpi::apriltag::to_json(wpi::util::json& json, const AprilTag& apriltag) { + json = wpi::util::json{{"ID", apriltag.ID}, {"pose", apriltag.pose}}; } -void frc::from_json(const wpi::json& json, AprilTag& apriltag) { +void wpi::apriltag::from_json(const wpi::util::json& json, AprilTag& apriltag) { apriltag.ID = json.at("ID").get(); - apriltag.pose = json.at("pose").get(); + apriltag.pose = json.at("pose").get(); } diff --git a/apriltag/src/main/native/cpp/AprilTagDetection.cpp b/apriltag/src/main/native/cpp/AprilTagDetection.cpp index 9e88513b3c..61001b5cb8 100644 --- a/apriltag/src/main/native/cpp/AprilTagDetection.cpp +++ b/apriltag/src/main/native/cpp/AprilTagDetection.cpp @@ -16,7 +16,7 @@ #include "apriltag.h" -using namespace frc; +using namespace wpi::apriltag; static_assert(sizeof(AprilTagDetection) == sizeof(apriltag_detection_t), "structure sizes don't match"); diff --git a/apriltag/src/main/native/cpp/AprilTagDetector.cpp b/apriltag/src/main/native/cpp/AprilTagDetector.cpp index fd3a41eebc..d3c85f1001 100644 --- a/apriltag/src/main/native/cpp/AprilTagDetector.cpp +++ b/apriltag/src/main/native/cpp/AprilTagDetector.cpp @@ -19,7 +19,7 @@ #include "tag16h5.h" #include "tag36h11.h" -using namespace frc; +using namespace wpi::apriltag; AprilTagDetector::Results::Results(void* impl, const private_init&) : span{reinterpret_cast( diff --git a/apriltag/src/main/native/cpp/AprilTagFieldLayout.cpp b/apriltag/src/main/native/cpp/AprilTagFieldLayout.cpp index 82b964d6a0..6ab3362d27 100644 --- a/apriltag/src/main/native/cpp/AprilTagFieldLayout.cpp +++ b/apriltag/src/main/native/cpp/AprilTagFieldLayout.cpp @@ -14,26 +14,26 @@ #include "wpi/util/json.hpp" #include "wpi/util/raw_ostream.hpp" -using namespace frc; +using namespace wpi::apriltag; AprilTagFieldLayout::AprilTagFieldLayout(std::string_view path) { - auto fileBuffer = wpi::MemoryBuffer::GetFile(path); + auto fileBuffer = wpi::util::MemoryBuffer::GetFile(path); if (!fileBuffer) { throw std::runtime_error(fmt::format("Cannot open file: {}", path)); } - wpi::json json = wpi::json::parse(fileBuffer.value()->GetCharBuffer()); + wpi::util::json json = wpi::util::json::parse(fileBuffer.value()->GetCharBuffer()); for (const auto& tag : json.at("tags").get>()) { m_apriltags[tag.ID] = tag; } - m_fieldWidth = units::meter_t{json.at("field").at("width").get()}; - m_fieldLength = units::meter_t{json.at("field").at("length").get()}; + m_fieldWidth = wpi::units::meter_t{json.at("field").at("width").get()}; + m_fieldLength = wpi::units::meter_t{json.at("field").at("length").get()}; } AprilTagFieldLayout::AprilTagFieldLayout(std::vector apriltags, - units::meter_t fieldLength, - units::meter_t fieldWidth) + wpi::units::meter_t fieldLength, + wpi::units::meter_t fieldWidth) : m_fieldLength(std::move(fieldLength)), m_fieldWidth(std::move(fieldWidth)) { for (const auto& tag : apriltags) { @@ -41,11 +41,11 @@ AprilTagFieldLayout::AprilTagFieldLayout(std::vector apriltags, } } -units::meter_t AprilTagFieldLayout::GetFieldLength() const { +wpi::units::meter_t AprilTagFieldLayout::GetFieldLength() const { return m_fieldLength; } -units::meter_t AprilTagFieldLayout::GetFieldWidth() const { +wpi::units::meter_t AprilTagFieldLayout::GetFieldWidth() const { return m_fieldWidth; } @@ -61,26 +61,26 @@ std::vector AprilTagFieldLayout::GetTags() const { void AprilTagFieldLayout::SetOrigin(OriginPosition origin) { switch (origin) { case OriginPosition::kBlueAllianceWallRightSide: - SetOrigin(Pose3d{}); + SetOrigin(wpi::math::Pose3d{}); break; case OriginPosition::kRedAllianceWallRightSide: - SetOrigin(Pose3d{Translation3d{m_fieldLength, m_fieldWidth, 0_m}, - Rotation3d{0_deg, 0_deg, 180_deg}}); + SetOrigin(wpi::math::Pose3d{wpi::math::Translation3d{m_fieldLength, m_fieldWidth, 0_m}, + wpi::math::Rotation3d{0_deg, 0_deg, 180_deg}}); break; default: throw std::invalid_argument("Invalid origin"); } } -void AprilTagFieldLayout::SetOrigin(const Pose3d& origin) { +void AprilTagFieldLayout::SetOrigin(const wpi::math::Pose3d& origin) { m_origin = origin; } -Pose3d AprilTagFieldLayout::GetOrigin() const { +wpi::math::Pose3d AprilTagFieldLayout::GetOrigin() const { return m_origin; } -std::optional AprilTagFieldLayout::GetTagPose(int ID) const { +std::optional AprilTagFieldLayout::GetTagPose(int ID) const { const auto& it = m_apriltags.find(ID); if (it == m_apriltags.end()) { return std::nullopt; @@ -91,43 +91,43 @@ std::optional AprilTagFieldLayout::GetTagPose(int ID) const { void AprilTagFieldLayout::Serialize(std::string_view path) { std::error_code error_code; - wpi::raw_fd_ostream output{path, error_code}; + wpi::util::raw_fd_ostream output{path, error_code}; if (error_code) { throw std::runtime_error(fmt::format("Cannot open file: {}", path)); } - wpi::json json = *this; + wpi::util::json json = *this; output << json; output.flush(); } -void frc::to_json(wpi::json& json, const AprilTagFieldLayout& layout) { +void wpi::apriltag::to_json(wpi::util::json& json, const AprilTagFieldLayout& layout) { std::vector tagVector; tagVector.reserve(layout.m_apriltags.size()); for (const auto& pair : layout.m_apriltags) { tagVector.push_back(pair.second); } - json = wpi::json{{"field", + json = wpi::util::json{{"field", {{"length", layout.m_fieldLength.value()}, {"width", layout.m_fieldWidth.value()}}}, {"tags", tagVector}}; } -void frc::from_json(const wpi::json& json, AprilTagFieldLayout& layout) { +void wpi::apriltag::from_json(const wpi::util::json& json, AprilTagFieldLayout& layout) { layout.m_apriltags.clear(); for (const auto& tag : json.at("tags").get>()) { layout.m_apriltags[tag.ID] = tag; } layout.m_fieldLength = - units::meter_t{json.at("field").at("length").get()}; + wpi::units::meter_t{json.at("field").at("length").get()}; layout.m_fieldWidth = - units::meter_t{json.at("field").at("width").get()}; + wpi::units::meter_t{json.at("field").at("width").get()}; } // Use namespace declaration for forward declaration -namespace frc { +namespace wpi::apriltag { // C++ generated from resource files std::string_view GetResource_2022_rapidreact_json(); @@ -136,7 +136,7 @@ std::string_view GetResource_2024_crescendo_json(); std::string_view GetResource_2025_reefscape_welded_json(); std::string_view GetResource_2025_reefscape_andymark_json(); -} // namespace frc +} // namespace wpi::apriltag AprilTagFieldLayout AprilTagFieldLayout::LoadField(AprilTagField field) { std::string_view fieldString; @@ -160,10 +160,10 @@ AprilTagFieldLayout AprilTagFieldLayout::LoadField(AprilTagField field) { throw std::invalid_argument("Invalid Field"); } - wpi::json json = wpi::json::parse(fieldString); + wpi::util::json json = wpi::util::json::parse(fieldString); return json.get(); } -AprilTagFieldLayout frc::LoadAprilTagLayoutField(AprilTagField field) { +AprilTagFieldLayout wpi::apriltag::LoadAprilTagLayoutField(AprilTagField field) { return AprilTagFieldLayout::LoadField(field); } diff --git a/apriltag/src/main/native/cpp/AprilTagPoseEstimate.cpp b/apriltag/src/main/native/cpp/AprilTagPoseEstimate.cpp index a139b7fa91..343642e6ed 100644 --- a/apriltag/src/main/native/cpp/AprilTagPoseEstimate.cpp +++ b/apriltag/src/main/native/cpp/AprilTagPoseEstimate.cpp @@ -6,7 +6,7 @@ #include -using namespace frc; +using namespace wpi::apriltag; double AprilTagPoseEstimate::GetAmbiguity() const { auto min = (std::min)(error1, error2); diff --git a/apriltag/src/main/native/cpp/AprilTagPoseEstimator.cpp b/apriltag/src/main/native/cpp/AprilTagPoseEstimator.cpp index 4c07d5cc5c..56d6915052 100644 --- a/apriltag/src/main/native/cpp/AprilTagPoseEstimator.cpp +++ b/apriltag/src/main/native/cpp/AprilTagPoseEstimator.cpp @@ -19,7 +19,7 @@ #include "apriltag.h" #include "apriltag_pose.h" -using namespace frc; +using namespace wpi::apriltag; static Eigen::Matrix3d OrthogonalizeRotationMatrix( const Eigen::Matrix3d& input) { @@ -42,14 +42,14 @@ static Eigen::Matrix3d OrthogonalizeRotationMatrix( return Q; } -static Transform3d MakePose(const apriltag_pose_t& pose) { +static wpi::math::Transform3d MakePose(const apriltag_pose_t& pose) { if (!pose.R || !pose.t) { return {}; } - return {Translation3d{units::meter_t{pose.t->data[0]}, - units::meter_t{pose.t->data[1]}, - units::meter_t{pose.t->data[2]}}, - Rotation3d{OrthogonalizeRotationMatrix( + return {wpi::math::Translation3d{wpi::units::meter_t{pose.t->data[0]}, + wpi::units::meter_t{pose.t->data[1]}, + wpi::units::meter_t{pose.t->data[2]}}, + wpi::math::Rotation3d{OrthogonalizeRotationMatrix( Eigen::Map>{ pose.R->data})}}; } @@ -80,7 +80,7 @@ static apriltag_detection_t MakeBasicDet( return detection; } -static Transform3d DoEstimateHomography( +static wpi::math::Transform3d DoEstimateHomography( const apriltag_detection_t* detection, const AprilTagPoseEstimator::Config& config) { auto info = MakeDetectionInfo(detection, config); @@ -89,13 +89,13 @@ static Transform3d DoEstimateHomography( return MakePose(pose); } -Transform3d AprilTagPoseEstimator::EstimateHomography( +wpi::math::Transform3d AprilTagPoseEstimator::EstimateHomography( const AprilTagDetection& detection) const { return DoEstimateHomography( reinterpret_cast(&detection), m_config); } -Transform3d AprilTagPoseEstimator::EstimateHomography( +wpi::math::Transform3d AprilTagPoseEstimator::EstimateHomography( std::span homography) const { auto detection = MakeBasicDet(homography, nullptr); auto rv = DoEstimateHomography(&detection, m_config); @@ -130,7 +130,7 @@ AprilTagPoseEstimate AprilTagPoseEstimator::EstimateOrthogonalIteration( return rv; } -static Transform3d DoEstimate(const apriltag_detection_t* detection, +static wpi::math::Transform3d DoEstimate(const apriltag_detection_t* detection, const AprilTagPoseEstimator::Config& config) { auto info = MakeDetectionInfo(detection, config); apriltag_pose_t pose; @@ -138,13 +138,13 @@ static Transform3d DoEstimate(const apriltag_detection_t* detection, return MakePose(pose); } -Transform3d AprilTagPoseEstimator::Estimate( +wpi::math::Transform3d AprilTagPoseEstimator::Estimate( const AprilTagDetection& detection) const { return DoEstimate(reinterpret_cast(&detection), m_config); } -Transform3d AprilTagPoseEstimator::Estimate( +wpi::math::Transform3d AprilTagPoseEstimator::Estimate( std::span homography, std::span corners) const { auto detection = MakeBasicDet(homography, &corners); diff --git a/apriltag/src/main/native/cpp/jni/AprilTagJNI.cpp b/apriltag/src/main/native/cpp/jni/AprilTagJNI.cpp index 77904a9d7a..af8b7f2cf4 100644 --- a/apriltag/src/main/native/cpp/jni/AprilTagJNI.cpp +++ b/apriltag/src/main/native/cpp/jni/AprilTagJNI.cpp @@ -16,8 +16,8 @@ #include "wpi/apriltag/AprilTagDetector.hpp" #include "wpi/apriltag/AprilTagPoseEstimator.hpp" -using namespace frc; -using namespace wpi::java; +using namespace wpi::apriltag; +using namespace wpi::util::java; static JavaVM* jvm = nullptr; @@ -162,7 +162,7 @@ static AprilTagDetector::QuadThresholdParameters FromJavaDetectorQTP( return { FIELD(int, Int, minClusterPixels), FIELD(int, Int, maxNumMaxima), - .criticalAngle = units::radian_t{static_cast( + .criticalAngle = wpi::units::radian_t{static_cast( env->GetDoubleField(jparams, criticalAngleField))}, FIELD(float, Float, maxLineFitMSE), FIELD(int, Int, minWhiteBlackDiff), @@ -256,7 +256,7 @@ static jobject MakeJObject( static_cast(params.deglitch)); } -static jobject MakeJObject(JNIEnv* env, const Translation3d& xlate) { +static jobject MakeJObject(JNIEnv* env, const wpi::math::Translation3d& xlate) { static jmethodID constructor = env->GetMethodID(translation3dCls, "", "(DDD)V"); if (!constructor) { @@ -268,7 +268,7 @@ static jobject MakeJObject(JNIEnv* env, const Translation3d& xlate) { static_cast(xlate.Y()), static_cast(xlate.Z())); } -static jobject MakeJObject(JNIEnv* env, const Quaternion& q) { +static jobject MakeJObject(JNIEnv* env, const wpi::math::Quaternion& q) { static jmethodID constructor = env->GetMethodID(quaternionCls, "", "(DDDD)V"); if (!constructor) { @@ -281,7 +281,7 @@ static jobject MakeJObject(JNIEnv* env, const Quaternion& q) { static_cast(q.Z())); } -static jobject MakeJObject(JNIEnv* env, const Rotation3d& rot) { +static jobject MakeJObject(JNIEnv* env, const wpi::math::Rotation3d& rot) { static jmethodID constructor = env->GetMethodID( rotation3dCls, "", "(Lorg/wpilib/math/geometry/Quaternion;)V"); if (!constructor) { @@ -292,7 +292,7 @@ static jobject MakeJObject(JNIEnv* env, const Rotation3d& rot) { return env->NewObject(rotation3dCls, constructor, q.obj()); } -static jobject MakeJObject(JNIEnv* env, const Transform3d& xform) { +static jobject MakeJObject(JNIEnv* env, const wpi::math::Transform3d& xform) { static jmethodID constructor = env->GetMethodID(transform3dCls, "", "(Lorg/wpilib/math/geometry/Translation3d;" @@ -517,7 +517,7 @@ Java_org_wpilib_vision_apriltag_jni_AprilTagJNI_estimatePoseHomography return nullptr; } - AprilTagPoseEstimator estimator({units::meter_t{tagSize}, fx, fy, cx, cy}); + AprilTagPoseEstimator estimator({wpi::units::meter_t{tagSize}, fx, fy, cx, cy}); return MakeJObject(env, estimator.EstimateHomography(harr)); } @@ -553,7 +553,7 @@ Java_org_wpilib_vision_apriltag_jni_AprilTagJNI_estimatePoseOrthogonalIteration return nullptr; } - AprilTagPoseEstimator estimator({units::meter_t{tagSize}, fx, fy, cx, cy}); + AprilTagPoseEstimator estimator({wpi::units::meter_t{tagSize}, fx, fy, cx, cy}); return MakeJObject(env, estimator.EstimateOrthogonalIteration(harr, carr, nIters)); } @@ -590,7 +590,7 @@ Java_org_wpilib_vision_apriltag_jni_AprilTagJNI_estimatePose return nullptr; } - AprilTagPoseEstimator estimator({units::meter_t{tagSize}, fx, fy, cx, cy}); + AprilTagPoseEstimator estimator({wpi::units::meter_t{tagSize}, fx, fy, cx, cy}); return MakeJObject(env, estimator.Estimate(harr, carr)); } @@ -603,13 +603,13 @@ JNIEXPORT void JNICALL Java_org_wpilib_vision_apriltag_jni_AprilTagJNI_generate16h5AprilTagImage (JNIEnv* env, jclass, jobject frameObj, jlong framePtr, jint id) { - auto* frame = reinterpret_cast(framePtr); + auto* frame = reinterpret_cast(framePtr); if (!frame) { nullPointerEx.Throw(env, "frame is null"); return; } bool newData = AprilTag::Generate16h5AprilTagImage(frame, id); - wpi::SetFrameData(env, rawFrameCls, frameObj, *frame, newData); + wpi::util::SetFrameData(env, rawFrameCls, frameObj, *frame, newData); } /* @@ -621,14 +621,14 @@ JNIEXPORT void JNICALL Java_org_wpilib_vision_apriltag_jni_AprilTagJNI_generate36h11AprilTagImage (JNIEnv* env, jclass, jobject frameObj, jlong framePtr, jint id) { - auto* frame = reinterpret_cast(framePtr); + auto* frame = reinterpret_cast(framePtr); if (!frame) { nullPointerEx.Throw(env, "frame is null"); return; } // function might reallocate bool newData = AprilTag::Generate36h11AprilTagImage(frame, id); - wpi::SetFrameData(env, rawFrameCls, frameObj, *frame, newData); + wpi::util::SetFrameData(env, rawFrameCls, frameObj, *frame, newData); } } // extern "C" diff --git a/apriltag/src/main/native/include/wpi/apriltag/AprilTag.hpp b/apriltag/src/main/native/include/wpi/apriltag/AprilTag.hpp index 85545335b1..5189c05be4 100644 --- a/apriltag/src/main/native/include/wpi/apriltag/AprilTag.hpp +++ b/apriltag/src/main/native/include/wpi/apriltag/AprilTag.hpp @@ -9,7 +9,7 @@ #include "wpi/util/SymbolExports.hpp" #include "wpi/util/json_fwd.hpp" -namespace frc { +namespace wpi::apriltag { /** * Represents an AprilTag's metadata. @@ -19,18 +19,18 @@ struct WPILIB_DLLEXPORT AprilTag { int ID; /// The tag's pose. - Pose3d pose; + wpi::math::Pose3d pose; bool operator==(const AprilTag&) const = default; - static bool Generate36h11AprilTagImage(wpi::RawFrame* frame, int id); - static bool Generate16h5AprilTagImage(wpi::RawFrame* frame, int id); + static bool Generate36h11AprilTagImage(wpi::util::RawFrame* frame, int id); + static bool Generate16h5AprilTagImage(wpi::util::RawFrame* frame, int id); }; WPILIB_DLLEXPORT -void to_json(wpi::json& json, const AprilTag& apriltag); +void to_json(wpi::util::json& json, const AprilTag& apriltag); WPILIB_DLLEXPORT -void from_json(const wpi::json& json, AprilTag& apriltag); +void from_json(const wpi::util::json& json, AprilTag& apriltag); -} // namespace frc +} // namespace wpi::apriltag diff --git a/apriltag/src/main/native/include/wpi/apriltag/AprilTagDetection.hpp b/apriltag/src/main/native/include/wpi/apriltag/AprilTagDetection.hpp index 4500b7b072..8b88868639 100644 --- a/apriltag/src/main/native/include/wpi/apriltag/AprilTagDetection.hpp +++ b/apriltag/src/main/native/include/wpi/apriltag/AprilTagDetection.hpp @@ -13,7 +13,7 @@ #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::apriltag { /** * A detection of an AprilTag tag. @@ -158,4 +158,4 @@ class WPILIB_DLLEXPORT AprilTagDetection final { double p[4][2]; }; -} // namespace frc +} // namespace wpi::apriltag diff --git a/apriltag/src/main/native/include/wpi/apriltag/AprilTagDetector.hpp b/apriltag/src/main/native/include/wpi/apriltag/AprilTagDetector.hpp index 7449536ba1..16410c77ab 100644 --- a/apriltag/src/main/native/include/wpi/apriltag/AprilTagDetector.hpp +++ b/apriltag/src/main/native/include/wpi/apriltag/AprilTagDetector.hpp @@ -16,7 +16,7 @@ #include "wpi/util/StringMap.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::apriltag { /** * An AprilTag detector engine. This is expensive to set up and tear down, so @@ -98,7 +98,7 @@ class WPILIB_DLLEXPORT AprilTagDetector { * angles that are close to straight or close to 180 degrees. Zero means * that no quads are rejected. Default is 45 degrees. */ - units::radian_t criticalAngle = 45_deg; + wpi::units::radian_t criticalAngle = 45_deg; /** * When fitting lines to the contours, the maximum mean squared error @@ -254,8 +254,8 @@ class WPILIB_DLLEXPORT AprilTagDetector { void DestroyFamily(std::string_view name, void* data); void* m_impl; - wpi::StringMap m_families; - units::radian_t m_qtpCriticalAngle = 10_deg; + wpi::util::StringMap m_families; + wpi::units::radian_t m_qtpCriticalAngle = 10_deg; }; -} // namespace frc +} // namespace wpi::apriltag diff --git a/apriltag/src/main/native/include/wpi/apriltag/AprilTagDetector_cv.hpp b/apriltag/src/main/native/include/wpi/apriltag/AprilTagDetector_cv.hpp index 887d1d0979..696f27eba6 100644 --- a/apriltag/src/main/native/include/wpi/apriltag/AprilTagDetector_cv.hpp +++ b/apriltag/src/main/native/include/wpi/apriltag/AprilTagDetector_cv.hpp @@ -8,11 +8,11 @@ #include "wpi/apriltag/AprilTagDetector.hpp" -namespace frc { +namespace wpi::apriltag { inline AprilTagDetector::Results AprilTagDetect(AprilTagDetector& detector, cv::Mat& image) { return detector.Detect(image.cols, image.rows, image.data); } -} // namespace frc +} // namespace wpi::apriltag diff --git a/apriltag/src/main/native/include/wpi/apriltag/AprilTagFieldLayout.hpp b/apriltag/src/main/native/include/wpi/apriltag/AprilTagFieldLayout.hpp index ed81399653..4626ec86e5 100644 --- a/apriltag/src/main/native/include/wpi/apriltag/AprilTagFieldLayout.hpp +++ b/apriltag/src/main/native/include/wpi/apriltag/AprilTagFieldLayout.hpp @@ -16,14 +16,14 @@ #include "wpi/util/SymbolExports.hpp" #include "wpi/util/json_fwd.hpp" -namespace frc { +namespace wpi::apriltag { /** * Class for representing a layout of AprilTags on a field and reading them from * a JSON format. * * The JSON format contains two top-level objects, "tags" and "field". * The "tags" object is a list of all AprilTags contained within a layout. Each - * AprilTag serializes to a JSON object containing an ID and a Pose3d. The + * AprilTag serializes to a JSON object containing an ID and a wpi::math::Pose3d. The * "field" object is a descriptor of the size of the field in meters with * "width" and "length" values. This is to account for arbitrary field sizes * when transforming the poses. @@ -73,19 +73,19 @@ class WPILIB_DLLEXPORT AprilTagFieldLayout { * @param fieldWidth Width of field the layout is representing. */ AprilTagFieldLayout(std::vector apriltags, - units::meter_t fieldLength, units::meter_t fieldWidth); + wpi::units::meter_t fieldLength, wpi::units::meter_t fieldWidth); /** * Returns the length of the field the layout is representing. * @return length */ - units::meter_t GetFieldLength() const; + wpi::units::meter_t GetFieldLength() const; /** * Returns the length of the field the layout is representing. * @return width */ - units::meter_t GetFieldWidth() const; + wpi::units::meter_t GetFieldWidth() const; /** * Returns a vector of all the april tags used in this layout. @@ -112,13 +112,13 @@ class WPILIB_DLLEXPORT AprilTagFieldLayout { * * @param origin The new origin for tag transformations */ - void SetOrigin(const Pose3d& origin); + void SetOrigin(const wpi::math::Pose3d& origin); /** * Returns the origin used for tag pose transformation. * @return the origin */ - Pose3d GetOrigin() const; + wpi::math::Pose3d GetOrigin() const; /** * Gets an AprilTag pose by its ID. @@ -127,7 +127,7 @@ class WPILIB_DLLEXPORT AprilTagFieldLayout { * @return The pose corresponding to the ID that was passed in or an empty * optional if a tag with that ID is not found. */ - std::optional GetTagPose(int ID) const; + std::optional GetTagPose(int ID) const; /** * Serializes an AprilTagFieldLayout to a JSON file. @@ -143,22 +143,22 @@ class WPILIB_DLLEXPORT AprilTagFieldLayout { private: std::unordered_map m_apriltags; - units::meter_t m_fieldLength; - units::meter_t m_fieldWidth; - Pose3d m_origin; + wpi::units::meter_t m_fieldLength; + wpi::units::meter_t m_fieldWidth; + wpi::math::Pose3d m_origin; - friend WPILIB_DLLEXPORT void to_json(wpi::json& json, + friend WPILIB_DLLEXPORT void to_json(wpi::util::json& json, const AprilTagFieldLayout& layout); - friend WPILIB_DLLEXPORT void from_json(const wpi::json& json, + friend WPILIB_DLLEXPORT void from_json(const wpi::util::json& json, AprilTagFieldLayout& layout); }; WPILIB_DLLEXPORT -void to_json(wpi::json& json, const AprilTagFieldLayout& layout); +void to_json(wpi::util::json& json, const AprilTagFieldLayout& layout); WPILIB_DLLEXPORT -void from_json(const wpi::json& json, AprilTagFieldLayout& layout); +void from_json(const wpi::util::json& json, AprilTagFieldLayout& layout); /** * Loads an AprilTagFieldLayout from a predefined field @@ -171,4 +171,4 @@ void from_json(const wpi::json& json, AprilTagFieldLayout& layout); WPILIB_DLLEXPORT AprilTagFieldLayout LoadAprilTagLayoutField(AprilTagField field); -} // namespace frc +} // namespace wpi::apriltag diff --git a/apriltag/src/main/native/include/wpi/apriltag/AprilTagFields.hpp b/apriltag/src/main/native/include/wpi/apriltag/AprilTagFields.hpp index 039250760a..4d73d41de0 100644 --- a/apriltag/src/main/native/include/wpi/apriltag/AprilTagFields.hpp +++ b/apriltag/src/main/native/include/wpi/apriltag/AprilTagFields.hpp @@ -8,7 +8,7 @@ #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::apriltag { /** * Loadable AprilTag field layouts. @@ -32,4 +32,4 @@ enum class AprilTagField { kNumFields, }; -} // namespace frc +} // namespace wpi::apriltag diff --git a/apriltag/src/main/native/include/wpi/apriltag/AprilTagPoseEstimate.hpp b/apriltag/src/main/native/include/wpi/apriltag/AprilTagPoseEstimate.hpp index 8e8fb587b8..0d4037071e 100644 --- a/apriltag/src/main/native/include/wpi/apriltag/AprilTagPoseEstimate.hpp +++ b/apriltag/src/main/native/include/wpi/apriltag/AprilTagPoseEstimate.hpp @@ -7,15 +7,15 @@ #include "wpi/math/geometry/Transform3d.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::apriltag { /** A pair of AprilTag pose estimates. */ struct WPILIB_DLLEXPORT AprilTagPoseEstimate { /** Pose 1. */ - Transform3d pose1; + wpi::math::Transform3d pose1; /** Pose 2. */ - Transform3d pose2; + wpi::math::Transform3d pose2; /** Object-space error of pose 1. */ double error1; @@ -32,4 +32,4 @@ struct WPILIB_DLLEXPORT AprilTagPoseEstimate { double GetAmbiguity() const; }; -} // namespace frc +} // namespace wpi::apriltag diff --git a/apriltag/src/main/native/include/wpi/apriltag/AprilTagPoseEstimator.hpp b/apriltag/src/main/native/include/wpi/apriltag/AprilTagPoseEstimator.hpp index 830658cd66..61317e56d6 100644 --- a/apriltag/src/main/native/include/wpi/apriltag/AprilTagPoseEstimator.hpp +++ b/apriltag/src/main/native/include/wpi/apriltag/AprilTagPoseEstimator.hpp @@ -11,7 +11,7 @@ #include "wpi/units/length.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::apriltag { class AprilTagDetection; @@ -23,7 +23,7 @@ class WPILIB_DLLEXPORT AprilTagPoseEstimator { bool operator==(const Config&) const = default; /** The tag size. */ - units::meter_t tagSize; + wpi::units::meter_t tagSize; /** Camera horizontal focal length, in pixels. */ double fx; @@ -65,7 +65,7 @@ class WPILIB_DLLEXPORT AprilTagPoseEstimator { * @param detection Tag detection * @return Pose estimate */ - Transform3d EstimateHomography(const AprilTagDetection& detection) const; + wpi::math::Transform3d EstimateHomography(const AprilTagDetection& detection) const; /** * Estimates the pose of the tag using the homography method described in [1]. @@ -73,7 +73,7 @@ class WPILIB_DLLEXPORT AprilTagPoseEstimator { * @param homography Homography 3x3 matrix data * @return Pose estimate */ - Transform3d EstimateHomography(std::span homography) const; + wpi::math::Transform3d EstimateHomography(std::span homography) const; /** * Estimates the pose of the tag. This returns one or two possible poses for @@ -123,7 +123,7 @@ class WPILIB_DLLEXPORT AprilTagPoseEstimator { * @param detection Tag detection * @return Pose estimate */ - Transform3d Estimate(const AprilTagDetection& detection) const; + wpi::math::Transform3d Estimate(const AprilTagDetection& detection) const; /** * Estimates tag pose. This method is an easier to use interface to @@ -134,11 +134,11 @@ class WPILIB_DLLEXPORT AprilTagPoseEstimator { * @param corners Corner point array (X and Y for each corner in order) * @return Pose estimate */ - Transform3d Estimate(std::span homography, + wpi::math::Transform3d Estimate(std::span homography, std::span corners) const; private: Config m_config; }; -} // namespace frc +} // namespace wpi::apriltag diff --git a/apriltag/src/main/python/semiwrap/AprilTag.yml b/apriltag/src/main/python/semiwrap/AprilTag.yml index 42ae4168c8..5e8b2ebd8b 100644 --- a/apriltag/src/main/python/semiwrap/AprilTag.yml +++ b/apriltag/src/main/python/semiwrap/AprilTag.yml @@ -4,7 +4,7 @@ functions: from_json: ignore: true classes: - frc::AprilTag: + wpi::apriltag::AprilTag: attributes: ID: pose: diff --git a/apriltag/src/main/python/semiwrap/AprilTagDetection.yml b/apriltag/src/main/python/semiwrap/AprilTagDetection.yml index 23a35df5d2..78332dad94 100644 --- a/apriltag/src/main/python/semiwrap/AprilTagDetection.yml +++ b/apriltag/src/main/python/semiwrap/AprilTagDetection.yml @@ -2,7 +2,7 @@ extra_includes: - pybind11/eigen.h classes: - frc::AprilTagDetection: + wpi::apriltag::AprilTagDetection: methods: GetFamily: GetId: @@ -18,7 +18,7 @@ classes: return py::str("") .format(self.GetFamily(), self.GetId(), self.GetHamming(), self.GetDecisionMargin(), self.GetCenter()); }) - frc::AprilTagDetection::Point: + wpi::apriltag::AprilTagDetection::Point: attributes: x: y: diff --git a/apriltag/src/main/python/semiwrap/AprilTagDetector.yml b/apriltag/src/main/python/semiwrap/AprilTagDetector.yml index 3385e5172e..df9e1d970d 100644 --- a/apriltag/src/main/python/semiwrap/AprilTagDetector.yml +++ b/apriltag/src/main/python/semiwrap/AprilTagDetector.yml @@ -2,7 +2,7 @@ extra_includes: - pybind11_typing.h classes: - frc::AprilTagDetector: + wpi::apriltag::AprilTagDetector: methods: AprilTagDetector: SetConfig: @@ -59,7 +59,7 @@ classes: :return: list of results )doc" ) - frc::AprilTagDetector::Config: + wpi::apriltag::AprilTagDetector::Config: attributes: numThreads: quadDecimate: @@ -69,7 +69,7 @@ classes: debug: methods: operator==: - frc::AprilTagDetector::QuadThresholdParameters: + wpi::apriltag::AprilTagDetector::QuadThresholdParameters: attributes: minClusterPixels: maxNumMaxima: @@ -79,7 +79,7 @@ classes: deglitch: methods: operator==: - frc::AprilTagDetector::Results: + wpi::apriltag::AprilTagDetector::Results: rename: _Results ignored_bases: - std::span diff --git a/apriltag/src/main/python/semiwrap/AprilTagFieldLayout.yml b/apriltag/src/main/python/semiwrap/AprilTagFieldLayout.yml index eba162f44c..ac032718d9 100644 --- a/apriltag/src/main/python/semiwrap/AprilTagFieldLayout.yml +++ b/apriltag/src/main/python/semiwrap/AprilTagFieldLayout.yml @@ -6,7 +6,7 @@ functions: LoadAprilTagLayoutField: ignore: true classes: - frc::AprilTagFieldLayout: + wpi::apriltag::AprilTagFieldLayout: enums: OriginPosition: methods: @@ -14,7 +14,7 @@ classes: overloads: '': std::string_view: - std::vector, units::meter_t, units::meter_t: + std::vector, wpi::units::meter_t, wpi::units::meter_t: LoadField: GetFieldLength: GetFieldWidth: @@ -22,7 +22,7 @@ classes: SetOrigin: overloads: OriginPosition: - const Pose3d&: + const wpi::math::Pose3d&: GetOrigin: GetTagPose: Serialize: diff --git a/apriltag/src/main/python/semiwrap/AprilTagPoseEstimate.yml b/apriltag/src/main/python/semiwrap/AprilTagPoseEstimate.yml index 37faf79df4..2e31bb8f46 100644 --- a/apriltag/src/main/python/semiwrap/AprilTagPoseEstimate.yml +++ b/apriltag/src/main/python/semiwrap/AprilTagPoseEstimate.yml @@ -1,5 +1,5 @@ classes: - frc::AprilTagPoseEstimate: + wpi::apriltag::AprilTagPoseEstimate: attributes: pose1: pose2: diff --git a/apriltag/src/main/python/semiwrap/AprilTagPoseEstimator.yml b/apriltag/src/main/python/semiwrap/AprilTagPoseEstimator.yml index a6ce2f9e69..d2cc7e8ea3 100644 --- a/apriltag/src/main/python/semiwrap/AprilTagPoseEstimator.yml +++ b/apriltag/src/main/python/semiwrap/AprilTagPoseEstimator.yml @@ -2,7 +2,7 @@ extra_includes: - wpi/apriltag/AprilTagDetection.hpp classes: - frc::AprilTagPoseEstimator: + wpi::apriltag::AprilTagPoseEstimator: methods: AprilTagPoseEstimator: SetConfig: @@ -19,7 +19,7 @@ classes: overloads: const AprilTagDetection& [const]: std::span, std::span [const]: - frc::AprilTagPoseEstimator::Config: + wpi::apriltag::AprilTagPoseEstimator::Config: force_no_default_constructor: true attributes: tagSize: @@ -30,7 +30,7 @@ classes: methods: operator==: inline_code: | - .def(py::init([](units::meter_t tagSize, double fx, double fy, double cx, double cy) { + .def(py::init([](wpi::units::meter_t tagSize, double fx, double fy, double cx, double cy) { AprilTagPoseEstimator::Config cfg{tagSize, fx, fy, cx, cy}; return std::make_unique(std::move(cfg)); }), py::arg("tagSize"), py::arg("fx"), py::arg("fy"), py::arg("cx"), py::arg("cy")) diff --git a/apriltag/src/test/native/cpp/AprilTagDetectorTest.cpp b/apriltag/src/test/native/cpp/AprilTagDetectorTest.cpp index 5a7dc5f4ba..365e72dc57 100644 --- a/apriltag/src/test/native/cpp/AprilTagDetectorTest.cpp +++ b/apriltag/src/test/native/cpp/AprilTagDetectorTest.cpp @@ -6,7 +6,7 @@ #include "wpi/apriltag/AprilTagDetector.hpp" -using namespace frc; +using namespace wpi::apriltag; TEST(AprilTagDetectorTest, ConfigDefaults) { AprilTagDetector detector; diff --git a/apriltag/src/test/native/cpp/AprilTagJsonTest.cpp b/apriltag/src/test/native/cpp/AprilTagJsonTest.cpp index 4c6d399de4..d980d09864 100644 --- a/apriltag/src/test/native/cpp/AprilTagJsonTest.cpp +++ b/apriltag/src/test/native/cpp/AprilTagJsonTest.cpp @@ -11,17 +11,17 @@ #include "wpi/math/geometry/Pose3d.hpp" #include "wpi/util/json.hpp" -using namespace frc; +using namespace wpi::apriltag; TEST(AprilTagJsonTest, DeserializeMatches) { auto layout = AprilTagFieldLayout{ std::vector{ - AprilTag{1, Pose3d{}}, - AprilTag{3, Pose3d{0_m, 1_m, 0_m, Rotation3d{0_deg, 0_deg, 0_deg}}}}, + AprilTag{1, wpi::math::Pose3d{}}, + AprilTag{3, wpi::math::Pose3d{0_m, 1_m, 0_m, wpi::math::Rotation3d{0_deg, 0_deg, 0_deg}}}}, 54_ft, 27_ft}; AprilTagFieldLayout deserialized; - wpi::json json = layout; + wpi::util::json json = layout; EXPECT_NO_THROW(deserialized = json.get()); EXPECT_EQ(layout, deserialized); } diff --git a/apriltag/src/test/native/cpp/AprilTagPoseSetOriginTest.cpp b/apriltag/src/test/native/cpp/AprilTagPoseSetOriginTest.cpp index 0f293724d4..4adb7fc911 100644 --- a/apriltag/src/test/native/cpp/AprilTagPoseSetOriginTest.cpp +++ b/apriltag/src/test/native/cpp/AprilTagPoseSetOriginTest.cpp @@ -11,23 +11,23 @@ #include "wpi/math/geometry/Pose3d.hpp" #include "wpi/util/json.hpp" -using namespace frc; +using namespace wpi::apriltag; TEST(AprilTagPoseSetOriginTest, TransformationMatches) { auto layout = AprilTagFieldLayout{ std::vector{ AprilTag{1, - Pose3d{0_ft, 0_ft, 0_ft, Rotation3d{0_deg, 0_deg, 0_deg}}}, + wpi::math::Pose3d{0_ft, 0_ft, 0_ft, wpi::math::Rotation3d{0_deg, 0_deg, 0_deg}}}, AprilTag{ - 2, Pose3d{4_ft, 4_ft, 4_ft, Rotation3d{0_deg, 0_deg, 180_deg}}}}, + 2, wpi::math::Pose3d{4_ft, 4_ft, 4_ft, wpi::math::Rotation3d{0_deg, 0_deg, 180_deg}}}}, 54_ft, 27_ft}; layout.SetOrigin( AprilTagFieldLayout::OriginPosition::kRedAllianceWallRightSide); auto mirrorPose = - Pose3d{54_ft, 27_ft, 0_ft, Rotation3d{0_deg, 0_deg, 180_deg}}; + wpi::math::Pose3d{54_ft, 27_ft, 0_ft, wpi::math::Rotation3d{0_deg, 0_deg, 180_deg}}; EXPECT_EQ(mirrorPose, *layout.GetTagPose(1)); - mirrorPose = Pose3d{50_ft, 23_ft, 4_ft, Rotation3d{0_deg, 0_deg, 0_deg}}; + mirrorPose = wpi::math::Pose3d{50_ft, 23_ft, 4_ft, wpi::math::Rotation3d{0_deg, 0_deg, 0_deg}}; EXPECT_EQ(mirrorPose, *layout.GetTagPose(2)); } diff --git a/apriltag/src/test/native/cpp/LoadConfigTest.cpp b/apriltag/src/test/native/cpp/LoadConfigTest.cpp index 3e414ae4ed..a2b54ea818 100644 --- a/apriltag/src/test/native/cpp/LoadConfigTest.cpp +++ b/apriltag/src/test/native/cpp/LoadConfigTest.cpp @@ -9,7 +9,7 @@ #include "wpi/apriltag/AprilTagFieldLayout.hpp" #include "wpi/apriltag/AprilTagFields.hpp" -namespace frc { +namespace wpi::apriltag { std::vector GetAllFields() { std::vector output; @@ -27,21 +27,21 @@ TEST(AprilTagFieldsTest, TestLoad2022RapidReact) { // Blue Hangar Truss - Hub auto expectedPose = - Pose3d{127.272_in, 216.01_in, 67.932_in, Rotation3d{0_deg, 0_deg, 0_deg}}; + wpi::math::Pose3d{127.272_in, 216.01_in, 67.932_in, wpi::math::Rotation3d{0_deg, 0_deg, 0_deg}}; auto maybePose = layout.GetTagPose(1); EXPECT_TRUE(maybePose); EXPECT_EQ(expectedPose, *maybePose); // Blue Terminal Near Station - expectedPose = Pose3d{4.768_in, 67.631_in, 35.063_in, - Rotation3d{0_deg, 0_deg, 46.25_deg}}; + expectedPose = wpi::math::Pose3d{4.768_in, 67.631_in, 35.063_in, + wpi::math::Rotation3d{0_deg, 0_deg, 46.25_deg}}; maybePose = layout.GetTagPose(5); EXPECT_TRUE(maybePose); EXPECT_EQ(expectedPose, *maybePose); // Upper Hub Blue-Near - expectedPose = Pose3d{332.321_in, 183.676_in, 95.186_in, - Rotation3d{0_deg, 26.75_deg, 69_deg}}; + expectedPose = wpi::math::Pose3d{332.321_in, 183.676_in, 95.186_in, + wpi::math::Rotation3d{0_deg, 26.75_deg, 69_deg}}; maybePose = layout.GetTagPose(53); EXPECT_TRUE(maybePose); EXPECT_EQ(expectedPose, *maybePose); @@ -62,4 +62,4 @@ TEST_P(AllFieldsFixtureTest, CheckEntireEnum) { INSTANTIATE_TEST_SUITE_P(ValuesEnumTestInstTests, AllFieldsFixtureTest, ::testing::ValuesIn(GetAllFields())); -} // namespace frc +} // namespace wpi::apriltag diff --git a/benchmark/src/main/native/cpp/Main.cpp b/benchmark/src/main/native/cpp/Main.cpp index 6e29c56bac..406245c12e 100644 --- a/benchmark/src/main/native/cpp/Main.cpp +++ b/benchmark/src/main/native/cpp/Main.cpp @@ -10,17 +10,17 @@ #include "wpi/units/length.hpp" #include "wpi/util/array.hpp" -static constexpr wpi::array poses{ - frc::Pose2d{-1_m, 1_m, -90_deg}, frc::Pose2d{-1_m, 2_m, 90_deg}, - frc::Pose2d{0_m, 0_m, 0_deg}, frc::Pose2d{0_m, 3_m, -90_deg}, - frc::Pose2d{1_m, 1_m, 90_deg}, frc::Pose2d{1_m, 2_m, 90_deg}, +static constexpr wpi::util::array poses{ + wpi::math::Pose2d{-1_m, 1_m, -90_deg}, wpi::math::Pose2d{-1_m, 2_m, 90_deg}, + wpi::math::Pose2d{0_m, 0_m, 0_deg}, wpi::math::Pose2d{0_m, 3_m, -90_deg}, + wpi::math::Pose2d{1_m, 1_m, 90_deg}, wpi::math::Pose2d{1_m, 2_m, 90_deg}, }; static constexpr int iterations = 100; void BM_Transform(benchmark::State& state) { - frc::TravelingSalesman traveler{[](auto pose1, auto pose2) { + wpi::math::TravelingSalesman traveler{[](auto pose1, auto pose2) { auto transform = pose2 - pose1; - return units::math::hypot(transform.X(), transform.Y()).value(); + return wpi::units::math::hypot(transform.X(), transform.Y()).value(); }}; // NOLINTNEXTLINE(clang-analyzer-deadcode.DeadStores) for (auto _ : state) { @@ -30,9 +30,9 @@ void BM_Transform(benchmark::State& state) { BENCHMARK(BM_Transform); void BM_Twist(benchmark::State& state) { - frc::TravelingSalesman traveler{[](auto pose1, auto pose2) { + wpi::math::TravelingSalesman traveler{[](auto pose1, auto pose2) { auto twist = (pose2 - pose1).Log(); - return units::math::hypot(twist.dx, twist.dy).value(); + return wpi::units::math::hypot(twist.dx, twist.dy).value(); }}; // NOLINTNEXTLINE(clang-analyzer-deadcode.DeadStores) for (auto _ : state) { diff --git a/cameraserver/multiCameraServer/src/main/native/cpp/main.cpp b/cameraserver/multiCameraServer/src/main/native/cpp/main.cpp index e1f43b8ede..0682108ce7 100644 --- a/cameraserver/multiCameraServer/src/main/native/cpp/main.cpp +++ b/cameraserver/multiCameraServer/src/main/native/cpp/main.cpp @@ -59,19 +59,19 @@ bool server = false; struct CameraConfig { std::string name; std::string path; - wpi::json config; + wpi::util::json config; }; std::vector cameras; -bool ReadCameraConfig(const wpi::json& config) { +bool ReadCameraConfig(const wpi::util::json& config) { CameraConfig c; // name try { c.name = config.at("name").get(); - } catch (const wpi::json::exception& e) { - wpi::print(stderr, "config error in '{}': could not read camera name: {}\n", + } catch (const wpi::util::json::exception& e) { + wpi::util::print(stderr, "config error in '{}': could not read camera name: {}\n", configFile, e.what()); return false; } @@ -79,8 +79,8 @@ bool ReadCameraConfig(const wpi::json& config) { // path try { c.path = config.at("path").get(); - } catch (const wpi::json::exception& e) { - wpi::print(stderr, + } catch (const wpi::util::json::exception& e) { + wpi::util::print(stderr, "config error in '{}': camera '{}': could not read path: {}\n", configFile, c.name, e.what()); return false; @@ -94,26 +94,26 @@ bool ReadCameraConfig(const wpi::json& config) { bool ReadConfig() { // open config file - auto fileBuffer = wpi::MemoryBuffer::GetFile(configFile); + auto fileBuffer = wpi::util::MemoryBuffer::GetFile(configFile); if (!fileBuffer) { - wpi::print(stderr, "could not open '{}': {}\n", configFile, + wpi::util::print(stderr, "could not open '{}': {}\n", configFile, fileBuffer.error().message()); return false; } // parse file - wpi::json j; + wpi::util::json j; try { - j = wpi::json::parse(fileBuffer.value()->GetCharBuffer()); - } catch (const wpi::json::parse_error& e) { - wpi::print(stderr, "config error in '{}': byte {}: {}\n", configFile, + j = wpi::util::json::parse(fileBuffer.value()->GetCharBuffer()); + } catch (const wpi::util::json::parse_error& e) { + wpi::util::print(stderr, "config error in '{}': byte {}: {}\n", configFile, e.byte, e.what()); return false; } // top level must be an object if (!j.is_object()) { - wpi::print(stderr, "config error in '{}': must be JSON object\n", + wpi::util::print(stderr, "config error in '{}': must be JSON object\n", configFile); return false; } @@ -121,8 +121,8 @@ bool ReadConfig() { // team number try { team = j.at("team").get(); - } catch (const wpi::json::exception& e) { - wpi::print(stderr, "config error in '{}': could not read team number: {}\n", + } catch (const wpi::util::json::exception& e) { + wpi::util::print(stderr, "config error in '{}': could not read team number: {}\n", configFile, e.what()); return false; } @@ -131,18 +131,18 @@ bool ReadConfig() { if (j.count("ntmode") != 0) { try { auto str = j.at("ntmode").get(); - if (wpi::equals_lower(str, "client")) { + if (wpi::util::equals_lower(str, "client")) { server = false; - } else if (wpi::equals_lower(str, "server")) { + } else if (wpi::util::equals_lower(str, "server")) { server = true; } else { - wpi::print( + wpi::util::print( stderr, "config error in '{}': could not understand ntmode value '{}'\n", configFile, str); } - } catch (const wpi::json::exception& e) { - wpi::print(stderr, "config error in '{}': could not read ntmode: {}\n", + } catch (const wpi::util::json::exception& e) { + wpi::util::print(stderr, "config error in '{}': could not read ntmode: {}\n", configFile, e.what()); } } @@ -154,8 +154,8 @@ bool ReadConfig() { return false; } } - } catch (const wpi::json::exception& e) { - wpi::print(stderr, "config error in '{}': could not read cameras: {}\n", + } catch (const wpi::util::json::exception& e) { + wpi::util::print(stderr, "config error in '{}': could not read cameras: {}\n", configFile, e.what()); return false; } @@ -164,9 +164,9 @@ bool ReadConfig() { } void StartCamera(const CameraConfig& config) { - wpi::print("Starting camera '{}' on {}\n", config.name, config.path); + wpi::util::print("Starting camera '{}' on {}\n", config.name, config.path); auto camera = - frc::CameraServer::StartAutomaticCapture(config.name, config.path); + wpi::CameraServer::StartAutomaticCapture(config.name, config.path); camera.SetConfigJson(config.config); } @@ -183,12 +183,12 @@ int main(int argc, char* argv[]) { } // start NetworkTables - auto ntinst = nt::NetworkTableInstance::GetDefault(); + auto ntinst = wpi::nt::NetworkTableInstance::GetDefault(); if (server) { std::puts("Setting up NetworkTables server"); ntinst.StartServer(); } else { - wpi::print("Setting up NetworkTables client for team {}\n", team); + wpi::util::print("Setting up NetworkTables client for team {}\n", team); ntinst.StartClient("multicameraserver"); ntinst.SetServerTeam(team); } diff --git a/cameraserver/src/main/native/cpp/cameraserver/CameraServer.cpp b/cameraserver/src/main/native/cpp/cameraserver/CameraServer.cpp index 48272ffe3d..161d2d07b5 100644 --- a/cameraserver/src/main/native/cpp/cameraserver/CameraServer.cpp +++ b/cameraserver/src/main/native/cpp/cameraserver/CameraServer.cpp @@ -26,7 +26,7 @@ #include "wpi/util/StringMap.hpp" #include "wpi/util/mutex.hpp" -using namespace frc; +using namespace wpi; static constexpr char const* kPublishName = "/CameraPublisher"; @@ -61,7 +61,7 @@ struct SourcePublisher { nt::StringArrayPublisher streamsPublisher; nt::StringEntry modeEntry; nt::StringArrayPublisher modesPublisher; - wpi::DenseMap properties; + wpi::util::DenseMap properties; }; struct Instance { @@ -71,13 +71,13 @@ struct Instance { std::vector GetSourceStreamValues(CS_Source source); void UpdateStreamValues(); - wpi::mutex m_mutex; + wpi::util::mutex m_mutex; std::atomic m_defaultUsbDevice{0}; std::string m_primarySourceName; - wpi::StringMap m_sources; - wpi::StringMap m_sinks; - wpi::DenseMap m_fixedSources; - wpi::DenseMap m_publishers; + wpi::util::StringMap m_sources; + wpi::util::StringMap m_sinks; + wpi::util::DenseMap m_fixedSources; + wpi::util::DenseMap m_publishers; std::shared_ptr m_publishTable{ nt::NetworkTableInstance::GetDefault().GetTable(kPublishName)}; cs::VideoListener m_videoListener; @@ -94,7 +94,7 @@ static Instance& GetInstance() { } static std::string_view MakeSourceValue(CS_Source source, - wpi::SmallVectorImpl& buf) { + wpi::util::SmallVectorImpl& buf) { CS_Status status = 0; buf.clear(); switch (cs::GetSourceKind(source, &status)) { @@ -282,7 +282,7 @@ PropertyPublisher::PropertyPublisher(nt::NetworkTable& table, const cs::VideoEvent& event) { std::string name; std::string infoName; - if (wpi::starts_with(event.name, "raw_")) { + if (wpi::util::starts_with(event.name, "raw_")) { name = fmt::format("RawProperty/{}", event.name); infoName = fmt::format("RawPropertyInfo/{}", event.name); } else { @@ -361,9 +361,9 @@ SourcePublisher::SourcePublisher(Instance& inst, modeEntry{table->GetStringTopic("mode").GetEntry("")}, modesPublisher{table->GetStringArrayTopic("modes").Publish()} { CS_Status status = 0; - wpi::SmallString<64> buf; + wpi::util::SmallString<64> buf; sourcePublisher.Set(MakeSourceValue(source, buf)); - wpi::SmallString<64> descBuf; + wpi::util::SmallString<64> descBuf; descriptionPublisher.Set(cs::GetSourceDescription(source, descBuf, &status)); connectedPublisher.Set(cs::IsSourceConnected(source, &status)); streamsPublisher.Set(inst.GetSourceStreamValues(source)); @@ -404,7 +404,7 @@ Instance::Instance() { case cs::VideoEvent::kSourceConnected: if (auto publisher = GetPublisher(event.sourceHandle)) { // update the description too (as it may have changed) - wpi::SmallString<64> descBuf; + wpi::util::SmallString<64> descBuf; publisher->descriptionPublisher.Set(cs::GetSourceDescription( event.sourceHandle, descBuf, &status)); publisher->connectedPublisher.Set(true); @@ -543,7 +543,7 @@ cs::CvSink CameraServer::GetVideo() { cs::CvSink CameraServer::GetVideo(const cs::VideoSource& camera) { auto& inst = ::GetInstance(); - wpi::SmallString<64> name{"opencv_"}; + wpi::util::SmallString<64> name{"opencv_"}; name += camera.GetName(); { @@ -570,7 +570,7 @@ cs::CvSink CameraServer::GetVideo(const cs::VideoSource& camera) { cs::CvSink CameraServer::GetVideo(const cs::VideoSource& camera, cs::VideoMode::PixelFormat pixelFormat) { auto& inst = ::GetInstance(); - wpi::SmallString<64> name{"opencv_"}; + wpi::util::SmallString<64> name{"opencv_"}; name += camera.GetName(); { diff --git a/cameraserver/src/main/native/cpp/cameraserver/CameraServerShared.cpp b/cameraserver/src/main/native/cpp/cameraserver/CameraServerShared.cpp index 36722f1ee1..19d1b0fc76 100644 --- a/cameraserver/src/main/native/cpp/cameraserver/CameraServerShared.cpp +++ b/cameraserver/src/main/native/cpp/cameraserver/CameraServerShared.cpp @@ -10,7 +10,7 @@ #include "wpi/util/mutex.hpp" namespace { -class DefaultCameraServerShared : public frc::CameraServerShared { +class DefaultCameraServerShared : public wpi::CameraServerShared { public: void ReportUsage(std::string_view resource, std::string_view data) override {} void SetCameraServerErrorV(fmt::string_view format, @@ -25,10 +25,10 @@ class DefaultCameraServerShared : public frc::CameraServerShared { }; } // namespace -static std::unique_ptr cameraServerShared = nullptr; -static wpi::mutex setLock; +static std::unique_ptr cameraServerShared = nullptr; +static wpi::util::mutex setLock; -namespace frc { +namespace wpi { CameraServerShared* GetCameraServerShared() { std::unique_lock lock(setLock); if (!cameraServerShared) { @@ -36,10 +36,10 @@ CameraServerShared* GetCameraServerShared() { } return cameraServerShared.get(); } -} // namespace frc +} // namespace wpi extern "C" { -void CameraServer_SetCameraServerShared(frc::CameraServerShared* shared) { +void CameraServer_SetCameraServerShared(wpi::CameraServerShared* shared) { std::unique_lock lock(setLock); cameraServerShared.reset(shared); } diff --git a/cameraserver/src/main/native/cpp/vision/VisionRunner.cpp b/cameraserver/src/main/native/cpp/vision/VisionRunner.cpp index 4c20b8a1ef..990cb3a14a 100644 --- a/cameraserver/src/main/native/cpp/vision/VisionRunner.cpp +++ b/cameraserver/src/main/native/cpp/vision/VisionRunner.cpp @@ -11,7 +11,7 @@ #include "wpi/cameraserver/CameraServerShared.hpp" -using namespace frc; +using namespace wpi::vision; VisionRunnerBase::VisionRunnerBase(cs::VideoSource videoSource) : m_image(std::make_unique()), @@ -24,7 +24,7 @@ VisionRunnerBase::VisionRunnerBase(cs::VideoSource videoSource) VisionRunnerBase::~VisionRunnerBase() = default; void VisionRunnerBase::RunOnce() { - auto csShared = frc::GetCameraServerShared(); + auto csShared = wpi::vision::GetCameraServerShared(); auto res = csShared->GetRobotMainThreadId(); if (res.second && (std::this_thread::get_id() == res.first)) { csShared->SetVisionRunnerError( @@ -41,7 +41,7 @@ void VisionRunnerBase::RunOnce() { } void VisionRunnerBase::RunForever() { - auto csShared = frc::GetCameraServerShared(); + auto csShared = wpi::vision::GetCameraServerShared(); auto res = csShared->GetRobotMainThreadId(); if (res.second && (std::this_thread::get_id() == res.first)) { csShared->SetVisionRunnerError( diff --git a/cameraserver/src/main/native/include/wpi/cameraserver/CameraServer.hpp b/cameraserver/src/main/native/include/wpi/cameraserver/CameraServer.hpp index 3082cf56f0..1f2cf59ed1 100644 --- a/cameraserver/src/main/native/include/wpi/cameraserver/CameraServer.hpp +++ b/cameraserver/src/main/native/include/wpi/cameraserver/CameraServer.hpp @@ -13,7 +13,7 @@ #include "wpi/cs/cscore_cv.hpp" -namespace frc { +namespace wpi { /** * Singleton class for creating and keeping camera servers. @@ -200,4 +200,4 @@ class CameraServer { CameraServer() = default; }; -} // namespace frc +} // namespace wpi diff --git a/cameraserver/src/main/native/include/wpi/cameraserver/CameraServerShared.hpp b/cameraserver/src/main/native/include/wpi/cameraserver/CameraServerShared.hpp index 0c8889f5fd..9a8a8ce779 100644 --- a/cameraserver/src/main/native/include/wpi/cameraserver/CameraServerShared.hpp +++ b/cameraserver/src/main/native/include/wpi/cameraserver/CameraServerShared.hpp @@ -11,7 +11,7 @@ #include -namespace frc { +namespace wpi { class CameraServerShared { public: virtual ~CameraServerShared() = default; @@ -42,9 +42,9 @@ class CameraServerShared { }; CameraServerShared* GetCameraServerShared(); -} // namespace frc +} // namespace wpi extern "C" { // Takes ownership -void CameraServer_SetCameraServerShared(frc::CameraServerShared* shared); +void CameraServer_SetCameraServerShared(wpi::CameraServerShared* shared); } // extern "C" diff --git a/cameraserver/src/main/native/include/wpi/vision/VisionPipeline.hpp b/cameraserver/src/main/native/include/wpi/vision/VisionPipeline.hpp index 954906bae2..0e63b61379 100644 --- a/cameraserver/src/main/native/include/wpi/vision/VisionPipeline.hpp +++ b/cameraserver/src/main/native/include/wpi/vision/VisionPipeline.hpp @@ -8,7 +8,7 @@ namespace cv { class Mat; } // namespace cv -namespace frc { +namespace wpi::vision { /** * A vision pipeline is responsible for running a group of OpenCV algorithms to @@ -26,4 +26,4 @@ class VisionPipeline { */ virtual void Process(cv::Mat& mat) = 0; }; -} // namespace frc +} // namespace wpi::vision diff --git a/cameraserver/src/main/native/include/wpi/vision/VisionRunner.hpp b/cameraserver/src/main/native/include/wpi/vision/VisionRunner.hpp index ba9726b05b..d565ef3c56 100644 --- a/cameraserver/src/main/native/include/wpi/vision/VisionRunner.hpp +++ b/cameraserver/src/main/native/include/wpi/vision/VisionRunner.hpp @@ -11,7 +11,7 @@ #include "wpi/cs/cscore_cv.hpp" #include "wpi/vision/VisionPipeline.hpp" -namespace frc { +namespace wpi::vision { /** * Non-template base class for VisionRunner. @@ -111,4 +111,4 @@ class VisionRunner : public VisionRunnerBase { std::function m_listener; }; -} // namespace frc +} // namespace wpi::vision diff --git a/commandsv2/src/generate/main/native/cpp/wpi/commands2/button/commandhid.cpp.jinja b/commandsv2/src/generate/main/native/cpp/wpi/commands2/button/commandhid.cpp.jinja index e6108c4076..dd60be7b34 100644 --- a/commandsv2/src/generate/main/native/cpp/wpi/commands2/button/commandhid.cpp.jinja +++ b/commandsv2/src/generate/main/native/cpp/wpi/commands2/button/commandhid.cpp.jinja @@ -8,23 +8,23 @@ {%- endmacro %} #include "wpi/commands2/button/Command{{ ConsoleName }}Controller.hpp" -using namespace frc2; +using namespace wpi::cmd; Command{{ ConsoleName }}Controller::Command{{ ConsoleName }}Controller(int port) - : CommandGenericHID(port), m_hid{frc::{{ ConsoleName }}Controller(port)} {} + : CommandGenericHID(port), m_hid{wpi::{{ ConsoleName }}Controller(port)} {} -frc::{{ ConsoleName }}Controller& Command{{ ConsoleName }}Controller::GetHID() { +wpi::{{ ConsoleName }}Controller& Command{{ ConsoleName }}Controller::GetHID() { return m_hid; } {% for button in buttons %} -Trigger Command{{ ConsoleName }}Controller::{{ capitalize_first(button.name) }}(frc::EventLoop* loop) const { - return Button(frc::{{ ConsoleName }}Controller::Button::k{{ capitalize_first(button.name) }}, loop); +Trigger Command{{ ConsoleName }}Controller::{{ capitalize_first(button.name) }}(wpi::EventLoop* loop) const { + return Button(wpi::{{ ConsoleName }}Controller::Button::k{{ capitalize_first(button.name) }}, loop); } {% endfor -%} {% for trigger in triggers -%} {% if trigger.UseThresholdMethods %} Trigger Command{{ ConsoleName }}Controller::{{ capitalize_first(trigger.name) }}(double threshold, - frc::EventLoop* loop) const { + wpi::EventLoop* loop) const { return Trigger(loop, [this, threshold] { return m_hid.Get{{ capitalize_first(trigger.name) }}Axis() > threshold; }); diff --git a/commandsv2/src/generate/main/native/include/wpi/commands2/button/commandhid.hpp.jinja b/commandsv2/src/generate/main/native/include/wpi/commands2/button/commandhid.hpp.jinja index 694c61bad4..3429248ba2 100644 --- a/commandsv2/src/generate/main/native/include/wpi/commands2/button/commandhid.hpp.jinja +++ b/commandsv2/src/generate/main/native/include/wpi/commands2/button/commandhid.hpp.jinja @@ -13,12 +13,12 @@ #include "wpi/commands2/CommandScheduler.hpp" #include "wpi/commands2/button/CommandGenericHID.hpp" -namespace frc2 { +namespace wpi::cmd { /** - * A version of {@link frc::{{ ConsoleName }}Controller} with {@link Trigger} factories for + * A version of {@link wpi::{{ ConsoleName }}Controller} with {@link Trigger} factories for * command-based. * - * @see frc::{{ ConsoleName }}Controller + * @see wpi::{{ ConsoleName }}Controller */ class Command{{ ConsoleName }}Controller : public CommandGenericHID { public: @@ -35,7 +35,7 @@ class Command{{ ConsoleName }}Controller : public CommandGenericHID { * * @return the wrapped GenericHID object */ - frc::{{ ConsoleName }}Controller& GetHID(); + wpi::{{ ConsoleName }}Controller& GetHID(); {% for button in buttons %} /** * Constructs a Trigger instance around the {{ button.DocName|default(button.name) }} button's @@ -46,7 +46,7 @@ class Command{{ ConsoleName }}Controller : public CommandGenericHID { * @return a Trigger instance representing the {{ button.DocName|default(button.name) }} button's * digital signal attached to the given loop. */ - Trigger {{ capitalize_first(button.name) }}(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger {{ capitalize_first(button.name) }}(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; {% endfor -%} {% for trigger in triggers -%} @@ -65,7 +65,7 @@ class Command{{ ConsoleName }}Controller : public CommandGenericHID { * exceeds the provided threshold, attached to the given loop */ Trigger {{ capitalize_first(trigger.name) }}(double threshold = 0.5, - frc::EventLoop* loop = CommandScheduler::GetInstance() + wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; {% endif -%} {% endfor -%} @@ -87,6 +87,6 @@ class Command{{ ConsoleName }}Controller : public CommandGenericHID { double Get{{ capitalize_first(trigger.name) }}Axis() const; {% endfor %} private: - frc::{{ ConsoleName }}Controller m_hid; + wpi::{{ ConsoleName }}Controller m_hid; }; -} // namespace frc2 +} // namespace wpi::cmd diff --git a/commandsv2/src/generated/main/native/cpp/wpi/commands2/button/CommandPS4Controller.cpp b/commandsv2/src/generated/main/native/cpp/wpi/commands2/button/CommandPS4Controller.cpp index 62a68e6110..0e57562f03 100644 --- a/commandsv2/src/generated/main/native/cpp/wpi/commands2/button/CommandPS4Controller.cpp +++ b/commandsv2/src/generated/main/native/cpp/wpi/commands2/button/CommandPS4Controller.cpp @@ -6,69 +6,69 @@ #include "wpi/commands2/button/CommandPS4Controller.hpp" -using namespace frc2; +using namespace wpi::cmd; CommandPS4Controller::CommandPS4Controller(int port) - : CommandGenericHID(port), m_hid{frc::PS4Controller(port)} {} + : CommandGenericHID(port), m_hid{wpi::PS4Controller(port)} {} -frc::PS4Controller& CommandPS4Controller::GetHID() { +wpi::PS4Controller& CommandPS4Controller::GetHID() { return m_hid; } -Trigger CommandPS4Controller::Square(frc::EventLoop* loop) const { - return Button(frc::PS4Controller::Button::kSquare, loop); +Trigger CommandPS4Controller::Square(wpi::EventLoop* loop) const { + return Button(wpi::PS4Controller::Button::kSquare, loop); } -Trigger CommandPS4Controller::Cross(frc::EventLoop* loop) const { - return Button(frc::PS4Controller::Button::kCross, loop); +Trigger CommandPS4Controller::Cross(wpi::EventLoop* loop) const { + return Button(wpi::PS4Controller::Button::kCross, loop); } -Trigger CommandPS4Controller::Circle(frc::EventLoop* loop) const { - return Button(frc::PS4Controller::Button::kCircle, loop); +Trigger CommandPS4Controller::Circle(wpi::EventLoop* loop) const { + return Button(wpi::PS4Controller::Button::kCircle, loop); } -Trigger CommandPS4Controller::Triangle(frc::EventLoop* loop) const { - return Button(frc::PS4Controller::Button::kTriangle, loop); +Trigger CommandPS4Controller::Triangle(wpi::EventLoop* loop) const { + return Button(wpi::PS4Controller::Button::kTriangle, loop); } -Trigger CommandPS4Controller::L1(frc::EventLoop* loop) const { - return Button(frc::PS4Controller::Button::kL1, loop); +Trigger CommandPS4Controller::L1(wpi::EventLoop* loop) const { + return Button(wpi::PS4Controller::Button::kL1, loop); } -Trigger CommandPS4Controller::R1(frc::EventLoop* loop) const { - return Button(frc::PS4Controller::Button::kR1, loop); +Trigger CommandPS4Controller::R1(wpi::EventLoop* loop) const { + return Button(wpi::PS4Controller::Button::kR1, loop); } -Trigger CommandPS4Controller::L2(frc::EventLoop* loop) const { - return Button(frc::PS4Controller::Button::kL2, loop); +Trigger CommandPS4Controller::L2(wpi::EventLoop* loop) const { + return Button(wpi::PS4Controller::Button::kL2, loop); } -Trigger CommandPS4Controller::R2(frc::EventLoop* loop) const { - return Button(frc::PS4Controller::Button::kR2, loop); +Trigger CommandPS4Controller::R2(wpi::EventLoop* loop) const { + return Button(wpi::PS4Controller::Button::kR2, loop); } -Trigger CommandPS4Controller::Share(frc::EventLoop* loop) const { - return Button(frc::PS4Controller::Button::kShare, loop); +Trigger CommandPS4Controller::Share(wpi::EventLoop* loop) const { + return Button(wpi::PS4Controller::Button::kShare, loop); } -Trigger CommandPS4Controller::Options(frc::EventLoop* loop) const { - return Button(frc::PS4Controller::Button::kOptions, loop); +Trigger CommandPS4Controller::Options(wpi::EventLoop* loop) const { + return Button(wpi::PS4Controller::Button::kOptions, loop); } -Trigger CommandPS4Controller::L3(frc::EventLoop* loop) const { - return Button(frc::PS4Controller::Button::kL3, loop); +Trigger CommandPS4Controller::L3(wpi::EventLoop* loop) const { + return Button(wpi::PS4Controller::Button::kL3, loop); } -Trigger CommandPS4Controller::R3(frc::EventLoop* loop) const { - return Button(frc::PS4Controller::Button::kR3, loop); +Trigger CommandPS4Controller::R3(wpi::EventLoop* loop) const { + return Button(wpi::PS4Controller::Button::kR3, loop); } -Trigger CommandPS4Controller::PS(frc::EventLoop* loop) const { - return Button(frc::PS4Controller::Button::kPS, loop); +Trigger CommandPS4Controller::PS(wpi::EventLoop* loop) const { + return Button(wpi::PS4Controller::Button::kPS, loop); } -Trigger CommandPS4Controller::Touchpad(frc::EventLoop* loop) const { - return Button(frc::PS4Controller::Button::kTouchpad, loop); +Trigger CommandPS4Controller::Touchpad(wpi::EventLoop* loop) const { + return Button(wpi::PS4Controller::Button::kTouchpad, loop); } double CommandPS4Controller::GetLeftX() const { diff --git a/commandsv2/src/generated/main/native/cpp/wpi/commands2/button/CommandPS5Controller.cpp b/commandsv2/src/generated/main/native/cpp/wpi/commands2/button/CommandPS5Controller.cpp index 28bfb454bd..e3c375cbb9 100644 --- a/commandsv2/src/generated/main/native/cpp/wpi/commands2/button/CommandPS5Controller.cpp +++ b/commandsv2/src/generated/main/native/cpp/wpi/commands2/button/CommandPS5Controller.cpp @@ -6,69 +6,69 @@ #include "wpi/commands2/button/CommandPS5Controller.hpp" -using namespace frc2; +using namespace wpi::cmd; CommandPS5Controller::CommandPS5Controller(int port) - : CommandGenericHID(port), m_hid{frc::PS5Controller(port)} {} + : CommandGenericHID(port), m_hid{wpi::PS5Controller(port)} {} -frc::PS5Controller& CommandPS5Controller::GetHID() { +wpi::PS5Controller& CommandPS5Controller::GetHID() { return m_hid; } -Trigger CommandPS5Controller::Square(frc::EventLoop* loop) const { - return Button(frc::PS5Controller::Button::kSquare, loop); +Trigger CommandPS5Controller::Square(wpi::EventLoop* loop) const { + return Button(wpi::PS5Controller::Button::kSquare, loop); } -Trigger CommandPS5Controller::Cross(frc::EventLoop* loop) const { - return Button(frc::PS5Controller::Button::kCross, loop); +Trigger CommandPS5Controller::Cross(wpi::EventLoop* loop) const { + return Button(wpi::PS5Controller::Button::kCross, loop); } -Trigger CommandPS5Controller::Circle(frc::EventLoop* loop) const { - return Button(frc::PS5Controller::Button::kCircle, loop); +Trigger CommandPS5Controller::Circle(wpi::EventLoop* loop) const { + return Button(wpi::PS5Controller::Button::kCircle, loop); } -Trigger CommandPS5Controller::Triangle(frc::EventLoop* loop) const { - return Button(frc::PS5Controller::Button::kTriangle, loop); +Trigger CommandPS5Controller::Triangle(wpi::EventLoop* loop) const { + return Button(wpi::PS5Controller::Button::kTriangle, loop); } -Trigger CommandPS5Controller::L1(frc::EventLoop* loop) const { - return Button(frc::PS5Controller::Button::kL1, loop); +Trigger CommandPS5Controller::L1(wpi::EventLoop* loop) const { + return Button(wpi::PS5Controller::Button::kL1, loop); } -Trigger CommandPS5Controller::R1(frc::EventLoop* loop) const { - return Button(frc::PS5Controller::Button::kR1, loop); +Trigger CommandPS5Controller::R1(wpi::EventLoop* loop) const { + return Button(wpi::PS5Controller::Button::kR1, loop); } -Trigger CommandPS5Controller::L2(frc::EventLoop* loop) const { - return Button(frc::PS5Controller::Button::kL2, loop); +Trigger CommandPS5Controller::L2(wpi::EventLoop* loop) const { + return Button(wpi::PS5Controller::Button::kL2, loop); } -Trigger CommandPS5Controller::R2(frc::EventLoop* loop) const { - return Button(frc::PS5Controller::Button::kR2, loop); +Trigger CommandPS5Controller::R2(wpi::EventLoop* loop) const { + return Button(wpi::PS5Controller::Button::kR2, loop); } -Trigger CommandPS5Controller::Create(frc::EventLoop* loop) const { - return Button(frc::PS5Controller::Button::kCreate, loop); +Trigger CommandPS5Controller::Create(wpi::EventLoop* loop) const { + return Button(wpi::PS5Controller::Button::kCreate, loop); } -Trigger CommandPS5Controller::Options(frc::EventLoop* loop) const { - return Button(frc::PS5Controller::Button::kOptions, loop); +Trigger CommandPS5Controller::Options(wpi::EventLoop* loop) const { + return Button(wpi::PS5Controller::Button::kOptions, loop); } -Trigger CommandPS5Controller::L3(frc::EventLoop* loop) const { - return Button(frc::PS5Controller::Button::kL3, loop); +Trigger CommandPS5Controller::L3(wpi::EventLoop* loop) const { + return Button(wpi::PS5Controller::Button::kL3, loop); } -Trigger CommandPS5Controller::R3(frc::EventLoop* loop) const { - return Button(frc::PS5Controller::Button::kR3, loop); +Trigger CommandPS5Controller::R3(wpi::EventLoop* loop) const { + return Button(wpi::PS5Controller::Button::kR3, loop); } -Trigger CommandPS5Controller::PS(frc::EventLoop* loop) const { - return Button(frc::PS5Controller::Button::kPS, loop); +Trigger CommandPS5Controller::PS(wpi::EventLoop* loop) const { + return Button(wpi::PS5Controller::Button::kPS, loop); } -Trigger CommandPS5Controller::Touchpad(frc::EventLoop* loop) const { - return Button(frc::PS5Controller::Button::kTouchpad, loop); +Trigger CommandPS5Controller::Touchpad(wpi::EventLoop* loop) const { + return Button(wpi::PS5Controller::Button::kTouchpad, loop); } double CommandPS5Controller::GetLeftX() const { diff --git a/commandsv2/src/generated/main/native/cpp/wpi/commands2/button/CommandStadiaController.cpp b/commandsv2/src/generated/main/native/cpp/wpi/commands2/button/CommandStadiaController.cpp index 4ba12c3779..a6141abd0d 100644 --- a/commandsv2/src/generated/main/native/cpp/wpi/commands2/button/CommandStadiaController.cpp +++ b/commandsv2/src/generated/main/native/cpp/wpi/commands2/button/CommandStadiaController.cpp @@ -6,73 +6,73 @@ #include "wpi/commands2/button/CommandStadiaController.hpp" -using namespace frc2; +using namespace wpi::cmd; CommandStadiaController::CommandStadiaController(int port) - : CommandGenericHID(port), m_hid{frc::StadiaController(port)} {} + : CommandGenericHID(port), m_hid{wpi::StadiaController(port)} {} -frc::StadiaController& CommandStadiaController::GetHID() { +wpi::StadiaController& CommandStadiaController::GetHID() { return m_hid; } -Trigger CommandStadiaController::A(frc::EventLoop* loop) const { - return Button(frc::StadiaController::Button::kA, loop); +Trigger CommandStadiaController::A(wpi::EventLoop* loop) const { + return Button(wpi::StadiaController::Button::kA, loop); } -Trigger CommandStadiaController::B(frc::EventLoop* loop) const { - return Button(frc::StadiaController::Button::kB, loop); +Trigger CommandStadiaController::B(wpi::EventLoop* loop) const { + return Button(wpi::StadiaController::Button::kB, loop); } -Trigger CommandStadiaController::X(frc::EventLoop* loop) const { - return Button(frc::StadiaController::Button::kX, loop); +Trigger CommandStadiaController::X(wpi::EventLoop* loop) const { + return Button(wpi::StadiaController::Button::kX, loop); } -Trigger CommandStadiaController::Y(frc::EventLoop* loop) const { - return Button(frc::StadiaController::Button::kY, loop); +Trigger CommandStadiaController::Y(wpi::EventLoop* loop) const { + return Button(wpi::StadiaController::Button::kY, loop); } -Trigger CommandStadiaController::LeftBumper(frc::EventLoop* loop) const { - return Button(frc::StadiaController::Button::kLeftBumper, loop); +Trigger CommandStadiaController::LeftBumper(wpi::EventLoop* loop) const { + return Button(wpi::StadiaController::Button::kLeftBumper, loop); } -Trigger CommandStadiaController::RightBumper(frc::EventLoop* loop) const { - return Button(frc::StadiaController::Button::kRightBumper, loop); +Trigger CommandStadiaController::RightBumper(wpi::EventLoop* loop) const { + return Button(wpi::StadiaController::Button::kRightBumper, loop); } -Trigger CommandStadiaController::LeftStick(frc::EventLoop* loop) const { - return Button(frc::StadiaController::Button::kLeftStick, loop); +Trigger CommandStadiaController::LeftStick(wpi::EventLoop* loop) const { + return Button(wpi::StadiaController::Button::kLeftStick, loop); } -Trigger CommandStadiaController::RightStick(frc::EventLoop* loop) const { - return Button(frc::StadiaController::Button::kRightStick, loop); +Trigger CommandStadiaController::RightStick(wpi::EventLoop* loop) const { + return Button(wpi::StadiaController::Button::kRightStick, loop); } -Trigger CommandStadiaController::Ellipses(frc::EventLoop* loop) const { - return Button(frc::StadiaController::Button::kEllipses, loop); +Trigger CommandStadiaController::Ellipses(wpi::EventLoop* loop) const { + return Button(wpi::StadiaController::Button::kEllipses, loop); } -Trigger CommandStadiaController::Hamburger(frc::EventLoop* loop) const { - return Button(frc::StadiaController::Button::kHamburger, loop); +Trigger CommandStadiaController::Hamburger(wpi::EventLoop* loop) const { + return Button(wpi::StadiaController::Button::kHamburger, loop); } -Trigger CommandStadiaController::Stadia(frc::EventLoop* loop) const { - return Button(frc::StadiaController::Button::kStadia, loop); +Trigger CommandStadiaController::Stadia(wpi::EventLoop* loop) const { + return Button(wpi::StadiaController::Button::kStadia, loop); } -Trigger CommandStadiaController::RightTrigger(frc::EventLoop* loop) const { - return Button(frc::StadiaController::Button::kRightTrigger, loop); +Trigger CommandStadiaController::RightTrigger(wpi::EventLoop* loop) const { + return Button(wpi::StadiaController::Button::kRightTrigger, loop); } -Trigger CommandStadiaController::LeftTrigger(frc::EventLoop* loop) const { - return Button(frc::StadiaController::Button::kLeftTrigger, loop); +Trigger CommandStadiaController::LeftTrigger(wpi::EventLoop* loop) const { + return Button(wpi::StadiaController::Button::kLeftTrigger, loop); } -Trigger CommandStadiaController::Google(frc::EventLoop* loop) const { - return Button(frc::StadiaController::Button::kGoogle, loop); +Trigger CommandStadiaController::Google(wpi::EventLoop* loop) const { + return Button(wpi::StadiaController::Button::kGoogle, loop); } -Trigger CommandStadiaController::Frame(frc::EventLoop* loop) const { - return Button(frc::StadiaController::Button::kFrame, loop); +Trigger CommandStadiaController::Frame(wpi::EventLoop* loop) const { + return Button(wpi::StadiaController::Button::kFrame, loop); } double CommandStadiaController::GetLeftX() const { diff --git a/commandsv2/src/generated/main/native/cpp/wpi/commands2/button/CommandXboxController.cpp b/commandsv2/src/generated/main/native/cpp/wpi/commands2/button/CommandXboxController.cpp index 27def8a8ba..6adf138dbd 100644 --- a/commandsv2/src/generated/main/native/cpp/wpi/commands2/button/CommandXboxController.cpp +++ b/commandsv2/src/generated/main/native/cpp/wpi/commands2/button/CommandXboxController.cpp @@ -6,64 +6,64 @@ #include "wpi/commands2/button/CommandXboxController.hpp" -using namespace frc2; +using namespace wpi::cmd; CommandXboxController::CommandXboxController(int port) - : CommandGenericHID(port), m_hid{frc::XboxController(port)} {} + : CommandGenericHID(port), m_hid{wpi::XboxController(port)} {} -frc::XboxController& CommandXboxController::GetHID() { +wpi::XboxController& CommandXboxController::GetHID() { return m_hid; } -Trigger CommandXboxController::A(frc::EventLoop* loop) const { - return Button(frc::XboxController::Button::kA, loop); +Trigger CommandXboxController::A(wpi::EventLoop* loop) const { + return Button(wpi::XboxController::Button::kA, loop); } -Trigger CommandXboxController::B(frc::EventLoop* loop) const { - return Button(frc::XboxController::Button::kB, loop); +Trigger CommandXboxController::B(wpi::EventLoop* loop) const { + return Button(wpi::XboxController::Button::kB, loop); } -Trigger CommandXboxController::X(frc::EventLoop* loop) const { - return Button(frc::XboxController::Button::kX, loop); +Trigger CommandXboxController::X(wpi::EventLoop* loop) const { + return Button(wpi::XboxController::Button::kX, loop); } -Trigger CommandXboxController::Y(frc::EventLoop* loop) const { - return Button(frc::XboxController::Button::kY, loop); +Trigger CommandXboxController::Y(wpi::EventLoop* loop) const { + return Button(wpi::XboxController::Button::kY, loop); } -Trigger CommandXboxController::LeftBumper(frc::EventLoop* loop) const { - return Button(frc::XboxController::Button::kLeftBumper, loop); +Trigger CommandXboxController::LeftBumper(wpi::EventLoop* loop) const { + return Button(wpi::XboxController::Button::kLeftBumper, loop); } -Trigger CommandXboxController::RightBumper(frc::EventLoop* loop) const { - return Button(frc::XboxController::Button::kRightBumper, loop); +Trigger CommandXboxController::RightBumper(wpi::EventLoop* loop) const { + return Button(wpi::XboxController::Button::kRightBumper, loop); } -Trigger CommandXboxController::Back(frc::EventLoop* loop) const { - return Button(frc::XboxController::Button::kBack, loop); +Trigger CommandXboxController::Back(wpi::EventLoop* loop) const { + return Button(wpi::XboxController::Button::kBack, loop); } -Trigger CommandXboxController::Start(frc::EventLoop* loop) const { - return Button(frc::XboxController::Button::kStart, loop); +Trigger CommandXboxController::Start(wpi::EventLoop* loop) const { + return Button(wpi::XboxController::Button::kStart, loop); } -Trigger CommandXboxController::LeftStick(frc::EventLoop* loop) const { - return Button(frc::XboxController::Button::kLeftStick, loop); +Trigger CommandXboxController::LeftStick(wpi::EventLoop* loop) const { + return Button(wpi::XboxController::Button::kLeftStick, loop); } -Trigger CommandXboxController::RightStick(frc::EventLoop* loop) const { - return Button(frc::XboxController::Button::kRightStick, loop); +Trigger CommandXboxController::RightStick(wpi::EventLoop* loop) const { + return Button(wpi::XboxController::Button::kRightStick, loop); } Trigger CommandXboxController::LeftTrigger(double threshold, - frc::EventLoop* loop) const { + wpi::EventLoop* loop) const { return Trigger(loop, [this, threshold] { return m_hid.GetLeftTriggerAxis() > threshold; }); } Trigger CommandXboxController::RightTrigger(double threshold, - frc::EventLoop* loop) const { + wpi::EventLoop* loop) const { return Trigger(loop, [this, threshold] { return m_hid.GetRightTriggerAxis() > threshold; }); diff --git a/commandsv2/src/generated/main/native/include/wpi/commands2/button/CommandPS4Controller.hpp b/commandsv2/src/generated/main/native/include/wpi/commands2/button/CommandPS4Controller.hpp index 8b97909ed0..27decaf701 100644 --- a/commandsv2/src/generated/main/native/include/wpi/commands2/button/CommandPS4Controller.hpp +++ b/commandsv2/src/generated/main/native/include/wpi/commands2/button/CommandPS4Controller.hpp @@ -11,12 +11,12 @@ #include "wpi/commands2/CommandScheduler.hpp" #include "wpi/commands2/button/CommandGenericHID.hpp" -namespace frc2 { +namespace wpi::cmd { /** - * A version of {@link frc::PS4Controller} with {@link Trigger} factories for + * A version of {@link wpi::PS4Controller} with {@link Trigger} factories for * command-based. * - * @see frc::PS4Controller + * @see wpi::PS4Controller */ class CommandPS4Controller : public CommandGenericHID { public: @@ -33,7 +33,7 @@ class CommandPS4Controller : public CommandGenericHID { * * @return the wrapped GenericHID object */ - frc::PS4Controller& GetHID(); + wpi::PS4Controller& GetHID(); /** * Constructs a Trigger instance around the square button's @@ -44,7 +44,7 @@ class CommandPS4Controller : public CommandGenericHID { * @return a Trigger instance representing the square button's * digital signal attached to the given loop. */ - Trigger Square(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger Square(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -56,7 +56,7 @@ class CommandPS4Controller : public CommandGenericHID { * @return a Trigger instance representing the cross button's * digital signal attached to the given loop. */ - Trigger Cross(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger Cross(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -68,7 +68,7 @@ class CommandPS4Controller : public CommandGenericHID { * @return a Trigger instance representing the circle button's * digital signal attached to the given loop. */ - Trigger Circle(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger Circle(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -80,7 +80,7 @@ class CommandPS4Controller : public CommandGenericHID { * @return a Trigger instance representing the triangle button's * digital signal attached to the given loop. */ - Trigger Triangle(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger Triangle(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -92,7 +92,7 @@ class CommandPS4Controller : public CommandGenericHID { * @return a Trigger instance representing the left trigger 1 button's * digital signal attached to the given loop. */ - Trigger L1(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger L1(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -104,7 +104,7 @@ class CommandPS4Controller : public CommandGenericHID { * @return a Trigger instance representing the right trigger 1 button's * digital signal attached to the given loop. */ - Trigger R1(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger R1(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -116,7 +116,7 @@ class CommandPS4Controller : public CommandGenericHID { * @return a Trigger instance representing the left trigger 2 button's * digital signal attached to the given loop. */ - Trigger L2(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger L2(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -128,7 +128,7 @@ class CommandPS4Controller : public CommandGenericHID { * @return a Trigger instance representing the right trigger 2 button's * digital signal attached to the given loop. */ - Trigger R2(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger R2(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -140,7 +140,7 @@ class CommandPS4Controller : public CommandGenericHID { * @return a Trigger instance representing the share button's * digital signal attached to the given loop. */ - Trigger Share(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger Share(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -152,7 +152,7 @@ class CommandPS4Controller : public CommandGenericHID { * @return a Trigger instance representing the options button's * digital signal attached to the given loop. */ - Trigger Options(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger Options(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -164,7 +164,7 @@ class CommandPS4Controller : public CommandGenericHID { * @return a Trigger instance representing the L3 (left stick) button's * digital signal attached to the given loop. */ - Trigger L3(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger L3(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -176,7 +176,7 @@ class CommandPS4Controller : public CommandGenericHID { * @return a Trigger instance representing the R3 (right stick) button's * digital signal attached to the given loop. */ - Trigger R3(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger R3(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -188,7 +188,7 @@ class CommandPS4Controller : public CommandGenericHID { * @return a Trigger instance representing the PlayStation button's * digital signal attached to the given loop. */ - Trigger PS(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger PS(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -200,7 +200,7 @@ class CommandPS4Controller : public CommandGenericHID { * @return a Trigger instance representing the touchpad button's * digital signal attached to the given loop. */ - Trigger Touchpad(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger Touchpad(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -248,6 +248,6 @@ class CommandPS4Controller : public CommandGenericHID { double GetR2Axis() const; private: - frc::PS4Controller m_hid; + wpi::PS4Controller m_hid; }; -} // namespace frc2 +} // namespace wpi::cmd diff --git a/commandsv2/src/generated/main/native/include/wpi/commands2/button/CommandPS5Controller.hpp b/commandsv2/src/generated/main/native/include/wpi/commands2/button/CommandPS5Controller.hpp index ca60915621..916a7a362e 100644 --- a/commandsv2/src/generated/main/native/include/wpi/commands2/button/CommandPS5Controller.hpp +++ b/commandsv2/src/generated/main/native/include/wpi/commands2/button/CommandPS5Controller.hpp @@ -11,12 +11,12 @@ #include "wpi/commands2/CommandScheduler.hpp" #include "wpi/commands2/button/CommandGenericHID.hpp" -namespace frc2 { +namespace wpi::cmd { /** - * A version of {@link frc::PS5Controller} with {@link Trigger} factories for + * A version of {@link wpi::PS5Controller} with {@link Trigger} factories for * command-based. * - * @see frc::PS5Controller + * @see wpi::PS5Controller */ class CommandPS5Controller : public CommandGenericHID { public: @@ -33,7 +33,7 @@ class CommandPS5Controller : public CommandGenericHID { * * @return the wrapped GenericHID object */ - frc::PS5Controller& GetHID(); + wpi::PS5Controller& GetHID(); /** * Constructs a Trigger instance around the square button's @@ -44,7 +44,7 @@ class CommandPS5Controller : public CommandGenericHID { * @return a Trigger instance representing the square button's * digital signal attached to the given loop. */ - Trigger Square(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger Square(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -56,7 +56,7 @@ class CommandPS5Controller : public CommandGenericHID { * @return a Trigger instance representing the cross button's * digital signal attached to the given loop. */ - Trigger Cross(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger Cross(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -68,7 +68,7 @@ class CommandPS5Controller : public CommandGenericHID { * @return a Trigger instance representing the circle button's * digital signal attached to the given loop. */ - Trigger Circle(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger Circle(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -80,7 +80,7 @@ class CommandPS5Controller : public CommandGenericHID { * @return a Trigger instance representing the triangle button's * digital signal attached to the given loop. */ - Trigger Triangle(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger Triangle(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -92,7 +92,7 @@ class CommandPS5Controller : public CommandGenericHID { * @return a Trigger instance representing the left trigger 1 button's * digital signal attached to the given loop. */ - Trigger L1(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger L1(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -104,7 +104,7 @@ class CommandPS5Controller : public CommandGenericHID { * @return a Trigger instance representing the right trigger 1 button's * digital signal attached to the given loop. */ - Trigger R1(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger R1(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -116,7 +116,7 @@ class CommandPS5Controller : public CommandGenericHID { * @return a Trigger instance representing the left trigger 2 button's * digital signal attached to the given loop. */ - Trigger L2(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger L2(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -128,7 +128,7 @@ class CommandPS5Controller : public CommandGenericHID { * @return a Trigger instance representing the right trigger 2 button's * digital signal attached to the given loop. */ - Trigger R2(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger R2(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -140,7 +140,7 @@ class CommandPS5Controller : public CommandGenericHID { * @return a Trigger instance representing the create button's * digital signal attached to the given loop. */ - Trigger Create(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger Create(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -152,7 +152,7 @@ class CommandPS5Controller : public CommandGenericHID { * @return a Trigger instance representing the options button's * digital signal attached to the given loop. */ - Trigger Options(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger Options(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -164,7 +164,7 @@ class CommandPS5Controller : public CommandGenericHID { * @return a Trigger instance representing the L3 (left stick) button's * digital signal attached to the given loop. */ - Trigger L3(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger L3(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -176,7 +176,7 @@ class CommandPS5Controller : public CommandGenericHID { * @return a Trigger instance representing the R3 (right stick) button's * digital signal attached to the given loop. */ - Trigger R3(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger R3(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -188,7 +188,7 @@ class CommandPS5Controller : public CommandGenericHID { * @return a Trigger instance representing the PlayStation button's * digital signal attached to the given loop. */ - Trigger PS(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger PS(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -200,7 +200,7 @@ class CommandPS5Controller : public CommandGenericHID { * @return a Trigger instance representing the touchpad button's * digital signal attached to the given loop. */ - Trigger Touchpad(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger Touchpad(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -248,6 +248,6 @@ class CommandPS5Controller : public CommandGenericHID { double GetR2Axis() const; private: - frc::PS5Controller m_hid; + wpi::PS5Controller m_hid; }; -} // namespace frc2 +} // namespace wpi::cmd diff --git a/commandsv2/src/generated/main/native/include/wpi/commands2/button/CommandStadiaController.hpp b/commandsv2/src/generated/main/native/include/wpi/commands2/button/CommandStadiaController.hpp index 207bd90e33..43d85855b4 100644 --- a/commandsv2/src/generated/main/native/include/wpi/commands2/button/CommandStadiaController.hpp +++ b/commandsv2/src/generated/main/native/include/wpi/commands2/button/CommandStadiaController.hpp @@ -11,12 +11,12 @@ #include "wpi/commands2/CommandScheduler.hpp" #include "wpi/commands2/button/CommandGenericHID.hpp" -namespace frc2 { +namespace wpi::cmd { /** - * A version of {@link frc::StadiaController} with {@link Trigger} factories for + * A version of {@link wpi::StadiaController} with {@link Trigger} factories for * command-based. * - * @see frc::StadiaController + * @see wpi::StadiaController */ class CommandStadiaController : public CommandGenericHID { public: @@ -33,7 +33,7 @@ class CommandStadiaController : public CommandGenericHID { * * @return the wrapped GenericHID object */ - frc::StadiaController& GetHID(); + wpi::StadiaController& GetHID(); /** * Constructs a Trigger instance around the A button's @@ -44,7 +44,7 @@ class CommandStadiaController : public CommandGenericHID { * @return a Trigger instance representing the A button's * digital signal attached to the given loop. */ - Trigger A(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger A(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -56,7 +56,7 @@ class CommandStadiaController : public CommandGenericHID { * @return a Trigger instance representing the B button's * digital signal attached to the given loop. */ - Trigger B(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger B(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -68,7 +68,7 @@ class CommandStadiaController : public CommandGenericHID { * @return a Trigger instance representing the X button's * digital signal attached to the given loop. */ - Trigger X(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger X(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -80,7 +80,7 @@ class CommandStadiaController : public CommandGenericHID { * @return a Trigger instance representing the Y button's * digital signal attached to the given loop. */ - Trigger Y(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger Y(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -92,7 +92,7 @@ class CommandStadiaController : public CommandGenericHID { * @return a Trigger instance representing the left bumper button's * digital signal attached to the given loop. */ - Trigger LeftBumper(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger LeftBumper(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -104,7 +104,7 @@ class CommandStadiaController : public CommandGenericHID { * @return a Trigger instance representing the right bumper button's * digital signal attached to the given loop. */ - Trigger RightBumper(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger RightBumper(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -116,7 +116,7 @@ class CommandStadiaController : public CommandGenericHID { * @return a Trigger instance representing the left stick button's * digital signal attached to the given loop. */ - Trigger LeftStick(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger LeftStick(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -128,7 +128,7 @@ class CommandStadiaController : public CommandGenericHID { * @return a Trigger instance representing the right stick button's * digital signal attached to the given loop. */ - Trigger RightStick(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger RightStick(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -140,7 +140,7 @@ class CommandStadiaController : public CommandGenericHID { * @return a Trigger instance representing the ellipses button's * digital signal attached to the given loop. */ - Trigger Ellipses(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger Ellipses(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -152,7 +152,7 @@ class CommandStadiaController : public CommandGenericHID { * @return a Trigger instance representing the hamburger button's * digital signal attached to the given loop. */ - Trigger Hamburger(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger Hamburger(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -164,7 +164,7 @@ class CommandStadiaController : public CommandGenericHID { * @return a Trigger instance representing the stadia button's * digital signal attached to the given loop. */ - Trigger Stadia(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger Stadia(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -176,7 +176,7 @@ class CommandStadiaController : public CommandGenericHID { * @return a Trigger instance representing the right trigger button's * digital signal attached to the given loop. */ - Trigger RightTrigger(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger RightTrigger(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -188,7 +188,7 @@ class CommandStadiaController : public CommandGenericHID { * @return a Trigger instance representing the left trigger button's * digital signal attached to the given loop. */ - Trigger LeftTrigger(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger LeftTrigger(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -200,7 +200,7 @@ class CommandStadiaController : public CommandGenericHID { * @return a Trigger instance representing the google button's * digital signal attached to the given loop. */ - Trigger Google(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger Google(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -212,7 +212,7 @@ class CommandStadiaController : public CommandGenericHID { * @return a Trigger instance representing the frame button's * digital signal attached to the given loop. */ - Trigger Frame(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger Frame(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -244,6 +244,6 @@ class CommandStadiaController : public CommandGenericHID { double GetRightY() const; private: - frc::StadiaController m_hid; + wpi::StadiaController m_hid; }; -} // namespace frc2 +} // namespace wpi::cmd diff --git a/commandsv2/src/generated/main/native/include/wpi/commands2/button/CommandXboxController.hpp b/commandsv2/src/generated/main/native/include/wpi/commands2/button/CommandXboxController.hpp index 0029eaf99c..9fe07277b0 100644 --- a/commandsv2/src/generated/main/native/include/wpi/commands2/button/CommandXboxController.hpp +++ b/commandsv2/src/generated/main/native/include/wpi/commands2/button/CommandXboxController.hpp @@ -11,12 +11,12 @@ #include "wpi/commands2/CommandScheduler.hpp" #include "wpi/commands2/button/CommandGenericHID.hpp" -namespace frc2 { +namespace wpi::cmd { /** - * A version of {@link frc::XboxController} with {@link Trigger} factories for + * A version of {@link wpi::XboxController} with {@link Trigger} factories for * command-based. * - * @see frc::XboxController + * @see wpi::XboxController */ class CommandXboxController : public CommandGenericHID { public: @@ -33,7 +33,7 @@ class CommandXboxController : public CommandGenericHID { * * @return the wrapped GenericHID object */ - frc::XboxController& GetHID(); + wpi::XboxController& GetHID(); /** * Constructs a Trigger instance around the A button's @@ -44,7 +44,7 @@ class CommandXboxController : public CommandGenericHID { * @return a Trigger instance representing the A button's * digital signal attached to the given loop. */ - Trigger A(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger A(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -56,7 +56,7 @@ class CommandXboxController : public CommandGenericHID { * @return a Trigger instance representing the B button's * digital signal attached to the given loop. */ - Trigger B(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger B(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -68,7 +68,7 @@ class CommandXboxController : public CommandGenericHID { * @return a Trigger instance representing the X button's * digital signal attached to the given loop. */ - Trigger X(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger X(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -80,7 +80,7 @@ class CommandXboxController : public CommandGenericHID { * @return a Trigger instance representing the Y button's * digital signal attached to the given loop. */ - Trigger Y(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger Y(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -92,7 +92,7 @@ class CommandXboxController : public CommandGenericHID { * @return a Trigger instance representing the left bumper button's * digital signal attached to the given loop. */ - Trigger LeftBumper(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger LeftBumper(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -104,7 +104,7 @@ class CommandXboxController : public CommandGenericHID { * @return a Trigger instance representing the right bumper button's * digital signal attached to the given loop. */ - Trigger RightBumper(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger RightBumper(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -116,7 +116,7 @@ class CommandXboxController : public CommandGenericHID { * @return a Trigger instance representing the back button's * digital signal attached to the given loop. */ - Trigger Back(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger Back(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -128,7 +128,7 @@ class CommandXboxController : public CommandGenericHID { * @return a Trigger instance representing the start button's * digital signal attached to the given loop. */ - Trigger Start(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger Start(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -140,7 +140,7 @@ class CommandXboxController : public CommandGenericHID { * @return a Trigger instance representing the left stick button's * digital signal attached to the given loop. */ - Trigger LeftStick(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger LeftStick(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -152,7 +152,7 @@ class CommandXboxController : public CommandGenericHID { * @return a Trigger instance representing the right stick button's * digital signal attached to the given loop. */ - Trigger RightStick(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger RightStick(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -169,7 +169,7 @@ class CommandXboxController : public CommandGenericHID { * exceeds the provided threshold, attached to the given loop */ Trigger LeftTrigger(double threshold = 0.5, - frc::EventLoop* loop = CommandScheduler::GetInstance() + wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -186,7 +186,7 @@ class CommandXboxController : public CommandGenericHID { * exceeds the provided threshold, attached to the given loop */ Trigger RightTrigger(double threshold = 0.5, - frc::EventLoop* loop = CommandScheduler::GetInstance() + wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -234,6 +234,6 @@ class CommandXboxController : public CommandGenericHID { double GetRightTriggerAxis() const; private: - frc::XboxController m_hid; + wpi::XboxController m_hid; }; -} // namespace frc2 +} // namespace wpi::cmd diff --git a/commandsv2/src/main/native/cpp/frc2/command/Command.cpp b/commandsv2/src/main/native/cpp/frc2/command/Command.cpp index 9edd90a22c..11fcd2166f 100644 --- a/commandsv2/src/main/native/cpp/frc2/command/Command.cpp +++ b/commandsv2/src/main/native/cpp/frc2/command/Command.cpp @@ -13,10 +13,10 @@ #include "wpi/util/sendable/SendableBuilder.hpp" #include "wpi/util/sendable/SendableRegistry.hpp" -using namespace frc2; +using namespace wpi::cmd; Command::Command() { - wpi::SendableRegistry::Add(this, GetTypeName(*this)); + wpi::util::SendableRegistry::Add(this, GetTypeName(*this)); } Command::~Command() { @@ -32,7 +32,7 @@ void Command::Initialize() {} void Command::Execute() {} void Command::End(bool interrupted) {} -wpi::SmallSet Command::GetRequirements() const { +wpi::util::SmallSet Command::GetRequirements() const { return m_requirements; } @@ -40,7 +40,7 @@ void Command::AddRequirements(Requirements requirements) { m_requirements.insert(requirements.begin(), requirements.end()); } -void Command::AddRequirements(wpi::SmallSet requirements) { +void Command::AddRequirements(wpi::util::SmallSet requirements) { m_requirements.insert(requirements.begin(), requirements.end()); } @@ -49,22 +49,22 @@ void Command::AddRequirements(Subsystem* requirement) { } void Command::SetName(std::string_view name) { - wpi::SendableRegistry::SetName(this, name); + wpi::util::SendableRegistry::SetName(this, name); } std::string Command::GetName() const { - return wpi::SendableRegistry::GetName(this); + return wpi::util::SendableRegistry::GetName(this); } std::string Command::GetSubsystem() const { - return wpi::SendableRegistry::GetSubsystem(this); + return wpi::util::SendableRegistry::GetSubsystem(this); } void Command::SetSubsystem(std::string_view subsystem) { - wpi::SendableRegistry::SetSubsystem(this, subsystem); + wpi::util::SendableRegistry::SetSubsystem(this, subsystem); } -CommandPtr Command::WithTimeout(units::second_t duration) && { +CommandPtr Command::WithTimeout(wpi::units::second_t duration) && { return std::move(*this).ToPtr().WithTimeout(duration); } @@ -178,7 +178,7 @@ bool Command::IsComposed() const { void Command::SetComposed(bool isComposed) { if (isComposed) { - m_previousComposition = wpi::GetStackTrace(1); + m_previousComposition = wpi::util::GetStackTrace(1); } else { m_previousComposition.reset(); } @@ -188,7 +188,7 @@ std::optional Command::GetPreviousCompositionSite() const { return m_previousComposition; } -void Command::InitSendable(wpi::SendableBuilder& builder) { +void Command::InitSendable(wpi::util::SendableBuilder& builder) { builder.SetSmartDashboardType("Command"); builder.AddStringProperty(".name", [this] { return GetName(); }, nullptr); builder.AddBooleanProperty( @@ -220,7 +220,7 @@ void Command::InitSendable(wpi::SendableBuilder& builder) { "runsWhenDisabled", [this] { return RunsWhenDisabled(); }, nullptr); } -namespace frc2 { +namespace wpi::cmd { bool RequirementsDisjoint(Command* first, Command* second) { bool disjoint = true; auto&& requirements = second->GetRequirements(); @@ -229,4 +229,4 @@ bool RequirementsDisjoint(Command* first, Command* second) { } return disjoint; } -} // namespace frc2 +} // namespace wpi::cmd diff --git a/commandsv2/src/main/native/cpp/frc2/command/CommandPtr.cpp b/commandsv2/src/main/native/cpp/frc2/command/CommandPtr.cpp index 774c173ff5..fdf9c40849 100644 --- a/commandsv2/src/main/native/cpp/frc2/command/CommandPtr.cpp +++ b/commandsv2/src/main/native/cpp/frc2/command/CommandPtr.cpp @@ -22,7 +22,7 @@ #include "wpi/commands2/WrapperCommand.hpp" #include "wpi/system/Errors.hpp" -using namespace frc2; +using namespace wpi::cmd; CommandPtr::CommandPtr(std::unique_ptr&& command) : m_ptr(std::move(command)) { @@ -32,12 +32,12 @@ CommandPtr::CommandPtr(std::unique_ptr&& command) CommandPtr::CommandPtr(CommandPtr&& rhs) { m_ptr = std::move(rhs.m_ptr); AssertValid(); - rhs.m_moveOutSite = wpi::GetStackTrace(1); + rhs.m_moveOutSite = wpi::util::GetStackTrace(1); } void CommandPtr::AssertValid() const { if (!m_ptr) { - throw FRC_MakeError(frc::err::CommandIllegalUse, + throw FRC_MakeError(wpi::err::CommandIllegalUse, "Moved-from CommandPtr object used!\nMoved out at:\n{}", m_moveOutSite); } @@ -131,7 +131,7 @@ CommandPtr CommandPtr::BeforeStarting(CommandPtr&& before) && { return std::move(*this); } -CommandPtr CommandPtr::WithTimeout(units::second_t duration) && { +CommandPtr CommandPtr::WithTimeout(wpi::units::second_t duration) && { AssertValid(); std::vector> temp; temp.emplace_back(std::move(m_ptr)); diff --git a/commandsv2/src/main/native/cpp/frc2/command/CommandScheduler.cpp b/commandsv2/src/main/native/cpp/frc2/command/CommandScheduler.cpp index 656d501dfe..36115042dc 100644 --- a/commandsv2/src/main/native/cpp/frc2/command/CommandScheduler.cpp +++ b/commandsv2/src/main/native/cpp/frc2/command/CommandScheduler.cpp @@ -24,39 +24,39 @@ #include "wpi/util/sendable/SendableBuilder.hpp" #include "wpi/util/sendable/SendableRegistry.hpp" -using namespace frc2; +using namespace wpi::cmd; class CommandScheduler::Impl { public: // A set of the currently-running commands. - wpi::SmallSet scheduledCommands; + wpi::util::SmallSet scheduledCommands; // A map from required subsystems to their requiring commands. Also used as a // set of the currently-required subsystems. - wpi::DenseMap requirements; + wpi::util::DenseMap requirements; // A map from subsystems registered with the scheduler to their default // commands. Also used as a list of currently-registered subsystems. - wpi::DenseMap> subsystems; + wpi::util::DenseMap> subsystems; - frc::EventLoop defaultButtonLoop; + wpi::EventLoop defaultButtonLoop; // The set of currently-registered buttons that will be polled every // iteration. - frc::EventLoop* activeButtonLoop{&defaultButtonLoop}; + wpi::EventLoop* activeButtonLoop{&defaultButtonLoop}; bool disabled{false}; // Lists of user-supplied actions to be executed on scheduling events for // every command. - wpi::SmallVector initActions; - wpi::SmallVector executeActions; - wpi::SmallVector interruptActions; - wpi::SmallVector finishActions; + wpi::util::SmallVector initActions; + wpi::util::SmallVector executeActions; + wpi::util::SmallVector interruptActions; + wpi::util::SmallVector finishActions; // Map of Command* -> CommandPtr for CommandPtrs transferred to the scheduler // via Schedule(CommandPtr&&). These are erased (destroyed) at the very end of // the loop cycle when the command lifecycle is complete. - wpi::DenseMap ownedCommands; + wpi::util::DenseMap ownedCommands; }; template @@ -65,15 +65,15 @@ static bool ContainsKey(const TMap& map, TKey keyToCheck) { } CommandScheduler::CommandScheduler() - : m_impl(new Impl), m_watchdog(frc::TimedRobot::kDefaultPeriod, [] { + : m_impl(new Impl), m_watchdog(wpi::TimedRobot::kDefaultPeriod, [] { std::puts("CommandScheduler loop time overrun."); }) { HAL_ReportUsage("CommandScheduler", ""); - wpi::SendableRegistry::Add(this, "Scheduler"); + wpi::util::SendableRegistry::Add(this, "Scheduler"); } CommandScheduler::~CommandScheduler() { - wpi::SendableRegistry::Remove(this); + wpi::util::SendableRegistry::Remove(this); std::unique_ptr().swap(m_impl); } @@ -82,19 +82,19 @@ CommandScheduler& CommandScheduler::GetInstance() { return scheduler; } -void CommandScheduler::SetPeriod(units::second_t period) { +void CommandScheduler::SetPeriod(wpi::units::second_t period) { m_watchdog.SetTimeout(period); } -frc::EventLoop* CommandScheduler::GetActiveButtonLoop() const { +wpi::EventLoop* CommandScheduler::GetActiveButtonLoop() const { return m_impl->activeButtonLoop; } -void CommandScheduler::SetActiveButtonLoop(frc::EventLoop* loop) { +void CommandScheduler::SetActiveButtonLoop(wpi::EventLoop* loop) { m_impl->activeButtonLoop = loop; } -frc::EventLoop* CommandScheduler::GetDefaultButtonLoop() const { +wpi::EventLoop* CommandScheduler::GetDefaultButtonLoop() const { return &(m_impl->defaultButtonLoop); } @@ -102,13 +102,13 @@ void CommandScheduler::Schedule(Command* command) { RequireUngrouped(command); if (m_impl->disabled || m_impl->scheduledCommands.contains(command) || - (frc::RobotState::IsDisabled() && !command->RunsWhenDisabled())) { + (wpi::RobotState::IsDisabled() && !command->RunsWhenDisabled())) { return; } const auto& requirements = command->GetRequirements(); - wpi::SmallVector intersection; + wpi::util::SmallVector intersection; bool isDisjoint = true; bool allInterruptible = true; @@ -171,7 +171,7 @@ void CommandScheduler::Run() { // Run the periodic method of all registered subsystems. for (auto&& subsystem : m_impl->subsystems) { subsystem.getFirst()->Periodic(); - if constexpr (frc::RobotBase::IsSimulation()) { + if constexpr (wpi::RobotBase::IsSimulation()) { subsystem.getFirst()->SimulationPeriodic(); } m_watchdog.AddEpoch(subsystem.getFirst()->GetName() + ".Periodic()"); @@ -179,14 +179,14 @@ void CommandScheduler::Run() { // Cache the active instance to avoid concurrency problems if SetActiveLoop() // is called from inside the button bindings. - frc::EventLoop* loopCache = m_impl->activeButtonLoop; + wpi::EventLoop* loopCache = m_impl->activeButtonLoop; // Poll buttons for new commands to add. loopCache->Poll(); m_watchdog.AddEpoch("buttons.Run()"); - bool isDisabled = frc::RobotState::IsDisabled(); + bool isDisabled = wpi::RobotState::IsDisabled(); // create a new set to avoid iterator invalidation. - for (Command* command : wpi::SmallSet(m_impl->scheduledCommands)) { + for (Command* command : wpi::util::SmallSet(m_impl->scheduledCommands)) { if (!IsScheduled(command)) { continue; // skip as the normal scheduledCommands was modified } @@ -284,7 +284,7 @@ void CommandScheduler::UnregisterAllSubsystems() { void CommandScheduler::SetDefaultCommand(Subsystem* subsystem, CommandPtr&& defaultCommand) { if (!defaultCommand.get()->HasRequirement(subsystem)) { - throw FRC_MakeError(frc::err::CommandIllegalUse, "{}", + throw FRC_MakeError(wpi::err::CommandIllegalUse, "{}", "Default commands must require their subsystem!"); } RequireUngrouped(defaultCommand.get()); @@ -347,7 +347,7 @@ void CommandScheduler::Cancel(std::initializer_list commands) { } void CommandScheduler::CancelAll() { - wpi::SmallVector commands; + wpi::util::SmallVector commands; for (auto&& command : m_impl->scheduledCommands) { commands.emplace_back(command); } @@ -430,7 +430,7 @@ void CommandScheduler::OnCommandFinish(Action action) { void CommandScheduler::RequireUngrouped(const Command* command) { auto stacktrace = command->GetPreviousCompositionSite(); if (stacktrace.has_value()) { - throw FRC_MakeError(frc::err::CommandIllegalUse, + throw FRC_MakeError(wpi::err::CommandIllegalUse, "Commands that have been composed may not be added to " "another composition or scheduled individually!" "\nOriginally composed at:\n{}", @@ -454,7 +454,7 @@ void CommandScheduler::RequireUngrouped( void CommandScheduler::RequireUngroupedAndUnscheduled(const Command* command) { if (IsScheduled(command)) { - throw FRC_MakeError(frc::err::CommandIllegalUse, + throw FRC_MakeError(wpi::err::CommandIllegalUse, "Commands that have been scheduled individually may " "not be added to another composition!"); } @@ -475,7 +475,7 @@ void CommandScheduler::RequireUngroupedAndUnscheduled( } } -void CommandScheduler::InitSendable(wpi::SendableBuilder& builder) { +void CommandScheduler::InitSendable(wpi::util::SendableBuilder& builder) { builder.SetSmartDashboardType("Scheduler"); builder.AddStringArrayProperty( "Names", diff --git a/commandsv2/src/main/native/cpp/frc2/command/Commands.cpp b/commandsv2/src/main/native/cpp/frc2/command/Commands.cpp index 6e82229278..f6262bbad3 100644 --- a/commandsv2/src/main/native/cpp/frc2/command/Commands.cpp +++ b/commandsv2/src/main/native/cpp/frc2/command/Commands.cpp @@ -23,7 +23,7 @@ #include "wpi/util/FunctionExtras.hpp" #include "wpi/util/deprecated.hpp" -using namespace frc2; +using namespace wpi::cmd; // Factories @@ -73,7 +73,7 @@ CommandPtr cmd::Print(std::string_view msg) { return PrintCommand(msg).ToPtr(); } -CommandPtr cmd::DeferredProxy(wpi::unique_function supplier) { +CommandPtr cmd::DeferredProxy(wpi::util::unique_function supplier) { return Defer( [supplier = std::move(supplier)]() mutable { // There is no non-owning version of AsProxy(), so use the non-owning @@ -83,13 +83,13 @@ CommandPtr cmd::DeferredProxy(wpi::unique_function supplier) { {}); } -CommandPtr cmd::DeferredProxy(wpi::unique_function supplier) { +CommandPtr cmd::DeferredProxy(wpi::util::unique_function supplier) { return Defer([supplier = std::move( supplier)]() mutable { return supplier().AsProxy(); }, {}); } -CommandPtr cmd::Wait(units::second_t duration) { +CommandPtr cmd::Wait(wpi::units::second_t duration) { return WaitCommand(duration).ToPtr(); } @@ -104,7 +104,7 @@ CommandPtr cmd::Either(CommandPtr&& onTrue, CommandPtr&& onFalse, .ToPtr(); } -CommandPtr cmd::Defer(wpi::unique_function supplier, +CommandPtr cmd::Defer(wpi::util::unique_function supplier, Requirements requirements) { return DeferredCommand(std::move(supplier), requirements).ToPtr(); } diff --git a/commandsv2/src/main/native/cpp/frc2/command/ConditionalCommand.cpp b/commandsv2/src/main/native/cpp/frc2/command/ConditionalCommand.cpp index 2679ff9ab7..587fcf4dd8 100644 --- a/commandsv2/src/main/native/cpp/frc2/command/ConditionalCommand.cpp +++ b/commandsv2/src/main/native/cpp/frc2/command/ConditionalCommand.cpp @@ -10,7 +10,7 @@ #include "wpi/util/sendable/SendableBuilder.hpp" -using namespace frc2; +using namespace wpi::cmd; ConditionalCommand::ConditionalCommand(std::unique_ptr&& onTrue, std::unique_ptr&& onFalse, @@ -69,7 +69,7 @@ Command::InterruptionBehavior ConditionalCommand::GetInterruptionBehavior() } } -void ConditionalCommand::InitSendable(wpi::SendableBuilder& builder) { +void ConditionalCommand::InitSendable(wpi::util::SendableBuilder& builder) { Command::InitSendable(builder); builder.AddStringProperty( "onTrue", [this] { return m_onTrue->GetName(); }, nullptr); diff --git a/commandsv2/src/main/native/cpp/frc2/command/DeferredCommand.cpp b/commandsv2/src/main/native/cpp/frc2/command/DeferredCommand.cpp index 93667ef6cf..c2f21e9bdf 100644 --- a/commandsv2/src/main/native/cpp/frc2/command/DeferredCommand.cpp +++ b/commandsv2/src/main/native/cpp/frc2/command/DeferredCommand.cpp @@ -9,9 +9,9 @@ #include "wpi/commands2/Commands.hpp" #include "wpi/util/sendable/SendableBuilder.hpp" -using namespace frc2; +using namespace wpi::cmd; -DeferredCommand::DeferredCommand(wpi::unique_function supplier, +DeferredCommand::DeferredCommand(wpi::util::unique_function supplier, Requirements requirements) : m_supplier{std::move(supplier)} { AddRequirements(requirements); @@ -40,7 +40,7 @@ bool DeferredCommand::IsFinished() { return m_command->IsFinished(); } -void DeferredCommand::InitSendable(wpi::SendableBuilder& builder) { +void DeferredCommand::InitSendable(wpi::util::SendableBuilder& builder) { Command::InitSendable(builder); builder.AddStringProperty( "deferred", [this] { return m_command->GetName(); }, nullptr); diff --git a/commandsv2/src/main/native/cpp/frc2/command/FunctionalCommand.cpp b/commandsv2/src/main/native/cpp/frc2/command/FunctionalCommand.cpp index 07bc61fb56..ef05311479 100644 --- a/commandsv2/src/main/native/cpp/frc2/command/FunctionalCommand.cpp +++ b/commandsv2/src/main/native/cpp/frc2/command/FunctionalCommand.cpp @@ -6,7 +6,7 @@ #include -using namespace frc2; +using namespace wpi::cmd; FunctionalCommand::FunctionalCommand(std::function onInit, std::function onExecute, diff --git a/commandsv2/src/main/native/cpp/frc2/command/InstantCommand.cpp b/commandsv2/src/main/native/cpp/frc2/command/InstantCommand.cpp index 737fa7700a..88b861e03f 100644 --- a/commandsv2/src/main/native/cpp/frc2/command/InstantCommand.cpp +++ b/commandsv2/src/main/native/cpp/frc2/command/InstantCommand.cpp @@ -6,7 +6,7 @@ #include -using namespace frc2; +using namespace wpi::cmd; InstantCommand::InstantCommand(std::function toRun, Requirements requirements) diff --git a/commandsv2/src/main/native/cpp/frc2/command/NotifierCommand.cpp b/commandsv2/src/main/native/cpp/frc2/command/NotifierCommand.cpp index a74b666dd7..d45986f3e6 100644 --- a/commandsv2/src/main/native/cpp/frc2/command/NotifierCommand.cpp +++ b/commandsv2/src/main/native/cpp/frc2/command/NotifierCommand.cpp @@ -6,10 +6,10 @@ #include -using namespace frc2; +using namespace wpi::cmd; NotifierCommand::NotifierCommand(std::function toRun, - units::second_t period, + wpi::units::second_t period, Requirements requirements) : m_toRun(toRun), m_notifier{std::move(toRun)}, m_period{period} { AddRequirements(requirements); @@ -24,7 +24,7 @@ NotifierCommand::NotifierCommand(NotifierCommand&& other) NotifierCommand::NotifierCommand(const NotifierCommand& other) : CommandHelper(other), m_toRun(other.m_toRun), - m_notifier(frc::Notifier(other.m_toRun)), + m_notifier(wpi::Notifier(other.m_toRun)), m_period(other.m_period) {} void NotifierCommand::Initialize() { diff --git a/commandsv2/src/main/native/cpp/frc2/command/ParallelCommandGroup.cpp b/commandsv2/src/main/native/cpp/frc2/command/ParallelCommandGroup.cpp index 9ad69a31da..2580c8d571 100644 --- a/commandsv2/src/main/native/cpp/frc2/command/ParallelCommandGroup.cpp +++ b/commandsv2/src/main/native/cpp/frc2/command/ParallelCommandGroup.cpp @@ -7,7 +7,7 @@ #include #include -using namespace frc2; +using namespace wpi::cmd; ParallelCommandGroup::ParallelCommandGroup( std::vector>&& commands) { @@ -69,7 +69,7 @@ void ParallelCommandGroup::AddCommands( CommandScheduler::GetInstance().RequireUngroupedAndUnscheduled(commands); if (isRunning) { - throw FRC_MakeError(frc::err::CommandIllegalUse, + throw FRC_MakeError(wpi::err::CommandIllegalUse, "Commands cannot be added to a CommandGroup " "while the group is running"); } @@ -85,7 +85,7 @@ void ParallelCommandGroup::AddCommands( } m_commands.emplace_back(std::move(command), false); } else { - throw FRC_MakeError(frc::err::CommandIllegalUse, + throw FRC_MakeError(wpi::err::CommandIllegalUse, "Multiple commands in a parallel group cannot " "require the same subsystems"); } diff --git a/commandsv2/src/main/native/cpp/frc2/command/ParallelDeadlineGroup.cpp b/commandsv2/src/main/native/cpp/frc2/command/ParallelDeadlineGroup.cpp index 9b65aff4fb..39909d95ff 100644 --- a/commandsv2/src/main/native/cpp/frc2/command/ParallelDeadlineGroup.cpp +++ b/commandsv2/src/main/native/cpp/frc2/command/ParallelDeadlineGroup.cpp @@ -10,7 +10,7 @@ #include "wpi/util/sendable/SendableBuilder.hpp" -using namespace frc2; +using namespace wpi::cmd; ParallelDeadlineGroup::ParallelDeadlineGroup( std::unique_ptr&& deadline, @@ -69,7 +69,7 @@ void ParallelDeadlineGroup::AddCommands( CommandScheduler::GetInstance().RequireUngroupedAndUnscheduled(commands); if (!m_finished) { - throw FRC_MakeError(frc::err::CommandIllegalUse, + throw FRC_MakeError(wpi::err::CommandIllegalUse, "Commands cannot be added to a CommandGroup " "while the group is running"); } @@ -85,7 +85,7 @@ void ParallelDeadlineGroup::AddCommands( } m_commands.emplace_back(std::move(command), false); } else { - throw FRC_MakeError(frc::err::CommandIllegalUse, + throw FRC_MakeError(wpi::err::CommandIllegalUse, "Multiple commands in a parallel group cannot " "require the same subsystems"); } @@ -100,7 +100,7 @@ void ParallelDeadlineGroup::SetDeadline(std::unique_ptr&& deadline) { m_runWhenDisabled &= m_deadline->RunsWhenDisabled(); } -void ParallelDeadlineGroup::InitSendable(wpi::SendableBuilder& builder) { +void ParallelDeadlineGroup::InitSendable(wpi::util::SendableBuilder& builder) { Command::InitSendable(builder); builder.AddStringProperty( diff --git a/commandsv2/src/main/native/cpp/frc2/command/ParallelRaceGroup.cpp b/commandsv2/src/main/native/cpp/frc2/command/ParallelRaceGroup.cpp index d0b273205e..0c2f28108b 100644 --- a/commandsv2/src/main/native/cpp/frc2/command/ParallelRaceGroup.cpp +++ b/commandsv2/src/main/native/cpp/frc2/command/ParallelRaceGroup.cpp @@ -7,7 +7,7 @@ #include #include -using namespace frc2; +using namespace wpi::cmd; ParallelRaceGroup::ParallelRaceGroup( std::vector>&& commands) { @@ -56,7 +56,7 @@ void ParallelRaceGroup::AddCommands( CommandScheduler::GetInstance().RequireUngroupedAndUnscheduled(commands); if (isRunning) { - throw FRC_MakeError(frc::err::CommandIllegalUse, + throw FRC_MakeError(wpi::err::CommandIllegalUse, "Commands cannot be added to a CommandGroup " "while the group is running"); } @@ -72,7 +72,7 @@ void ParallelRaceGroup::AddCommands( } m_commands.emplace_back(std::move(command)); } else { - throw FRC_MakeError(frc::err::CommandIllegalUse, + throw FRC_MakeError(wpi::err::CommandIllegalUse, "Multiple commands in a parallel group cannot " "require the same subsystems"); } diff --git a/commandsv2/src/main/native/cpp/frc2/command/PrintCommand.cpp b/commandsv2/src/main/native/cpp/frc2/command/PrintCommand.cpp index 3347f4622c..222f38aefc 100644 --- a/commandsv2/src/main/native/cpp/frc2/command/PrintCommand.cpp +++ b/commandsv2/src/main/native/cpp/frc2/command/PrintCommand.cpp @@ -8,10 +8,10 @@ #include "wpi/util/print.hpp" -using namespace frc2; +using namespace wpi::cmd; PrintCommand::PrintCommand(std::string_view message) - : CommandHelper{[str = std::string(message)] { wpi::print("{}\n", str); }, + : CommandHelper{[str = std::string(message)] { wpi::util::print("{}\n", str); }, {}} {} bool PrintCommand::RunsWhenDisabled() const { diff --git a/commandsv2/src/main/native/cpp/frc2/command/ProxyCommand.cpp b/commandsv2/src/main/native/cpp/frc2/command/ProxyCommand.cpp index 68d2c47386..e51a1633e5 100644 --- a/commandsv2/src/main/native/cpp/frc2/command/ProxyCommand.cpp +++ b/commandsv2/src/main/native/cpp/frc2/command/ProxyCommand.cpp @@ -12,13 +12,13 @@ #include "wpi/util/deprecated.hpp" #include "wpi/util/sendable/SendableBuilder.hpp" -using namespace frc2; +using namespace wpi::cmd; WPI_IGNORE_DEPRECATED -ProxyCommand::ProxyCommand(wpi::unique_function supplier) +ProxyCommand::ProxyCommand(wpi::util::unique_function supplier) : m_supplier(std::move(supplier)) {} -ProxyCommand::ProxyCommand(wpi::unique_function supplier) +ProxyCommand::ProxyCommand(wpi::util::unique_function supplier) : ProxyCommand([supplier = std::move(supplier), holder = std::optional{}]() mutable { holder = supplier(); @@ -38,7 +38,7 @@ ProxyCommand::ProxyCommand(std::unique_ptr command) { void ProxyCommand::Initialize() { m_command = m_supplier(); - frc2::CommandScheduler::GetInstance().Schedule(m_command); + wpi::cmd::CommandScheduler::GetInstance().Schedule(m_command); } void ProxyCommand::End(bool interrupted) { @@ -55,7 +55,7 @@ bool ProxyCommand::IsFinished() { return m_command == nullptr || !m_command->IsScheduled(); } -void ProxyCommand::InitSendable(wpi::SendableBuilder& builder) { +void ProxyCommand::InitSendable(wpi::util::SendableBuilder& builder) { Command::InitSendable(builder); builder.AddStringProperty( "proxied", diff --git a/commandsv2/src/main/native/cpp/frc2/command/RepeatCommand.cpp b/commandsv2/src/main/native/cpp/frc2/command/RepeatCommand.cpp index 36f2da3e34..f396b5b499 100644 --- a/commandsv2/src/main/native/cpp/frc2/command/RepeatCommand.cpp +++ b/commandsv2/src/main/native/cpp/frc2/command/RepeatCommand.cpp @@ -9,7 +9,7 @@ #include "wpi/util/sendable/SendableBuilder.hpp" -using namespace frc2; +using namespace wpi::cmd; RepeatCommand::RepeatCommand(std::unique_ptr&& command) { CommandScheduler::GetInstance().RequireUngroupedAndUnscheduled(command.get()); @@ -58,7 +58,7 @@ Command::InterruptionBehavior RepeatCommand::GetInterruptionBehavior() const { return m_command->GetInterruptionBehavior(); } -void RepeatCommand::InitSendable(wpi::SendableBuilder& builder) { +void RepeatCommand::InitSendable(wpi::util::SendableBuilder& builder) { Command::InitSendable(builder); builder.AddStringProperty( "command", [this] { return m_command->GetName(); }, nullptr); diff --git a/commandsv2/src/main/native/cpp/frc2/command/RunCommand.cpp b/commandsv2/src/main/native/cpp/frc2/command/RunCommand.cpp index 9c1b89c7f3..43f9892c08 100644 --- a/commandsv2/src/main/native/cpp/frc2/command/RunCommand.cpp +++ b/commandsv2/src/main/native/cpp/frc2/command/RunCommand.cpp @@ -6,7 +6,7 @@ #include -using namespace frc2; +using namespace wpi::cmd; RunCommand::RunCommand(std::function toRun, Requirements requirements) : CommandHelper([] {}, std::move(toRun), [](bool interrupted) {}, diff --git a/commandsv2/src/main/native/cpp/frc2/command/ScheduleCommand.cpp b/commandsv2/src/main/native/cpp/frc2/command/ScheduleCommand.cpp index fa6591d82b..33a9951208 100644 --- a/commandsv2/src/main/native/cpp/frc2/command/ScheduleCommand.cpp +++ b/commandsv2/src/main/native/cpp/frc2/command/ScheduleCommand.cpp @@ -4,7 +4,7 @@ #include "wpi/commands2/ScheduleCommand.hpp" -using namespace frc2; +using namespace wpi::cmd; ScheduleCommand::ScheduleCommand(std::span toSchedule) { for (auto cmd : toSchedule) { @@ -18,7 +18,7 @@ ScheduleCommand::ScheduleCommand(Command* toSchedule) { void ScheduleCommand::Initialize() { for (auto command : m_toSchedule) { - frc2::CommandScheduler::GetInstance().Schedule(command); + wpi::cmd::CommandScheduler::GetInstance().Schedule(command); } } diff --git a/commandsv2/src/main/native/cpp/frc2/command/SequentialCommandGroup.cpp b/commandsv2/src/main/native/cpp/frc2/command/SequentialCommandGroup.cpp index 751e1e5471..fdbc9c20db 100644 --- a/commandsv2/src/main/native/cpp/frc2/command/SequentialCommandGroup.cpp +++ b/commandsv2/src/main/native/cpp/frc2/command/SequentialCommandGroup.cpp @@ -9,7 +9,7 @@ #include "wpi/util/sendable/SendableBuilder.hpp" -using namespace frc2; +using namespace wpi::cmd; SequentialCommandGroup::SequentialCommandGroup( std::vector>&& commands) { @@ -68,7 +68,7 @@ void SequentialCommandGroup::AddCommands( CommandScheduler::GetInstance().RequireUngroupedAndUnscheduled(commands); if (m_currentCommandIndex != invalid_index) { - throw FRC_MakeError(frc::err::CommandIllegalUse, + throw FRC_MakeError(wpi::err::CommandIllegalUse, "Commands cannot be added to a CommandGroup " "while the group is running"); } @@ -85,7 +85,7 @@ void SequentialCommandGroup::AddCommands( } } -void SequentialCommandGroup::InitSendable(wpi::SendableBuilder& builder) { +void SequentialCommandGroup::InitSendable(wpi::util::SendableBuilder& builder) { Command::InitSendable(builder); builder.AddIntegerProperty( "index", [this] { return m_currentCommandIndex; }, nullptr); diff --git a/commandsv2/src/main/native/cpp/frc2/command/StartEndCommand.cpp b/commandsv2/src/main/native/cpp/frc2/command/StartEndCommand.cpp index 628054900c..10cfca1098 100644 --- a/commandsv2/src/main/native/cpp/frc2/command/StartEndCommand.cpp +++ b/commandsv2/src/main/native/cpp/frc2/command/StartEndCommand.cpp @@ -6,7 +6,7 @@ #include -using namespace frc2; +using namespace wpi::cmd; StartEndCommand::StartEndCommand(std::function onInit, std::function onEnd, diff --git a/commandsv2/src/main/native/cpp/frc2/command/Subsystem.cpp b/commandsv2/src/main/native/cpp/frc2/command/Subsystem.cpp index ce73da2124..e01a5e3113 100644 --- a/commandsv2/src/main/native/cpp/frc2/command/Subsystem.cpp +++ b/commandsv2/src/main/native/cpp/frc2/command/Subsystem.cpp @@ -11,7 +11,7 @@ #include "wpi/commands2/Commands.hpp" #include "wpi/util/Demangle.hpp" -using namespace frc2; +using namespace wpi::cmd; Subsystem::~Subsystem() { CommandScheduler::GetInstance().UnregisterSubsystem(this); } @@ -21,7 +21,7 @@ void Subsystem::Periodic() {} void Subsystem::SimulationPeriodic() {} std::string Subsystem::GetName() const { - return wpi::GetTypeName(*this); + return wpi::util::GetTypeName(*this); } void Subsystem::SetDefaultCommand(CommandPtr&& defaultCommand) { @@ -72,6 +72,6 @@ CommandPtr Subsystem::StartRun(std::function start, return cmd::StartRun(std::move(start), std::move(run), {this}); } -CommandPtr Subsystem::Defer(wpi::unique_function supplier) { +CommandPtr Subsystem::Defer(wpi::util::unique_function supplier) { return cmd::Defer(std::move(supplier), {this}); } diff --git a/commandsv2/src/main/native/cpp/frc2/command/SubsystemBase.cpp b/commandsv2/src/main/native/cpp/frc2/command/SubsystemBase.cpp index 81dcb3758c..f56a249b0f 100644 --- a/commandsv2/src/main/native/cpp/frc2/command/SubsystemBase.cpp +++ b/commandsv2/src/main/native/cpp/frc2/command/SubsystemBase.cpp @@ -11,19 +11,19 @@ #include "wpi/util/sendable/SendableBuilder.hpp" #include "wpi/util/sendable/SendableRegistry.hpp" -using namespace frc2; +using namespace wpi::cmd; SubsystemBase::SubsystemBase() { - wpi::SendableRegistry::Add(this, GetTypeName(*this)); + wpi::util::SendableRegistry::Add(this, GetTypeName(*this)); CommandScheduler::GetInstance().RegisterSubsystem({this}); } SubsystemBase::SubsystemBase(std::string_view name) { - wpi::SendableRegistry::Add(this, name); + wpi::util::SendableRegistry::Add(this, name); CommandScheduler::GetInstance().RegisterSubsystem({this}); } -void SubsystemBase::InitSendable(wpi::SendableBuilder& builder) { +void SubsystemBase::InitSendable(wpi::util::SendableBuilder& builder) { builder.SetSmartDashboardType("Subsystem"); builder.AddBooleanProperty( ".hasDefault", [this] { return GetDefaultCommand() != nullptr; }, @@ -54,21 +54,21 @@ void SubsystemBase::InitSendable(wpi::SendableBuilder& builder) { } std::string SubsystemBase::GetName() const { - return wpi::SendableRegistry::GetName(this); + return wpi::util::SendableRegistry::GetName(this); } void SubsystemBase::SetName(std::string_view name) { - wpi::SendableRegistry::SetName(this, name); + wpi::util::SendableRegistry::SetName(this, name); } std::string SubsystemBase::GetSubsystem() const { - return wpi::SendableRegistry::GetSubsystem(this); + return wpi::util::SendableRegistry::GetSubsystem(this); } void SubsystemBase::SetSubsystem(std::string_view name) { - wpi::SendableRegistry::SetSubsystem(this, name); + wpi::util::SendableRegistry::SetSubsystem(this, name); } -void SubsystemBase::AddChild(std::string name, wpi::Sendable* child) { - wpi::SendableRegistry::Add(child, GetSubsystem(), name); +void SubsystemBase::AddChild(std::string name, wpi::util::Sendable* child) { + wpi::util::SendableRegistry::Add(child, GetSubsystem(), name); } diff --git a/commandsv2/src/main/native/cpp/frc2/command/WaitCommand.cpp b/commandsv2/src/main/native/cpp/frc2/command/WaitCommand.cpp index 71d1a7196a..849f917652 100644 --- a/commandsv2/src/main/native/cpp/frc2/command/WaitCommand.cpp +++ b/commandsv2/src/main/native/cpp/frc2/command/WaitCommand.cpp @@ -8,9 +8,9 @@ #include "wpi/util/sendable/SendableBuilder.hpp" -using namespace frc2; +using namespace wpi::cmd; -WaitCommand::WaitCommand(units::second_t duration) : m_duration{duration} { +WaitCommand::WaitCommand(wpi::units::second_t duration) : m_duration{duration} { SetName(fmt::format("{}: {}", GetName(), duration)); } @@ -30,7 +30,7 @@ bool WaitCommand::RunsWhenDisabled() const { return true; } -void WaitCommand::InitSendable(wpi::SendableBuilder& builder) { +void WaitCommand::InitSendable(wpi::util::SendableBuilder& builder) { Command::InitSendable(builder); builder.AddDoubleProperty( "duration", [this] { return m_duration.value(); }, nullptr); diff --git a/commandsv2/src/main/native/cpp/frc2/command/WaitUntilCommand.cpp b/commandsv2/src/main/native/cpp/frc2/command/WaitUntilCommand.cpp index f4a46fddb5..3fe635535b 100644 --- a/commandsv2/src/main/native/cpp/frc2/command/WaitUntilCommand.cpp +++ b/commandsv2/src/main/native/cpp/frc2/command/WaitUntilCommand.cpp @@ -8,13 +8,13 @@ #include "wpi/system/Timer.hpp" -using namespace frc2; +using namespace wpi::cmd; WaitUntilCommand::WaitUntilCommand(std::function condition) : m_condition{std::move(condition)} {} -WaitUntilCommand::WaitUntilCommand(units::second_t time) - : m_condition{[=] { return frc::Timer::GetMatchTime() - time > 0_s; }} {} +WaitUntilCommand::WaitUntilCommand(wpi::units::second_t time) + : m_condition{[=] { return wpi::Timer::GetMatchTime() - time > 0_s; }} {} bool WaitUntilCommand::IsFinished() { return m_condition(); diff --git a/commandsv2/src/main/native/cpp/frc2/command/WrapperCommand.cpp b/commandsv2/src/main/native/cpp/frc2/command/WrapperCommand.cpp index 723d738054..286ca8084b 100644 --- a/commandsv2/src/main/native/cpp/frc2/command/WrapperCommand.cpp +++ b/commandsv2/src/main/native/cpp/frc2/command/WrapperCommand.cpp @@ -8,7 +8,7 @@ #include "wpi/commands2/Command.hpp" -using namespace frc2; +using namespace wpi::cmd; WrapperCommand::WrapperCommand(std::unique_ptr&& command) { CommandScheduler::GetInstance().RequireUngroupedAndUnscheduled(command.get()); @@ -42,6 +42,6 @@ Command::InterruptionBehavior WrapperCommand::GetInterruptionBehavior() const { return m_command->GetInterruptionBehavior(); } -wpi::SmallSet WrapperCommand::GetRequirements() const { +wpi::util::SmallSet WrapperCommand::GetRequirements() const { return m_command->GetRequirements(); } diff --git a/commandsv2/src/main/native/cpp/frc2/command/button/CommandGamepad.cpp b/commandsv2/src/main/native/cpp/frc2/command/button/CommandGamepad.cpp index d5a5e317b9..c1de22fd99 100644 --- a/commandsv2/src/main/native/cpp/frc2/command/button/CommandGamepad.cpp +++ b/commandsv2/src/main/native/cpp/frc2/command/button/CommandGamepad.cpp @@ -4,128 +4,128 @@ #include "wpi/commands2/button/CommandGamepad.hpp" -using namespace frc2; +using namespace wpi::cmd; CommandGamepad::CommandGamepad(int port) - : CommandGenericHID(port), m_hid{frc::Gamepad(port)} {} + : CommandGenericHID(port), m_hid{wpi::Gamepad(port)} {} -frc::Gamepad& CommandGamepad::GetHID() { +wpi::Gamepad& CommandGamepad::GetHID() { return m_hid; } -Trigger CommandGamepad::SouthFace(frc::EventLoop* loop) const { - return Button(frc::Gamepad::Button::kSouthFace, loop); +Trigger CommandGamepad::SouthFace(wpi::EventLoop* loop) const { + return Button(wpi::Gamepad::Button::kSouthFace, loop); } -Trigger CommandGamepad::EastFace(frc::EventLoop* loop) const { - return Button(frc::Gamepad::Button::kEastFace, loop); +Trigger CommandGamepad::EastFace(wpi::EventLoop* loop) const { + return Button(wpi::Gamepad::Button::kEastFace, loop); } -Trigger CommandGamepad::WestFace(frc::EventLoop* loop) const { - return Button(frc::Gamepad::Button::kWestFace, loop); +Trigger CommandGamepad::WestFace(wpi::EventLoop* loop) const { + return Button(wpi::Gamepad::Button::kWestFace, loop); } -Trigger CommandGamepad::NorthFace(frc::EventLoop* loop) const { - return Button(frc::Gamepad::Button::kNorthFace, loop); +Trigger CommandGamepad::NorthFace(wpi::EventLoop* loop) const { + return Button(wpi::Gamepad::Button::kNorthFace, loop); } -Trigger CommandGamepad::Back(frc::EventLoop* loop) const { - return Button(frc::Gamepad::Button::kBack, loop); +Trigger CommandGamepad::Back(wpi::EventLoop* loop) const { + return Button(wpi::Gamepad::Button::kBack, loop); } -Trigger CommandGamepad::Guide(frc::EventLoop* loop) const { - return Button(frc::Gamepad::Button::kGuide, loop); +Trigger CommandGamepad::Guide(wpi::EventLoop* loop) const { + return Button(wpi::Gamepad::Button::kGuide, loop); } -Trigger CommandGamepad::Start(frc::EventLoop* loop) const { - return Button(frc::Gamepad::Button::kStart, loop); +Trigger CommandGamepad::Start(wpi::EventLoop* loop) const { + return Button(wpi::Gamepad::Button::kStart, loop); } -Trigger CommandGamepad::LeftStick(frc::EventLoop* loop) const { - return Button(frc::Gamepad::Button::kLeftStick, loop); +Trigger CommandGamepad::LeftStick(wpi::EventLoop* loop) const { + return Button(wpi::Gamepad::Button::kLeftStick, loop); } -Trigger CommandGamepad::RightStick(frc::EventLoop* loop) const { - return Button(frc::Gamepad::Button::kRightStick, loop); +Trigger CommandGamepad::RightStick(wpi::EventLoop* loop) const { + return Button(wpi::Gamepad::Button::kRightStick, loop); } -Trigger CommandGamepad::LeftShoulder(frc::EventLoop* loop) const { - return Button(frc::Gamepad::Button::kLeftShoulder, loop); +Trigger CommandGamepad::LeftShoulder(wpi::EventLoop* loop) const { + return Button(wpi::Gamepad::Button::kLeftShoulder, loop); } -Trigger CommandGamepad::RightShoulder(frc::EventLoop* loop) const { - return Button(frc::Gamepad::Button::kRightShoulder, loop); +Trigger CommandGamepad::RightShoulder(wpi::EventLoop* loop) const { + return Button(wpi::Gamepad::Button::kRightShoulder, loop); } -Trigger CommandGamepad::DpadUp(frc::EventLoop* loop) const { - return Button(frc::Gamepad::Button::kDpadUp, loop); +Trigger CommandGamepad::DpadUp(wpi::EventLoop* loop) const { + return Button(wpi::Gamepad::Button::kDpadUp, loop); } -Trigger CommandGamepad::DpadDown(frc::EventLoop* loop) const { - return Button(frc::Gamepad::Button::kDpadDown, loop); +Trigger CommandGamepad::DpadDown(wpi::EventLoop* loop) const { + return Button(wpi::Gamepad::Button::kDpadDown, loop); } -Trigger CommandGamepad::DpadLeft(frc::EventLoop* loop) const { - return Button(frc::Gamepad::Button::kDpadLeft, loop); +Trigger CommandGamepad::DpadLeft(wpi::EventLoop* loop) const { + return Button(wpi::Gamepad::Button::kDpadLeft, loop); } -Trigger CommandGamepad::DpadRight(frc::EventLoop* loop) const { - return Button(frc::Gamepad::Button::kDpadRight, loop); +Trigger CommandGamepad::DpadRight(wpi::EventLoop* loop) const { + return Button(wpi::Gamepad::Button::kDpadRight, loop); } -Trigger CommandGamepad::Misc1(frc::EventLoop* loop) const { - return Button(frc::Gamepad::Button::kMisc1, loop); +Trigger CommandGamepad::Misc1(wpi::EventLoop* loop) const { + return Button(wpi::Gamepad::Button::kMisc1, loop); } -Trigger CommandGamepad::RightPaddle1(frc::EventLoop* loop) const { - return Button(frc::Gamepad::Button::kRightPaddle1, loop); +Trigger CommandGamepad::RightPaddle1(wpi::EventLoop* loop) const { + return Button(wpi::Gamepad::Button::kRightPaddle1, loop); } -Trigger CommandGamepad::LeftPaddle1(frc::EventLoop* loop) const { - return Button(frc::Gamepad::Button::kLeftPaddle1, loop); +Trigger CommandGamepad::LeftPaddle1(wpi::EventLoop* loop) const { + return Button(wpi::Gamepad::Button::kLeftPaddle1, loop); } -Trigger CommandGamepad::RightPaddle2(frc::EventLoop* loop) const { - return Button(frc::Gamepad::Button::kRightPaddle2, loop); +Trigger CommandGamepad::RightPaddle2(wpi::EventLoop* loop) const { + return Button(wpi::Gamepad::Button::kRightPaddle2, loop); } -Trigger CommandGamepad::LeftPaddle2(frc::EventLoop* loop) const { - return Button(frc::Gamepad::Button::kLeftPaddle2, loop); +Trigger CommandGamepad::LeftPaddle2(wpi::EventLoop* loop) const { + return Button(wpi::Gamepad::Button::kLeftPaddle2, loop); } -Trigger CommandGamepad::Touchpad(frc::EventLoop* loop) const { - return Button(frc::Gamepad::Button::kTouchpad, loop); +Trigger CommandGamepad::Touchpad(wpi::EventLoop* loop) const { + return Button(wpi::Gamepad::Button::kTouchpad, loop); } -Trigger CommandGamepad::Misc2(frc::EventLoop* loop) const { - return Button(frc::Gamepad::Button::kMisc2, loop); +Trigger CommandGamepad::Misc2(wpi::EventLoop* loop) const { + return Button(wpi::Gamepad::Button::kMisc2, loop); } -Trigger CommandGamepad::Misc3(frc::EventLoop* loop) const { - return Button(frc::Gamepad::Button::kMisc3, loop); +Trigger CommandGamepad::Misc3(wpi::EventLoop* loop) const { + return Button(wpi::Gamepad::Button::kMisc3, loop); } -Trigger CommandGamepad::Misc4(frc::EventLoop* loop) const { - return Button(frc::Gamepad::Button::kMisc4, loop); +Trigger CommandGamepad::Misc4(wpi::EventLoop* loop) const { + return Button(wpi::Gamepad::Button::kMisc4, loop); } -Trigger CommandGamepad::Misc5(frc::EventLoop* loop) const { - return Button(frc::Gamepad::Button::kMisc5, loop); +Trigger CommandGamepad::Misc5(wpi::EventLoop* loop) const { + return Button(wpi::Gamepad::Button::kMisc5, loop); } -Trigger CommandGamepad::Misc6(frc::EventLoop* loop) const { - return Button(frc::Gamepad::Button::kMisc6, loop); +Trigger CommandGamepad::Misc6(wpi::EventLoop* loop) const { + return Button(wpi::Gamepad::Button::kMisc6, loop); } Trigger CommandGamepad::LeftTrigger(double threshold, - frc::EventLoop* loop) const { + wpi::EventLoop* loop) const { return Trigger(loop, [this, threshold] { return m_hid.GetLeftTriggerAxis() > threshold; }); } Trigger CommandGamepad::RightTrigger(double threshold, - frc::EventLoop* loop) const { + wpi::EventLoop* loop) const { return Trigger(loop, [this, threshold] { return m_hid.GetRightTriggerAxis() > threshold; }); diff --git a/commandsv2/src/main/native/cpp/frc2/command/button/CommandGenericHID.cpp b/commandsv2/src/main/native/cpp/frc2/command/button/CommandGenericHID.cpp index 65040ea11d..aecb68dfc9 100644 --- a/commandsv2/src/main/native/cpp/frc2/command/button/CommandGenericHID.cpp +++ b/commandsv2/src/main/native/cpp/frc2/command/button/CommandGenericHID.cpp @@ -4,87 +4,87 @@ #include "wpi/commands2/button/CommandGenericHID.hpp" -using namespace frc2; +using namespace wpi::cmd; CommandGenericHID::CommandGenericHID(int port) : m_hid{port} {} -frc::GenericHID& CommandGenericHID::GetHID() { +wpi::GenericHID& CommandGenericHID::GetHID() { return m_hid; } -Trigger CommandGenericHID::Button(int button, frc::EventLoop* loop) const { +Trigger CommandGenericHID::Button(int button, wpi::EventLoop* loop) const { return Trigger(loop, [this, button] { return m_hid.GetRawButton(button); }); } -Trigger CommandGenericHID::POV(frc::DriverStation::POVDirection angle, - frc::EventLoop* loop) const { +Trigger CommandGenericHID::POV(wpi::DriverStation::POVDirection angle, + wpi::EventLoop* loop) const { return POV(0, angle, loop); } -Trigger CommandGenericHID::POV(int pov, frc::DriverStation::POVDirection angle, - frc::EventLoop* loop) const { +Trigger CommandGenericHID::POV(int pov, wpi::DriverStation::POVDirection angle, + wpi::EventLoop* loop) const { return Trigger(loop, [this, pov, angle] { return m_hid.GetPOV(pov) == angle; }); } -Trigger CommandGenericHID::POVUp(frc::EventLoop* loop) const { - return POV(frc::DriverStation::POVDirection::kUp, loop); +Trigger CommandGenericHID::POVUp(wpi::EventLoop* loop) const { + return POV(wpi::DriverStation::POVDirection::kUp, loop); } -Trigger CommandGenericHID::POVUpRight(frc::EventLoop* loop) const { - return POV(frc::DriverStation::POVDirection::kUpRight, loop); +Trigger CommandGenericHID::POVUpRight(wpi::EventLoop* loop) const { + return POV(wpi::DriverStation::POVDirection::kUpRight, loop); } -Trigger CommandGenericHID::POVRight(frc::EventLoop* loop) const { - return POV(frc::DriverStation::POVDirection::kRight, loop); +Trigger CommandGenericHID::POVRight(wpi::EventLoop* loop) const { + return POV(wpi::DriverStation::POVDirection::kRight, loop); } -Trigger CommandGenericHID::POVDownRight(frc::EventLoop* loop) const { - return POV(frc::DriverStation::POVDirection::kDownRight, loop); +Trigger CommandGenericHID::POVDownRight(wpi::EventLoop* loop) const { + return POV(wpi::DriverStation::POVDirection::kDownRight, loop); } -Trigger CommandGenericHID::POVDown(frc::EventLoop* loop) const { - return POV(frc::DriverStation::POVDirection::kDown, loop); +Trigger CommandGenericHID::POVDown(wpi::EventLoop* loop) const { + return POV(wpi::DriverStation::POVDirection::kDown, loop); } -Trigger CommandGenericHID::POVDownLeft(frc::EventLoop* loop) const { - return POV(frc::DriverStation::POVDirection::kDownLeft, loop); +Trigger CommandGenericHID::POVDownLeft(wpi::EventLoop* loop) const { + return POV(wpi::DriverStation::POVDirection::kDownLeft, loop); } -Trigger CommandGenericHID::POVLeft(frc::EventLoop* loop) const { - return POV(frc::DriverStation::POVDirection::kLeft, loop); +Trigger CommandGenericHID::POVLeft(wpi::EventLoop* loop) const { + return POV(wpi::DriverStation::POVDirection::kLeft, loop); } -Trigger CommandGenericHID::POVUpLeft(frc::EventLoop* loop) const { - return POV(frc::DriverStation::POVDirection::kUpLeft, loop); +Trigger CommandGenericHID::POVUpLeft(wpi::EventLoop* loop) const { + return POV(wpi::DriverStation::POVDirection::kUpLeft, loop); } -Trigger CommandGenericHID::POVCenter(frc::EventLoop* loop) const { - return POV(frc::DriverStation::POVDirection::kCenter, loop); +Trigger CommandGenericHID::POVCenter(wpi::EventLoop* loop) const { + return POV(wpi::DriverStation::POVDirection::kCenter, loop); } Trigger CommandGenericHID::AxisLessThan(int axis, double threshold, - frc::EventLoop* loop) const { + wpi::EventLoop* loop) const { return Trigger(loop, [this, axis, threshold]() { return m_hid.GetRawAxis(axis) < threshold; }); } Trigger CommandGenericHID::AxisGreaterThan(int axis, double threshold, - frc::EventLoop* loop) const { + wpi::EventLoop* loop) const { return Trigger(loop, [this, axis, threshold]() { return m_hid.GetRawAxis(axis) > threshold; }); } Trigger CommandGenericHID::AxisMagnitudeGreaterThan( - int axis, double threshold, frc::EventLoop* loop) const { + int axis, double threshold, wpi::EventLoop* loop) const { return Trigger(loop, [this, axis, threshold]() { return std::abs(m_hid.GetRawAxis(axis)) > threshold; }); } -void CommandGenericHID::SetRumble(frc::GenericHID::RumbleType type, +void CommandGenericHID::SetRumble(wpi::GenericHID::RumbleType type, double value) { m_hid.SetRumble(type, value); } diff --git a/commandsv2/src/main/native/cpp/frc2/command/button/CommandJoystick.cpp b/commandsv2/src/main/native/cpp/frc2/command/button/CommandJoystick.cpp index 324485e5ef..ea706b3fa2 100644 --- a/commandsv2/src/main/native/cpp/frc2/command/button/CommandJoystick.cpp +++ b/commandsv2/src/main/native/cpp/frc2/command/button/CommandJoystick.cpp @@ -4,28 +4,28 @@ #include "wpi/commands2/button/CommandJoystick.hpp" -using namespace frc2; +using namespace wpi::cmd; CommandJoystick::CommandJoystick(int port) - : CommandGenericHID(port), m_hid{frc::Joystick(port)} {} + : CommandGenericHID(port), m_hid{wpi::Joystick(port)} {} -frc::Joystick& CommandJoystick::GetHID() { +wpi::Joystick& CommandJoystick::GetHID() { return m_hid; } -Trigger CommandJoystick::Trigger(frc::EventLoop* loop) const { - return Button(frc::Joystick::ButtonType::kTriggerButton, loop); +Trigger CommandJoystick::Trigger(wpi::EventLoop* loop) const { + return Button(wpi::Joystick::ButtonType::kTriggerButton, loop); } -Trigger CommandJoystick::Top(frc::EventLoop* loop) const { - return Button(frc::Joystick::ButtonType::kTopButton, loop); +Trigger CommandJoystick::Top(wpi::EventLoop* loop) const { + return Button(wpi::Joystick::ButtonType::kTopButton, loop); } double CommandJoystick::GetMagnitude() const { return m_hid.GetMagnitude(); } -units::radian_t CommandJoystick::GetDirection() const { +wpi::units::radian_t CommandJoystick::GetDirection() const { // https://docs.wpilib.org/en/stable/docs/software/basic-programming/coordinate-system.html#joystick-and-controller-coordinate-system // A positive rotation around the X axis moves the joystick right, and a // positive rotation around the Y axis moves the joystick backward. When diff --git a/commandsv2/src/main/native/cpp/frc2/command/button/NetworkButton.cpp b/commandsv2/src/main/native/cpp/frc2/command/button/NetworkButton.cpp index d8497c6dcc..dbcb9943c9 100644 --- a/commandsv2/src/main/native/cpp/frc2/command/button/NetworkButton.cpp +++ b/commandsv2/src/main/native/cpp/frc2/command/button/NetworkButton.cpp @@ -7,23 +7,23 @@ #include #include -using namespace frc2; +using namespace wpi::cmd; -NetworkButton::NetworkButton(nt::BooleanTopic topic) +NetworkButton::NetworkButton(wpi::nt::BooleanTopic topic) : NetworkButton(topic.Subscribe(false)) {} -NetworkButton::NetworkButton(nt::BooleanSubscriber sub) - : Trigger([sub = std::make_shared(std::move(sub))] { +NetworkButton::NetworkButton(wpi::nt::BooleanSubscriber sub) + : Trigger([sub = std::make_shared(std::move(sub))] { return sub->GetTopic().GetInstance().IsConnected() && sub->Get(); }) {} -NetworkButton::NetworkButton(std::shared_ptr table, +NetworkButton::NetworkButton(std::shared_ptr table, std::string_view field) : NetworkButton(table->GetBooleanTopic(field)) {} NetworkButton::NetworkButton(std::string_view table, std::string_view field) - : NetworkButton(nt::NetworkTableInstance::GetDefault(), table, field) {} + : NetworkButton(wpi::nt::NetworkTableInstance::GetDefault(), table, field) {} -NetworkButton::NetworkButton(nt::NetworkTableInstance inst, +NetworkButton::NetworkButton(wpi::nt::NetworkTableInstance inst, std::string_view table, std::string_view field) : NetworkButton(inst.GetTable(table), field) {} diff --git a/commandsv2/src/main/native/cpp/frc2/command/button/RobotModeTriggers.cpp b/commandsv2/src/main/native/cpp/frc2/command/button/RobotModeTriggers.cpp index 2c82002bcf..486b4705d8 100644 --- a/commandsv2/src/main/native/cpp/frc2/command/button/RobotModeTriggers.cpp +++ b/commandsv2/src/main/native/cpp/frc2/command/button/RobotModeTriggers.cpp @@ -6,20 +6,20 @@ #include "wpi/driverstation/DriverStation.hpp" -using namespace frc2; +using namespace wpi::cmd; Trigger RobotModeTriggers::Autonomous() { - return Trigger{&frc::DriverStation::IsAutonomousEnabled}; + return Trigger{&wpi::DriverStation::IsAutonomousEnabled}; } Trigger RobotModeTriggers::Teleop() { - return Trigger{&frc::DriverStation::IsTeleopEnabled}; + return Trigger{&wpi::DriverStation::IsTeleopEnabled}; } Trigger RobotModeTriggers::Disabled() { - return Trigger{&frc::DriverStation::IsDisabled}; + return Trigger{&wpi::DriverStation::IsDisabled}; } Trigger RobotModeTriggers::Test() { - return Trigger{&frc::DriverStation::IsTestEnabled}; + return Trigger{&wpi::DriverStation::IsTestEnabled}; } diff --git a/commandsv2/src/main/native/cpp/frc2/command/button/Trigger.cpp b/commandsv2/src/main/native/cpp/frc2/command/button/Trigger.cpp index 07755afdbb..ba8909fd4b 100644 --- a/commandsv2/src/main/native/cpp/frc2/command/button/Trigger.cpp +++ b/commandsv2/src/main/native/cpp/frc2/command/button/Trigger.cpp @@ -10,11 +10,11 @@ #include "wpi/math/filter/Debouncer.hpp" using namespace frc; -using namespace frc2; +using namespace wpi::cmd; Trigger::Trigger(const Trigger& other) = default; -void Trigger::AddBinding(wpi::unique_function&& body) { +void Trigger::AddBinding(wpi::util::unique_function&& body) { m_loop->Bind([condition = m_condition, previous = m_condition(), body = std::move(body)]() mutable { bool current = condition(); @@ -28,7 +28,7 @@ void Trigger::AddBinding(wpi::unique_function&& body) { Trigger Trigger::OnChange(Command* command) { AddBinding([command](bool previous, bool current) { if (previous != current) { - frc2::CommandScheduler::GetInstance().Schedule(command); + wpi::cmd::CommandScheduler::GetInstance().Schedule(command); } }); return *this; @@ -37,7 +37,7 @@ Trigger Trigger::OnChange(Command* command) { Trigger Trigger::OnChange(CommandPtr&& command) { AddBinding([command = std::move(command)](bool previous, bool current) { if (previous != current) { - frc2::CommandScheduler::GetInstance().Schedule(command); + wpi::cmd::CommandScheduler::GetInstance().Schedule(command); } }); return *this; @@ -46,7 +46,7 @@ Trigger Trigger::OnChange(CommandPtr&& command) { Trigger Trigger::OnTrue(Command* command) { AddBinding([command](bool previous, bool current) { if (!previous && current) { - frc2::CommandScheduler::GetInstance().Schedule(command); + wpi::cmd::CommandScheduler::GetInstance().Schedule(command); } }); return *this; @@ -55,7 +55,7 @@ Trigger Trigger::OnTrue(Command* command) { Trigger Trigger::OnTrue(CommandPtr&& command) { AddBinding([command = std::move(command)](bool previous, bool current) { if (!previous && current) { - frc2::CommandScheduler::GetInstance().Schedule(command); + wpi::cmd::CommandScheduler::GetInstance().Schedule(command); } }); return *this; @@ -64,7 +64,7 @@ Trigger Trigger::OnTrue(CommandPtr&& command) { Trigger Trigger::OnFalse(Command* command) { AddBinding([command](bool previous, bool current) { if (previous && !current) { - frc2::CommandScheduler::GetInstance().Schedule(command); + wpi::cmd::CommandScheduler::GetInstance().Schedule(command); } }); return *this; @@ -73,7 +73,7 @@ Trigger Trigger::OnFalse(Command* command) { Trigger Trigger::OnFalse(CommandPtr&& command) { AddBinding([command = std::move(command)](bool previous, bool current) { if (previous && !current) { - frc2::CommandScheduler::GetInstance().Schedule(command); + wpi::cmd::CommandScheduler::GetInstance().Schedule(command); } }); return *this; @@ -82,7 +82,7 @@ Trigger Trigger::OnFalse(CommandPtr&& command) { Trigger Trigger::WhileTrue(Command* command) { AddBinding([command](bool previous, bool current) { if (!previous && current) { - frc2::CommandScheduler::GetInstance().Schedule(command); + wpi::cmd::CommandScheduler::GetInstance().Schedule(command); } else if (previous && !current) { command->Cancel(); } @@ -93,7 +93,7 @@ Trigger Trigger::WhileTrue(Command* command) { Trigger Trigger::WhileTrue(CommandPtr&& command) { AddBinding([command = std::move(command)](bool previous, bool current) { if (!previous && current) { - frc2::CommandScheduler::GetInstance().Schedule(command); + wpi::cmd::CommandScheduler::GetInstance().Schedule(command); } else if (previous && !current) { command.Cancel(); } @@ -104,7 +104,7 @@ Trigger Trigger::WhileTrue(CommandPtr&& command) { Trigger Trigger::WhileFalse(Command* command) { AddBinding([command](bool previous, bool current) { if (previous && !current) { - frc2::CommandScheduler::GetInstance().Schedule(command); + wpi::cmd::CommandScheduler::GetInstance().Schedule(command); } else if (!previous && current) { command->Cancel(); } @@ -115,7 +115,7 @@ Trigger Trigger::WhileFalse(Command* command) { Trigger Trigger::WhileFalse(CommandPtr&& command) { AddBinding([command = std::move(command)](bool previous, bool current) { if (!previous && current) { - frc2::CommandScheduler::GetInstance().Schedule(command); + wpi::cmd::CommandScheduler::GetInstance().Schedule(command); } else if (previous && !current) { command.Cancel(); } @@ -129,7 +129,7 @@ Trigger Trigger::ToggleOnTrue(Command* command) { if (command->IsScheduled()) { command->Cancel(); } else { - frc2::CommandScheduler::GetInstance().Schedule(command); + wpi::cmd::CommandScheduler::GetInstance().Schedule(command); } } }); @@ -142,7 +142,7 @@ Trigger Trigger::ToggleOnTrue(CommandPtr&& command) { if (command.IsScheduled()) { command.Cancel(); } else { - frc2::CommandScheduler::GetInstance().Schedule(command); + wpi::cmd::CommandScheduler::GetInstance().Schedule(command); } } }); @@ -155,7 +155,7 @@ Trigger Trigger::ToggleOnFalse(Command* command) { if (command->IsScheduled()) { command->Cancel(); } else { - frc2::CommandScheduler::GetInstance().Schedule(command); + wpi::cmd::CommandScheduler::GetInstance().Schedule(command); } } }); @@ -168,16 +168,16 @@ Trigger Trigger::ToggleOnFalse(CommandPtr&& command) { if (command.IsScheduled()) { command.Cancel(); } else { - frc2::CommandScheduler::GetInstance().Schedule(command); + wpi::cmd::CommandScheduler::GetInstance().Schedule(command); } } }); return *this; } -Trigger Trigger::Debounce(units::second_t debounceTime, - frc::Debouncer::DebounceType type) { - return Trigger(m_loop, [debouncer = frc::Debouncer(debounceTime, type), +Trigger Trigger::Debounce(wpi::units::second_t debounceTime, + wpi::math::Debouncer::DebounceType type) { + return Trigger(m_loop, [debouncer = wpi::math::Debouncer(debounceTime, type), condition = m_condition]() mutable { return debouncer.Calculate(condition()); }); diff --git a/commandsv2/src/main/native/cpp/frc2/command/sysid/SysIdRoutine.cpp b/commandsv2/src/main/native/cpp/frc2/command/sysid/SysIdRoutine.cpp index 6850d78c85..7b646843cd 100644 --- a/commandsv2/src/main/native/cpp/frc2/command/sysid/SysIdRoutine.cpp +++ b/commandsv2/src/main/native/cpp/frc2/command/sysid/SysIdRoutine.cpp @@ -6,14 +6,14 @@ #include "wpi/sysid/SysIdRoutineLog.hpp" -using namespace frc2::sysid; +using namespace wpi::cmd::sysid; -frc2::CommandPtr SysIdRoutine::Quasistatic(Direction direction) { - frc::sysid::State state; +wpi::cmd::CommandPtr SysIdRoutine::Quasistatic(Direction direction) { + wpi::sysid::State state; if (direction == Direction::kForward) { - state = frc::sysid::State::kQuasistaticForward; + state = wpi::sysid::State::kQuasistaticForward; } else { // if (direction == Direction::kReverse) { - state = frc::sysid::State::kQuasistaticReverse; + state = wpi::sysid::State::kQuasistaticReverse; } double outputSign = direction == Direction::kForward ? 1.0 : -1.0; @@ -29,21 +29,21 @@ frc2::CommandPtr SysIdRoutine::Quasistatic(Direction direction) { }) .FinallyDo([this] { m_mechanism.m_drive(0_V); - m_recordState(frc::sysid::State::kNone); + m_recordState(wpi::sysid::State::kNone); timer.Stop(); }) .WithName("sysid-" + - frc::sysid::SysIdRoutineLog::StateEnumToString(state) + + wpi::sysid::SysIdRoutineLog::StateEnumToString(state) + "-" + m_mechanism.m_name) .WithTimeout(m_config.m_timeout)); } -frc2::CommandPtr SysIdRoutine::Dynamic(Direction direction) { - frc::sysid::State state; +wpi::cmd::CommandPtr SysIdRoutine::Dynamic(Direction direction) { + wpi::sysid::State state; if (direction == Direction::kForward) { - state = frc::sysid::State::kDynamicForward; + state = wpi::sysid::State::kDynamicForward; } else { // if (direction == Direction::kReverse) { - state = frc::sysid::State::kDynamicReverse; + state = wpi::sysid::State::kDynamicReverse; } double outputSign = direction == Direction::kForward ? 1.0 : -1.0; @@ -57,10 +57,10 @@ frc2::CommandPtr SysIdRoutine::Dynamic(Direction direction) { })) .FinallyDo([this] { m_mechanism.m_drive(0_V); - m_recordState(frc::sysid::State::kNone); + m_recordState(wpi::sysid::State::kNone); }) .WithName("sysid-" + - frc::sysid::SysIdRoutineLog::StateEnumToString(state) + "-" + + wpi::sysid::SysIdRoutineLog::StateEnumToString(state) + "-" + m_mechanism.m_name) .WithTimeout(m_config.m_timeout); } diff --git a/commandsv2/src/main/native/include/wpi/commands2/Command.hpp b/commandsv2/src/main/native/include/wpi/commands2/Command.hpp index 5ff7701470..4de6c62052 100644 --- a/commandsv2/src/main/native/include/wpi/commands2/Command.hpp +++ b/commandsv2/src/main/native/include/wpi/commands2/Command.hpp @@ -17,7 +17,7 @@ #include "wpi/util/StackTrace.hpp" #include "wpi/util/sendable/Sendable.hpp" -namespace frc2 { +namespace wpi::cmd { /** * A state machine representing a complete action to be performed by the robot. @@ -37,7 +37,7 @@ namespace frc2 { * @see CommandScheduler * @see CommandHelper */ -class Command : public wpi::Sendable, public wpi::SendableHelper { +class Command : public wpi::util::Sendable, public wpi::util::SendableHelper { public: ~Command() override; @@ -87,7 +87,7 @@ class Command : public wpi::Sendable, public wpi::SendableHelper { * @return the set of subsystems that are required * @see InterruptionBehavior */ - virtual wpi::SmallSet GetRequirements() const; + virtual wpi::util::SmallSet GetRequirements() const; /** * Adds the specified Subsystem requirements to the command. @@ -121,7 +121,7 @@ class Command : public wpi::Sendable, public wpi::SendableHelper { * * @param requirements the Subsystem requirements to add */ - void AddRequirements(wpi::SmallSet requirements); + void AddRequirements(wpi::util::SmallSet requirements); /** * Adds the specified Subsystem requirement to the command. @@ -191,7 +191,7 @@ class Command : public wpi::Sendable, public wpi::SendableHelper { * @param duration the timeout duration * @return the command with the timeout added */ - CommandPtr WithTimeout(units::second_t duration) &&; + CommandPtr WithTimeout(wpi::units::second_t duration) &&; /** * Decorates this command with an interrupt condition. If the specified @@ -473,14 +473,14 @@ class Command : public wpi::Sendable, public wpi::SendableHelper { */ virtual CommandPtr ToPtr() && = 0; - void InitSendable(wpi::SendableBuilder& builder) override; + void InitSendable(wpi::util::SendableBuilder& builder) override; protected: Command(); private: /// Requirements set. - wpi::SmallSet m_requirements; + wpi::util::SmallSet m_requirements; std::optional m_previousComposition; }; @@ -493,4 +493,4 @@ class Command : public wpi::Sendable, public wpi::SendableHelper { * @return False if first and second share a requirement. */ bool RequirementsDisjoint(Command* first, Command* second); -} // namespace frc2 +} // namespace wpi::cmd diff --git a/commandsv2/src/main/native/include/wpi/commands2/CommandHelper.hpp b/commandsv2/src/main/native/include/wpi/commands2/CommandHelper.hpp index 41db01d6f2..9522a2ef2a 100644 --- a/commandsv2/src/main/native/include/wpi/commands2/CommandHelper.hpp +++ b/commandsv2/src/main/native/include/wpi/commands2/CommandHelper.hpp @@ -11,7 +11,7 @@ #include "wpi/commands2/Command.hpp" #include "wpi/commands2/CommandPtr.hpp" -namespace frc2 { +namespace wpi::cmd { /** * CRTP implementation to allow polymorphic decorator functions in Command. @@ -33,4 +33,4 @@ class CommandHelper : public Base { std::make_unique(std::move(*static_cast(this)))); } }; -} // namespace frc2 +} // namespace wpi::cmd diff --git a/commandsv2/src/main/native/include/wpi/commands2/CommandPtr.hpp b/commandsv2/src/main/native/include/wpi/commands2/CommandPtr.hpp index 3b49bef22e..4b0dfb6fc4 100644 --- a/commandsv2/src/main/native/include/wpi/commands2/CommandPtr.hpp +++ b/commandsv2/src/main/native/include/wpi/commands2/CommandPtr.hpp @@ -14,7 +14,7 @@ #include "wpi/commands2/Command.hpp" #include "wpi/commands2/Requirements.hpp" -namespace frc2 { +namespace wpi::cmd { /** * A wrapper around std::unique_ptr so commands have move-only * semantics. Commands should only be stored and passed around when held in a @@ -125,7 +125,7 @@ class [[nodiscard]] CommandPtr final { * @param duration the timeout duration * @return the command with the timeout added */ - CommandPtr WithTimeout(units::second_t duration) &&; + CommandPtr WithTimeout(wpi::units::second_t duration) &&; /** * Decorates this command with an interrupt condition. If the specified @@ -339,4 +339,4 @@ class [[nodiscard]] CommandPtr final { void AssertValid() const; }; -} // namespace frc2 +} // namespace wpi::cmd diff --git a/commandsv2/src/main/native/include/wpi/commands2/CommandScheduler.hpp b/commandsv2/src/main/native/include/wpi/commands2/CommandScheduler.hpp index 38b00dd02a..527772cef0 100644 --- a/commandsv2/src/main/native/include/wpi/commands2/CommandScheduler.hpp +++ b/commandsv2/src/main/native/include/wpi/commands2/CommandScheduler.hpp @@ -20,7 +20,7 @@ #include "wpi/util/sendable/Sendable.hpp" #include "wpi/util/sendable/SendableHelper.hpp" -namespace frc2 { +namespace wpi::cmd { class Command; class CommandPtr; class Subsystem; @@ -34,8 +34,8 @@ class Subsystem; * * This class is provided by the NewCommands VendorDep */ -class CommandScheduler final : public wpi::Sendable, - public wpi::SendableHelper { +class CommandScheduler final : public wpi::util::Sendable, + public wpi::util::SendableHelper { public: /** * Returns the Scheduler instance. @@ -56,30 +56,30 @@ class CommandScheduler final : public wpi::Sendable, * Changes the period of the loop overrun watchdog. This should be kept in * sync with the TimedRobot period. */ - void SetPeriod(units::second_t period); + void SetPeriod(wpi::units::second_t period); /** * Get the active button poll. * - * @return a reference to the current {@link frc::EventLoop} object polling + * @return a reference to the current {@link wpi::EventLoop} object polling * buttons. */ - frc::EventLoop* GetActiveButtonLoop() const; + wpi::EventLoop* GetActiveButtonLoop() const; /** * Replace the button poll with another one. * * @param loop the new button polling loop object. */ - void SetActiveButtonLoop(frc::EventLoop* loop); + void SetActiveButtonLoop(wpi::EventLoop* loop); /** * Get the default button poll. * - * @return a reference to the default {@link frc::EventLoop} object polling + * @return a reference to the default {@link wpi::EventLoop} object polling * buttons. */ - frc::EventLoop* GetDefaultButtonLoop() const; + wpi::EventLoop* GetDefaultButtonLoop() const; /** * Schedules a command for execution. Does nothing if the command is already @@ -212,7 +212,7 @@ class CommandScheduler final : public wpi::Sendable, template T> void SetDefaultCommand(Subsystem* subsystem, T&& defaultCommand) { if (!defaultCommand.HasRequirement(subsystem)) { - throw FRC_MakeError(frc::err::CommandIllegalUse, + throw FRC_MakeError(wpi::err::CommandIllegalUse, "Default commands must require their subsystem!"); } SetDefaultCommandImpl(subsystem, std::make_unique>( @@ -467,7 +467,7 @@ class CommandScheduler final : public wpi::Sendable, void RequireUngroupedAndUnscheduled( std::initializer_list commands); - void InitSendable(wpi::SendableBuilder& builder) override; + void InitSendable(wpi::util::SendableBuilder& builder) override; private: // Constructor; private as this is a singleton @@ -481,11 +481,11 @@ class CommandScheduler final : public wpi::Sendable, class Impl; std::unique_ptr m_impl; - frc::Watchdog m_watchdog; + wpi::Watchdog m_watchdog; friend class CommandTestBase; template friend class CommandTestBaseWithParam; }; -} // namespace frc2 +} // namespace wpi::cmd diff --git a/commandsv2/src/main/native/include/wpi/commands2/Commands.hpp b/commandsv2/src/main/native/include/wpi/commands2/Commands.hpp index 2186922baa..48237985fe 100644 --- a/commandsv2/src/main/native/include/wpi/commands2/Commands.hpp +++ b/commandsv2/src/main/native/include/wpi/commands2/Commands.hpp @@ -17,7 +17,7 @@ #include "wpi/commands2/SelectCommand.hpp" #include "wpi/util/deprecated.hpp" -namespace frc2 { +namespace wpi::cmd { class Subsystem; /** @@ -104,7 +104,7 @@ CommandPtr Print(std::string_view msg); * * @param duration after how long the command finishes */ -CommandPtr Wait(units::second_t duration); +CommandPtr Wait(wpi::units::second_t duration); /** * Constructs a command that does nothing, finishing once a condition becomes @@ -149,7 +149,7 @@ CommandPtr Select(std::function selector, * @param supplier the command supplier * @param requirements the set of requirements for this command */ -CommandPtr Defer(wpi::unique_function supplier, +CommandPtr Defer(wpi::util::unique_function supplier, Requirements requirements); /** @@ -159,7 +159,7 @@ CommandPtr Defer(wpi::unique_function supplier, * * @param supplier the command supplier */ -CommandPtr DeferredProxy(wpi::unique_function supplier); +CommandPtr DeferredProxy(wpi::util::unique_function supplier); /** * Constructs a command that schedules the command returned from the supplier @@ -168,7 +168,7 @@ CommandPtr DeferredProxy(wpi::unique_function supplier); * * @param supplier the command supplier */ -CommandPtr DeferredProxy(wpi::unique_function supplier); +CommandPtr DeferredProxy(wpi::util::unique_function supplier); // Command Groups namespace impl { @@ -263,4 +263,4 @@ CommandPtr Deadline(CommandPtr&& deadline, CommandPtrs&&... commands) { } // namespace cmd -} // namespace frc2 +} // namespace wpi::cmd diff --git a/commandsv2/src/main/native/include/wpi/commands2/ConditionalCommand.hpp b/commandsv2/src/main/native/include/wpi/commands2/ConditionalCommand.hpp index da091fba35..8f7048a88c 100644 --- a/commandsv2/src/main/native/include/wpi/commands2/ConditionalCommand.hpp +++ b/commandsv2/src/main/native/include/wpi/commands2/ConditionalCommand.hpp @@ -12,7 +12,7 @@ #include "wpi/commands2/Command.hpp" #include "wpi/commands2/CommandHelper.hpp" -namespace frc2 { +namespace wpi::cmd { /** * A command composition that runs one of two commands, depending on the value * of the given condition when this command is initialized. @@ -73,7 +73,7 @@ class ConditionalCommand : public CommandHelper { InterruptionBehavior GetInterruptionBehavior() const override; - void InitSendable(wpi::SendableBuilder& builder) override; + void InitSendable(wpi::util::SendableBuilder& builder) override; private: std::unique_ptr m_onTrue; @@ -82,4 +82,4 @@ class ConditionalCommand : public CommandHelper { Command* m_selectedCommand{nullptr}; bool m_runsWhenDisabled = true; }; -} // namespace frc2 +} // namespace wpi::cmd diff --git a/commandsv2/src/main/native/include/wpi/commands2/DeferredCommand.hpp b/commandsv2/src/main/native/include/wpi/commands2/DeferredCommand.hpp index ba9a4bb45e..a57a9cecf4 100644 --- a/commandsv2/src/main/native/include/wpi/commands2/DeferredCommand.hpp +++ b/commandsv2/src/main/native/include/wpi/commands2/DeferredCommand.hpp @@ -11,7 +11,7 @@ #include "wpi/commands2/Requirements.hpp" #include "wpi/util/FunctionExtras.hpp" -namespace frc2 { +namespace wpi::cmd { /** * Defers Command construction to runtime. Runs the command returned by a * supplier when this command is initialized, and ends when it ends. Useful for @@ -37,7 +37,7 @@ class DeferredCommand : public CommandHelper { * @param requirements The command requirements. * */ - DeferredCommand(wpi::unique_function supplier, + DeferredCommand(wpi::util::unique_function supplier, Requirements requirements); DeferredCommand(DeferredCommand&& other) = default; @@ -50,10 +50,10 @@ class DeferredCommand : public CommandHelper { bool IsFinished() override; - void InitSendable(wpi::SendableBuilder& builder) override; + void InitSendable(wpi::util::SendableBuilder& builder) override; private: - wpi::unique_function m_supplier; + wpi::util::unique_function m_supplier; std::unique_ptr m_command; }; -} // namespace frc2 +} // namespace wpi::cmd diff --git a/commandsv2/src/main/native/include/wpi/commands2/FunctionalCommand.hpp b/commandsv2/src/main/native/include/wpi/commands2/FunctionalCommand.hpp index 66e5252a4d..1148b71c07 100644 --- a/commandsv2/src/main/native/include/wpi/commands2/FunctionalCommand.hpp +++ b/commandsv2/src/main/native/include/wpi/commands2/FunctionalCommand.hpp @@ -10,7 +10,7 @@ #include "wpi/commands2/CommandHelper.hpp" #include "wpi/commands2/Requirements.hpp" -namespace frc2 { +namespace wpi::cmd { /** * A command that allows the user to pass in functions for each of the basic * command methods through the constructor. Useful for inline definitions of @@ -56,4 +56,4 @@ class FunctionalCommand : public CommandHelper { std::function m_onEnd; std::function m_isFinished; }; -} // namespace frc2 +} // namespace wpi::cmd diff --git a/commandsv2/src/main/native/include/wpi/commands2/InstantCommand.hpp b/commandsv2/src/main/native/include/wpi/commands2/InstantCommand.hpp index 1e9fe5a4b3..67c6fc1c51 100644 --- a/commandsv2/src/main/native/include/wpi/commands2/InstantCommand.hpp +++ b/commandsv2/src/main/native/include/wpi/commands2/InstantCommand.hpp @@ -10,7 +10,7 @@ #include "wpi/commands2/FunctionalCommand.hpp" #include "wpi/commands2/Requirements.hpp" -namespace frc2 { +namespace wpi::cmd { /** * A Command that runs instantly; it will initialize, execute once, and end on * the same iteration of the scheduler. Users can either pass in a Runnable and @@ -40,4 +40,4 @@ class InstantCommand : public CommandHelper { */ InstantCommand(); }; -} // namespace frc2 +} // namespace wpi::cmd diff --git a/commandsv2/src/main/native/include/wpi/commands2/NotifierCommand.hpp b/commandsv2/src/main/native/include/wpi/commands2/NotifierCommand.hpp index f978ba5ef7..dc5544a54c 100644 --- a/commandsv2/src/main/native/include/wpi/commands2/NotifierCommand.hpp +++ b/commandsv2/src/main/native/include/wpi/commands2/NotifierCommand.hpp @@ -12,7 +12,7 @@ #include "wpi/system/Notifier.hpp" #include "wpi/units/time.hpp" -namespace frc2 { +namespace wpi::cmd { /** * A command that starts a notifier to run the given runnable periodically in a * separate thread. Has no end condition as-is; either subclass it or use @@ -34,7 +34,7 @@ class NotifierCommand : public CommandHelper { * @param period the period at which the notifier should run * @param requirements the subsystems required by this command */ - NotifierCommand(std::function toRun, units::second_t period, + NotifierCommand(std::function toRun, wpi::units::second_t period, Requirements requirements = {}); NotifierCommand(NotifierCommand&& other); @@ -47,7 +47,7 @@ class NotifierCommand : public CommandHelper { private: std::function m_toRun; - frc::Notifier m_notifier; - units::second_t m_period; + wpi::Notifier m_notifier; + wpi::units::second_t m_period; }; -} // namespace frc2 +} // namespace wpi::cmd diff --git a/commandsv2/src/main/native/include/wpi/commands2/ParallelCommandGroup.hpp b/commandsv2/src/main/native/include/wpi/commands2/ParallelCommandGroup.hpp index 9c7316e207..35ca5c36f9 100644 --- a/commandsv2/src/main/native/include/wpi/commands2/ParallelCommandGroup.hpp +++ b/commandsv2/src/main/native/include/wpi/commands2/ParallelCommandGroup.hpp @@ -17,7 +17,7 @@ #include "wpi/commands2/CommandHelper.hpp" #include "wpi/util/DecayedDerivedFrom.hpp" -namespace frc2 { +namespace wpi::cmd { /** * A command composition that runs a set of commands in parallel, ending when * the last command ends. @@ -51,7 +51,7 @@ class ParallelCommandGroup * * @param commands the commands to include in this composition. */ - template ... Commands> + template ... Commands> explicit ParallelCommandGroup(Commands&&... commands) { AddCommands(std::forward(commands)...); } @@ -69,7 +69,7 @@ class ParallelCommandGroup * * @param commands Commands to add to the group. */ - template ... Commands> + template ... Commands> void AddCommands(Commands&&... commands) { std::vector> foo; ((void)foo.emplace_back(std::make_unique>( @@ -99,7 +99,7 @@ class ParallelCommandGroup Command::InterruptionBehavior::kCancelIncoming}; bool isRunning = false; }; -} // namespace frc2 +} // namespace wpi::cmd #ifdef _WIN32 #pragma warning(pop) diff --git a/commandsv2/src/main/native/include/wpi/commands2/ParallelDeadlineGroup.hpp b/commandsv2/src/main/native/include/wpi/commands2/ParallelDeadlineGroup.hpp index 38fa077039..132e6bb25c 100644 --- a/commandsv2/src/main/native/include/wpi/commands2/ParallelDeadlineGroup.hpp +++ b/commandsv2/src/main/native/include/wpi/commands2/ParallelDeadlineGroup.hpp @@ -17,7 +17,7 @@ #include "wpi/commands2/CommandHelper.hpp" #include "wpi/util/DecayedDerivedFrom.hpp" -namespace frc2 { +namespace wpi::cmd { /** * A command composition that runs a set of commands in parallel, ending only * when a specific command (the "deadline") ends, interrupting all other @@ -55,8 +55,8 @@ class ParallelDeadlineGroup * @param deadline the command that determines when the composition ends * @param commands the commands to be executed */ - template T, - wpi::DecayedDerivedFrom... Commands> + template T, + wpi::util::DecayedDerivedFrom... Commands> explicit ParallelDeadlineGroup(T&& deadline, Commands&&... commands) { SetDeadline(std::make_unique>(std::forward(deadline))); AddCommands(std::forward(commands)...); @@ -75,7 +75,7 @@ class ParallelDeadlineGroup * * @param commands Commands to add to the group. */ - template ... Commands> + template ... Commands> void AddCommands(Commands&&... commands) { std::vector> foo; ((void)foo.emplace_back(std::make_unique>( @@ -96,7 +96,7 @@ class ParallelDeadlineGroup Command::InterruptionBehavior GetInterruptionBehavior() const override; - void InitSendable(wpi::SendableBuilder& builder) override; + void InitSendable(wpi::util::SendableBuilder& builder) override; private: void AddCommands(std::vector>&& commands); @@ -110,7 +110,7 @@ class ParallelDeadlineGroup Command::InterruptionBehavior::kCancelIncoming}; bool m_finished{true}; }; -} // namespace frc2 +} // namespace wpi::cmd #ifdef _WIN32 #pragma warning(pop) diff --git a/commandsv2/src/main/native/include/wpi/commands2/ParallelRaceGroup.hpp b/commandsv2/src/main/native/include/wpi/commands2/ParallelRaceGroup.hpp index 39465a09b6..2564f557bc 100644 --- a/commandsv2/src/main/native/include/wpi/commands2/ParallelRaceGroup.hpp +++ b/commandsv2/src/main/native/include/wpi/commands2/ParallelRaceGroup.hpp @@ -17,7 +17,7 @@ #include "wpi/commands2/CommandHelper.hpp" #include "wpi/util/DecayedDerivedFrom.hpp" -namespace frc2 { +namespace wpi::cmd { /** * A composition that runs a set of commands in parallel, ending when any one of * the commands ends and interrupting all the others. @@ -40,7 +40,7 @@ class ParallelRaceGroup : public CommandHelper { */ explicit ParallelRaceGroup(std::vector>&& commands); - template ... Commands> + template ... Commands> explicit ParallelRaceGroup(Commands&&... commands) { AddCommands(std::forward(commands)...); } @@ -58,7 +58,7 @@ class ParallelRaceGroup : public CommandHelper { * * @param commands Commands to add to the group. */ - template ... Commands> + template ... Commands> void AddCommands(Commands&&... commands) { std::vector> foo; ((void)foo.emplace_back(std::make_unique>( @@ -89,7 +89,7 @@ class ParallelRaceGroup : public CommandHelper { bool m_finished{false}; bool isRunning = false; }; -} // namespace frc2 +} // namespace wpi::cmd #ifdef _WIN32 #pragma warning(pop) diff --git a/commandsv2/src/main/native/include/wpi/commands2/PrintCommand.hpp b/commandsv2/src/main/native/include/wpi/commands2/PrintCommand.hpp index 4ed65bf788..70079e5eac 100644 --- a/commandsv2/src/main/native/include/wpi/commands2/PrintCommand.hpp +++ b/commandsv2/src/main/native/include/wpi/commands2/PrintCommand.hpp @@ -9,7 +9,7 @@ #include "wpi/commands2/CommandHelper.hpp" #include "wpi/commands2/InstantCommand.hpp" -namespace frc2 { +namespace wpi::cmd { /** * A command that prints a string when initialized. * @@ -30,4 +30,4 @@ class PrintCommand : public CommandHelper { bool RunsWhenDisabled() const override; }; -} // namespace frc2 +} // namespace wpi::cmd diff --git a/commandsv2/src/main/native/include/wpi/commands2/ProxyCommand.hpp b/commandsv2/src/main/native/include/wpi/commands2/ProxyCommand.hpp index 7c0c8d44f4..e11fb06e56 100644 --- a/commandsv2/src/main/native/include/wpi/commands2/ProxyCommand.hpp +++ b/commandsv2/src/main/native/include/wpi/commands2/ProxyCommand.hpp @@ -11,7 +11,7 @@ #include "wpi/util/FunctionExtras.hpp" #include "wpi/util/deprecated.hpp" -namespace frc2 { +namespace wpi::cmd { /** * Schedules a given command when this command is initialized and ends when it * ends, but does not directly run it. Use this for including a command in a @@ -45,7 +45,7 @@ class ProxyCommand : public CommandHelper { */ WPI_IGNORE_DEPRECATED [[deprecated("Defer a proxy command instead.")]] - explicit ProxyCommand(wpi::unique_function supplier); + explicit ProxyCommand(wpi::util::unique_function supplier); /** * Creates a new ProxyCommand that schedules the supplied command when @@ -64,7 +64,7 @@ class ProxyCommand : public CommandHelper { * @see DeferredCommand */ [[deprecated("Defer a proxy command instead.")]] - explicit ProxyCommand(wpi::unique_function supplier); + explicit ProxyCommand(wpi::util::unique_function supplier); WPI_UNIGNORE_DEPRECATED /** @@ -94,10 +94,10 @@ class ProxyCommand : public CommandHelper { bool IsFinished() override; - void InitSendable(wpi::SendableBuilder& builder) override; + void InitSendable(wpi::util::SendableBuilder& builder) override; private: - wpi::unique_function m_supplier; + wpi::util::unique_function m_supplier; Command* m_command = nullptr; }; -} // namespace frc2 +} // namespace wpi::cmd diff --git a/commandsv2/src/main/native/include/wpi/commands2/RepeatCommand.hpp b/commandsv2/src/main/native/include/wpi/commands2/RepeatCommand.hpp index 0a77a33636..2e2e58e5b2 100644 --- a/commandsv2/src/main/native/include/wpi/commands2/RepeatCommand.hpp +++ b/commandsv2/src/main/native/include/wpi/commands2/RepeatCommand.hpp @@ -16,7 +16,7 @@ #include "wpi/commands2/Command.hpp" #include "wpi/commands2/CommandHelper.hpp" -namespace frc2 { +namespace wpi::cmd { /** * A command that runs another command repeatedly, restarting it when it ends, * until this command is interrupted. Command instances that are passed to it @@ -71,13 +71,13 @@ class RepeatCommand : public CommandHelper { Command::InterruptionBehavior GetInterruptionBehavior() const override; - void InitSendable(wpi::SendableBuilder& builder) override; + void InitSendable(wpi::util::SendableBuilder& builder) override; private: std::unique_ptr m_command; bool m_ended; }; -} // namespace frc2 +} // namespace wpi::cmd #ifdef _WIN32 #pragma warning(pop) diff --git a/commandsv2/src/main/native/include/wpi/commands2/Requirements.hpp b/commandsv2/src/main/native/include/wpi/commands2/Requirements.hpp index e4e0c3cfef..61fa1e5e3c 100644 --- a/commandsv2/src/main/native/include/wpi/commands2/Requirements.hpp +++ b/commandsv2/src/main/native/include/wpi/commands2/Requirements.hpp @@ -10,7 +10,7 @@ #include "wpi/commands2/Subsystem.hpp" -namespace frc2 { +namespace wpi::cmd { /** * Represents requirements for a command, which is a set of (pointers to) @@ -43,4 +43,4 @@ class Requirements { std::vector m_subsystems; }; -} // namespace frc2 +} // namespace wpi::cmd diff --git a/commandsv2/src/main/native/include/wpi/commands2/RunCommand.hpp b/commandsv2/src/main/native/include/wpi/commands2/RunCommand.hpp index d738b6e533..f4c4fe6848 100644 --- a/commandsv2/src/main/native/include/wpi/commands2/RunCommand.hpp +++ b/commandsv2/src/main/native/include/wpi/commands2/RunCommand.hpp @@ -10,7 +10,7 @@ #include "wpi/commands2/FunctionalCommand.hpp" #include "wpi/commands2/Requirements.hpp" -namespace frc2 { +namespace wpi::cmd { /** * A command that runs a Runnable continuously. Has no end condition as-is; * either subclass it or use Command.WithTimeout() or @@ -35,4 +35,4 @@ class RunCommand : public CommandHelper { RunCommand(const RunCommand& other) = default; }; -} // namespace frc2 +} // namespace wpi::cmd diff --git a/commandsv2/src/main/native/include/wpi/commands2/ScheduleCommand.hpp b/commandsv2/src/main/native/include/wpi/commands2/ScheduleCommand.hpp index 04ae047250..06d319810d 100644 --- a/commandsv2/src/main/native/include/wpi/commands2/ScheduleCommand.hpp +++ b/commandsv2/src/main/native/include/wpi/commands2/ScheduleCommand.hpp @@ -10,7 +10,7 @@ #include "wpi/commands2/CommandHelper.hpp" #include "wpi/util/SmallSet.hpp" -namespace frc2 { +namespace wpi::cmd { /** * Schedules the given commands when this command is initialized. Useful for * forking off from CommandGroups. Note that if run from a composition, the @@ -42,6 +42,6 @@ class ScheduleCommand : public CommandHelper { bool RunsWhenDisabled() const override; private: - wpi::SmallSet m_toSchedule; + wpi::util::SmallSet m_toSchedule; }; -} // namespace frc2 +} // namespace wpi::cmd diff --git a/commandsv2/src/main/native/include/wpi/commands2/SelectCommand.hpp b/commandsv2/src/main/native/include/wpi/commands2/SelectCommand.hpp index 7f1d5b9100..ac6ad6332d 100644 --- a/commandsv2/src/main/native/include/wpi/commands2/SelectCommand.hpp +++ b/commandsv2/src/main/native/include/wpi/commands2/SelectCommand.hpp @@ -21,7 +21,7 @@ #include "wpi/commands2/PrintCommand.hpp" #include "wpi/util/sendable/SendableBuilder.hpp" -namespace frc2 { +namespace wpi::cmd { /** * A command composition that runs one of a selection of commands using a * selector and a key to command mapping. @@ -117,7 +117,7 @@ class SelectCommand : public CommandHelper> { return m_interruptBehavior; } - void InitSendable(wpi::SendableBuilder& builder) override { + void InitSendable(wpi::util::SendableBuilder& builder) override { Command::InitSendable(builder); builder.AddStringProperty( @@ -155,7 +155,7 @@ void SelectCommand::Initialize() { m_selectedCommand->Initialize(); } -} // namespace frc2 +} // namespace wpi::cmd #ifdef _WIN32 #pragma warning(pop) diff --git a/commandsv2/src/main/native/include/wpi/commands2/SequentialCommandGroup.hpp b/commandsv2/src/main/native/include/wpi/commands2/SequentialCommandGroup.hpp index 35bf554302..25f296e0b4 100644 --- a/commandsv2/src/main/native/include/wpi/commands2/SequentialCommandGroup.hpp +++ b/commandsv2/src/main/native/include/wpi/commands2/SequentialCommandGroup.hpp @@ -18,7 +18,7 @@ #include "wpi/commands2/CommandHelper.hpp" #include "wpi/util/DecayedDerivedFrom.hpp" -namespace frc2 { +namespace wpi::cmd { const size_t invalid_index = std::numeric_limits::max(); @@ -52,7 +52,7 @@ class SequentialCommandGroup * * @param commands the commands to include in this composition. */ - template ... Commands> + template ... Commands> explicit SequentialCommandGroup(Commands&&... commands) { AddCommands(std::forward(commands)...); } @@ -70,7 +70,7 @@ class SequentialCommandGroup * * @param commands Commands to add, in order of execution. */ - template ... Commands> + template ... Commands> void AddCommands(Commands&&... commands) { std::vector> foo; ((void)foo.emplace_back(std::make_unique>( @@ -91,18 +91,18 @@ class SequentialCommandGroup Command::InterruptionBehavior GetInterruptionBehavior() const override; - void InitSendable(wpi::SendableBuilder& builder) override; + void InitSendable(wpi::util::SendableBuilder& builder) override; private: void AddCommands(std::vector>&& commands); - wpi::SmallVector, 4> m_commands; + wpi::util::SmallVector, 4> m_commands; size_t m_currentCommandIndex{invalid_index}; bool m_runWhenDisabled{true}; Command::InterruptionBehavior m_interruptBehavior{ Command::InterruptionBehavior::kCancelIncoming}; }; -} // namespace frc2 +} // namespace wpi::cmd #ifdef _WIN32 #pragma warning(pop) diff --git a/commandsv2/src/main/native/include/wpi/commands2/StartEndCommand.hpp b/commandsv2/src/main/native/include/wpi/commands2/StartEndCommand.hpp index 8a95180b7a..4738e52094 100644 --- a/commandsv2/src/main/native/include/wpi/commands2/StartEndCommand.hpp +++ b/commandsv2/src/main/native/include/wpi/commands2/StartEndCommand.hpp @@ -10,7 +10,7 @@ #include "wpi/commands2/FunctionalCommand.hpp" #include "wpi/commands2/Requirements.hpp" -namespace frc2 { +namespace wpi::cmd { /** * A command that runs a given runnable when it is initialized, and another * runnable when it ends. Useful for running and then stopping a motor, or @@ -38,4 +38,4 @@ class StartEndCommand StartEndCommand(const StartEndCommand& other) = default; }; -} // namespace frc2 +} // namespace wpi::cmd diff --git a/commandsv2/src/main/native/include/wpi/commands2/Subsystem.hpp b/commandsv2/src/main/native/include/wpi/commands2/Subsystem.hpp index 3983c6965c..8249b71210 100644 --- a/commandsv2/src/main/native/include/wpi/commands2/Subsystem.hpp +++ b/commandsv2/src/main/native/include/wpi/commands2/Subsystem.hpp @@ -12,7 +12,7 @@ #include "wpi/commands2/CommandScheduler.hpp" #include "wpi/util/FunctionExtras.hpp" -namespace frc2 { +namespace wpi::cmd { class Command; class CommandPtr; /** @@ -179,6 +179,6 @@ class Subsystem { * @param supplier the command supplier. * @return the command. */ - CommandPtr Defer(wpi::unique_function supplier); + CommandPtr Defer(wpi::util::unique_function supplier); }; -} // namespace frc2 +} // namespace wpi::cmd diff --git a/commandsv2/src/main/native/include/wpi/commands2/SubsystemBase.hpp b/commandsv2/src/main/native/include/wpi/commands2/SubsystemBase.hpp index 179faaa9b1..b9ca6af066 100644 --- a/commandsv2/src/main/native/include/wpi/commands2/SubsystemBase.hpp +++ b/commandsv2/src/main/native/include/wpi/commands2/SubsystemBase.hpp @@ -11,7 +11,7 @@ #include "wpi/util/sendable/Sendable.hpp" #include "wpi/util/sendable/SendableHelper.hpp" -namespace frc2 { +namespace wpi::cmd { /** * A base for subsystems that handles registration in the constructor, and * provides a more intuitive method for setting the default command. @@ -19,10 +19,10 @@ namespace frc2 { * This class is provided by the NewCommands VendorDep */ class SubsystemBase : public Subsystem, - public wpi::Sendable, - public wpi::SendableHelper { + public wpi::util::Sendable, + public wpi::util::SendableHelper { public: - void InitSendable(wpi::SendableBuilder& builder) override; + void InitSendable(wpi::util::SendableBuilder& builder) override; /** * Gets the name of this Subsystem. @@ -59,7 +59,7 @@ class SubsystemBase : public Subsystem, * @param name name to give child * @param child sendable */ - void AddChild(std::string name, wpi::Sendable* child); + void AddChild(std::string name, wpi::util::Sendable* child); protected: /** @@ -73,4 +73,4 @@ class SubsystemBase : public Subsystem, */ explicit SubsystemBase(std::string_view name); }; -} // namespace frc2 +} // namespace wpi::cmd diff --git a/commandsv2/src/main/native/include/wpi/commands2/WaitCommand.hpp b/commandsv2/src/main/native/include/wpi/commands2/WaitCommand.hpp index ce9435dcd7..ad09a509c0 100644 --- a/commandsv2/src/main/native/include/wpi/commands2/WaitCommand.hpp +++ b/commandsv2/src/main/native/include/wpi/commands2/WaitCommand.hpp @@ -9,7 +9,7 @@ #include "wpi/system/Timer.hpp" #include "wpi/units/time.hpp" -namespace frc2 { +namespace wpi::cmd { /** * A command that does nothing but takes a specified amount of time to finish. * @@ -23,7 +23,7 @@ class WaitCommand : public CommandHelper { * * @param duration the time to wait */ - explicit WaitCommand(units::second_t duration); + explicit WaitCommand(wpi::units::second_t duration); WaitCommand(WaitCommand&& other) = default; @@ -37,13 +37,13 @@ class WaitCommand : public CommandHelper { bool RunsWhenDisabled() const override; - void InitSendable(wpi::SendableBuilder& builder) override; + void InitSendable(wpi::util::SendableBuilder& builder) override; protected: /// The timer used for waiting. - frc::Timer m_timer; + wpi::Timer m_timer; private: - units::second_t m_duration; + wpi::units::second_t m_duration; }; -} // namespace frc2 +} // namespace wpi::cmd diff --git a/commandsv2/src/main/native/include/wpi/commands2/WaitUntilCommand.hpp b/commandsv2/src/main/native/include/wpi/commands2/WaitUntilCommand.hpp index 59cfc93f59..334751b2fe 100644 --- a/commandsv2/src/main/native/include/wpi/commands2/WaitUntilCommand.hpp +++ b/commandsv2/src/main/native/include/wpi/commands2/WaitUntilCommand.hpp @@ -10,7 +10,7 @@ #include "wpi/commands2/CommandHelper.hpp" #include "wpi/units/time.hpp" -namespace frc2 { +namespace wpi::cmd { /** * A command that does nothing but ends after a specified match time or * condition. Useful for CommandGroups. @@ -37,7 +37,7 @@ class WaitUntilCommand : public CommandHelper { * * @param time the match time after which to end, in seconds */ - explicit WaitUntilCommand(units::second_t time); + explicit WaitUntilCommand(wpi::units::second_t time); WaitUntilCommand(WaitUntilCommand&& other) = default; @@ -50,4 +50,4 @@ class WaitUntilCommand : public CommandHelper { private: std::function m_condition; }; -} // namespace frc2 +} // namespace wpi::cmd diff --git a/commandsv2/src/main/native/include/wpi/commands2/WrapperCommand.hpp b/commandsv2/src/main/native/include/wpi/commands2/WrapperCommand.hpp index 7c18710579..4b87f7f23c 100644 --- a/commandsv2/src/main/native/include/wpi/commands2/WrapperCommand.hpp +++ b/commandsv2/src/main/native/include/wpi/commands2/WrapperCommand.hpp @@ -16,7 +16,7 @@ #include "wpi/commands2/Command.hpp" #include "wpi/commands2/CommandHelper.hpp" -namespace frc2 { +namespace wpi::cmd { /** * A class used internally to wrap commands while overriding a specific method; * all other methods will call through to the wrapped command. @@ -66,13 +66,13 @@ class WrapperCommand : public CommandHelper { InterruptionBehavior GetInterruptionBehavior() const override; - wpi::SmallSet GetRequirements() const override; + wpi::util::SmallSet GetRequirements() const override; protected: /// Command being wrapped. std::unique_ptr m_command; }; -} // namespace frc2 +} // namespace wpi::cmd #ifdef _WIN32 #pragma warning(pop) diff --git a/commandsv2/src/main/native/include/wpi/commands2/button/CommandGamepad.hpp b/commandsv2/src/main/native/include/wpi/commands2/button/CommandGamepad.hpp index 5e21a3fc0f..8b2326e3fa 100644 --- a/commandsv2/src/main/native/include/wpi/commands2/button/CommandGamepad.hpp +++ b/commandsv2/src/main/native/include/wpi/commands2/button/CommandGamepad.hpp @@ -8,12 +8,12 @@ #include "wpi/commands2/button/Trigger.hpp" #include "wpi/driverstation/Gamepad.hpp" -namespace frc2 { +namespace wpi::cmd { /** - * A version of {@link frc::Gamepad} with {@link Trigger} factories for + * A version of {@link wpi::Gamepad} with {@link Trigger} factories for * command-based. * - * @see frc::Gamepad + * @see wpi::Gamepad */ class CommandGamepad : public CommandGenericHID { public: @@ -30,7 +30,7 @@ class CommandGamepad : public CommandGenericHID { * * @return the wrapped GenericHID object */ - frc::Gamepad& GetHID(); + wpi::Gamepad& GetHID(); /** * Constructs a Trigger instance around the South Face button's @@ -41,7 +41,7 @@ class CommandGamepad : public CommandGenericHID { * @return a Trigger instance representing the South Face button's * digital signal attached to the given loop. */ - Trigger SouthFace(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger SouthFace(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -53,7 +53,7 @@ class CommandGamepad : public CommandGenericHID { * @return a Trigger instance representing the East Face button's * digital signal attached to the given loop. */ - Trigger EastFace(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger EastFace(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -65,7 +65,7 @@ class CommandGamepad : public CommandGenericHID { * @return a Trigger instance representing the West Face button's * digital signal attached to the given loop. */ - Trigger WestFace(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger WestFace(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -77,7 +77,7 @@ class CommandGamepad : public CommandGenericHID { * @return a Trigger instance representing the North Face button's * digital signal attached to the given loop. */ - Trigger NorthFace(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger NorthFace(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -89,7 +89,7 @@ class CommandGamepad : public CommandGenericHID { * @return a Trigger instance representing the Back button's * digital signal attached to the given loop. */ - Trigger Back(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger Back(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -101,7 +101,7 @@ class CommandGamepad : public CommandGenericHID { * @return a Trigger instance representing the Guide button's * digital signal attached to the given loop. */ - Trigger Guide(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger Guide(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -113,7 +113,7 @@ class CommandGamepad : public CommandGenericHID { * @return a Trigger instance representing the Start button's * digital signal attached to the given loop. */ - Trigger Start(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger Start(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -125,7 +125,7 @@ class CommandGamepad : public CommandGenericHID { * @return a Trigger instance representing the left stick button's * digital signal attached to the given loop. */ - Trigger LeftStick(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger LeftStick(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -137,7 +137,7 @@ class CommandGamepad : public CommandGenericHID { * @return a Trigger instance representing the right stick button's * digital signal attached to the given loop. */ - Trigger RightStick(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger RightStick(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -150,7 +150,7 @@ class CommandGamepad : public CommandGenericHID { * digital signal attached to the given loop. */ Trigger LeftShoulder( - frc::EventLoop* loop = + wpi::EventLoop* loop = CommandScheduler::GetInstance().GetDefaultButtonLoop()) const; /** @@ -163,7 +163,7 @@ class CommandGamepad : public CommandGenericHID { * digital signal attached to the given loop. */ Trigger RightShoulder( - frc::EventLoop* loop = + wpi::EventLoop* loop = CommandScheduler::GetInstance().GetDefaultButtonLoop()) const; /** @@ -175,7 +175,7 @@ class CommandGamepad : public CommandGenericHID { * @return a Trigger instance representing the D-pad up button's * digital signal attached to the given loop. */ - Trigger DpadUp(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger DpadUp(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -187,7 +187,7 @@ class CommandGamepad : public CommandGenericHID { * @return a Trigger instance representing the D-pad down button's * digital signal attached to the given loop. */ - Trigger DpadDown(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger DpadDown(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -199,7 +199,7 @@ class CommandGamepad : public CommandGenericHID { * @return a Trigger instance representing the D-pad left button's * digital signal attached to the given loop. */ - Trigger DpadLeft(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger DpadLeft(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -211,7 +211,7 @@ class CommandGamepad : public CommandGenericHID { * @return a Trigger instance representing the D-pad right button's * digital signal attached to the given loop. */ - Trigger DpadRight(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger DpadRight(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -223,7 +223,7 @@ class CommandGamepad : public CommandGenericHID { * @return a Trigger instance representing the Miscellaneous 1 button's * digital signal attached to the given loop. */ - Trigger Misc1(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger Misc1(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -236,7 +236,7 @@ class CommandGamepad : public CommandGenericHID { * digital signal attached to the given loop. */ Trigger RightPaddle1( - frc::EventLoop* loop = + wpi::EventLoop* loop = CommandScheduler::GetInstance().GetDefaultButtonLoop()) const; /** @@ -248,7 +248,7 @@ class CommandGamepad : public CommandGenericHID { * @return a Trigger instance representing the Left Paddle 1 button's * digital signal attached to the given loop. */ - Trigger LeftPaddle1(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger LeftPaddle1(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -261,7 +261,7 @@ class CommandGamepad : public CommandGenericHID { * digital signal attached to the given loop. */ Trigger RightPaddle2( - frc::EventLoop* loop = + wpi::EventLoop* loop = CommandScheduler::GetInstance().GetDefaultButtonLoop()) const; /** @@ -273,7 +273,7 @@ class CommandGamepad : public CommandGenericHID { * @return a Trigger instance representing the Left Paddle 2 button's * digital signal attached to the given loop. */ - Trigger LeftPaddle2(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger LeftPaddle2(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -285,7 +285,7 @@ class CommandGamepad : public CommandGenericHID { * @return a Trigger instance representing the Touchpad button's * digital signal attached to the given loop. */ - Trigger Touchpad(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger Touchpad(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -297,7 +297,7 @@ class CommandGamepad : public CommandGenericHID { * @return a Trigger instance representing the Miscellaneous 2 button's * digital signal attached to the given loop. */ - Trigger Misc2(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger Misc2(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -309,7 +309,7 @@ class CommandGamepad : public CommandGenericHID { * @return a Trigger instance representing the Miscellaneous 3 button's * digital signal attached to the given loop. */ - Trigger Misc3(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger Misc3(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -321,7 +321,7 @@ class CommandGamepad : public CommandGenericHID { * @return a Trigger instance representing the Miscellaneous 4 button's * digital signal attached to the given loop. */ - Trigger Misc4(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger Misc4(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -333,7 +333,7 @@ class CommandGamepad : public CommandGenericHID { * @return a Trigger instance representing the Miscellaneous 5 button's * digital signal attached to the given loop. */ - Trigger Misc5(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger Misc5(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -345,7 +345,7 @@ class CommandGamepad : public CommandGenericHID { * @return a Trigger instance representing the Miscellaneous 6 button's * digital signal attached to the given loop. */ - Trigger Misc6(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger Misc6(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -362,7 +362,7 @@ class CommandGamepad : public CommandGenericHID { * exceeds the provided threshold, attached to the given loop */ Trigger LeftTrigger(double threshold = 0.5, - frc::EventLoop* loop = CommandScheduler::GetInstance() + wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -380,7 +380,7 @@ class CommandGamepad : public CommandGenericHID { */ Trigger RightTrigger( double threshold = 0.5, - frc::EventLoop* loop = + wpi::EventLoop* loop = CommandScheduler::GetInstance().GetDefaultButtonLoop()) const; /** @@ -428,6 +428,6 @@ class CommandGamepad : public CommandGenericHID { double GetRightTriggerAxis() const; private: - frc::Gamepad m_hid; + wpi::Gamepad m_hid; }; -} // namespace frc2 +} // namespace wpi::cmd diff --git a/commandsv2/src/main/native/include/wpi/commands2/button/CommandGenericHID.hpp b/commandsv2/src/main/native/include/wpi/commands2/button/CommandGenericHID.hpp index 0cc1846fa0..90b192b6d4 100644 --- a/commandsv2/src/main/native/include/wpi/commands2/button/CommandGenericHID.hpp +++ b/commandsv2/src/main/native/include/wpi/commands2/button/CommandGenericHID.hpp @@ -9,10 +9,10 @@ #include "wpi/driverstation/DriverStation.hpp" #include "wpi/driverstation/GenericHID.hpp" -namespace frc2 { +namespace wpi::cmd { /** - * A version of {@link frc::GenericHID} with {@link Trigger} factories for + * A version of {@link wpi::GenericHID} with {@link Trigger} factories for * command-based. * * @see GenericHID @@ -32,7 +32,7 @@ class CommandGenericHID { * * @return the wrapped GenericHID object */ - frc::GenericHID& GetHID(); + wpi::GenericHID& GetHID(); /** * Constructs an event instance around this button's digital signal. @@ -44,7 +44,7 @@ class CommandGenericHID { * to the given loop. */ Trigger Button(int button, - frc::EventLoop* loop = CommandScheduler::GetInstance() + wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -56,8 +56,8 @@ class CommandGenericHID { * @param angle POV angle. * @return a Trigger instance based around this angle of a POV on the HID. */ - Trigger POV(frc::DriverStation::POVDirection angle, - frc::EventLoop* loop = + Trigger POV(wpi::DriverStation::POVDirection angle, + wpi::EventLoop* loop = CommandScheduler::GetInstance().GetDefaultButtonLoop()) const; /** @@ -70,8 +70,8 @@ class CommandGenericHID { * @param angle POV angle. * @return a Trigger instance based around this angle of a POV on the HID. */ - Trigger POV(int pov, frc::DriverStation::POVDirection angle, - frc::EventLoop* loop = + Trigger POV(int pov, wpi::DriverStation::POVDirection angle, + wpi::EventLoop* loop = CommandScheduler::GetInstance().GetDefaultButtonLoop()) const; /** @@ -84,7 +84,7 @@ class CommandGenericHID { * @return a Trigger instance based around the up direction of a POV on the * HID. */ - Trigger POVUp(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger POVUp(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -97,7 +97,7 @@ class CommandGenericHID { * @return a Trigger instance based around the up right direction of a POV on * the HID. */ - Trigger POVUpRight(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger POVUpRight(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -110,7 +110,7 @@ class CommandGenericHID { * @return a Trigger instance based around the right direction of a POV on the * HID. */ - Trigger POVRight(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger POVRight(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -121,7 +121,7 @@ class CommandGenericHID { * on the HID. */ Trigger POVDownRight( - frc::EventLoop* loop = + wpi::EventLoop* loop = CommandScheduler::GetInstance().GetDefaultButtonLoop()) const; /** @@ -134,7 +134,7 @@ class CommandGenericHID { * @return a Trigger instance based around the down direction of a POV on * the HID. */ - Trigger POVDown(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger POVDown(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -147,7 +147,7 @@ class CommandGenericHID { * @return a Trigger instance based around the down left direction of a POV on * the HID. */ - Trigger POVDownLeft(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger POVDownLeft(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -160,7 +160,7 @@ class CommandGenericHID { * @return a Trigger instance based around the left direction of a POV on * the HID. */ - Trigger POVLeft(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger POVLeft(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -173,7 +173,7 @@ class CommandGenericHID { * @return a Trigger instance based around the up left direction of a POV on * the HID. */ - Trigger POVUpLeft(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger POVUpLeft(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -186,7 +186,7 @@ class CommandGenericHID { * @return a Trigger instance based around the center position of a POV on the * HID. */ - Trigger POVCenter(frc::EventLoop* loop = CommandScheduler::GetInstance() + Trigger POVCenter(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** @@ -204,7 +204,7 @@ class CommandGenericHID { */ Trigger AxisLessThan( int axis, double threshold, - frc::EventLoop* loop = + wpi::EventLoop* loop = CommandScheduler::GetInstance().GetDefaultButtonLoop()) const; /** @@ -222,7 +222,7 @@ class CommandGenericHID { */ Trigger AxisGreaterThan( int axis, double threshold, - frc::EventLoop* loop = + wpi::EventLoop* loop = CommandScheduler::GetInstance().GetDefaultButtonLoop()) const; /** @@ -237,7 +237,7 @@ class CommandGenericHID { */ Trigger AxisMagnitudeGreaterThan( int axis, double threshold, - frc::EventLoop* loop = + wpi::EventLoop* loop = CommandScheduler::GetInstance().GetDefaultButtonLoop()) const; /** @@ -248,7 +248,7 @@ class CommandGenericHID { * @param type Which rumble value to set * @param value The normalized value (0 to 1) to set the rumble to */ - void SetRumble(frc::GenericHID::RumbleType type, double value); + void SetRumble(wpi::GenericHID::RumbleType type, double value); /** * Get if the HID is connected. @@ -258,6 +258,6 @@ class CommandGenericHID { bool IsConnected() const; private: - frc::GenericHID m_hid; + wpi::GenericHID m_hid; }; -} // namespace frc2 +} // namespace wpi::cmd diff --git a/commandsv2/src/main/native/include/wpi/commands2/button/CommandJoystick.hpp b/commandsv2/src/main/native/include/wpi/commands2/button/CommandJoystick.hpp index e7e979e639..3c6d53f206 100644 --- a/commandsv2/src/main/native/include/wpi/commands2/button/CommandJoystick.hpp +++ b/commandsv2/src/main/native/include/wpi/commands2/button/CommandJoystick.hpp @@ -8,12 +8,12 @@ #include "wpi/commands2/button/Trigger.hpp" #include "wpi/driverstation/Joystick.hpp" -namespace frc2 { +namespace wpi::cmd { /** - * A version of {@link frc::Joystick} with {@link Trigger} factories for + * A version of {@link wpi::Joystick} with {@link Trigger} factories for * command-based. * - * @see frc::Joystick + * @see wpi::Joystick */ class CommandJoystick : public CommandGenericHID { public: @@ -30,7 +30,7 @@ class CommandJoystick : public CommandGenericHID { * * @return the wrapped GenericHID object */ - frc::Joystick& GetHID(); + wpi::Joystick& GetHID(); /** * Constructs an event instance around the trigger button's digital signal. @@ -41,7 +41,7 @@ class CommandJoystick : public CommandGenericHID { * attached to the given loop. */ class Trigger Trigger( - frc::EventLoop* loop = + wpi::EventLoop* loop = CommandScheduler::GetInstance().GetDefaultButtonLoop()) const; /** @@ -52,7 +52,7 @@ class CommandJoystick : public CommandGenericHID { * @return an event instance representing the top button's digital signal * attached to the given loop. */ - class Trigger Top(frc::EventLoop* loop = CommandScheduler::GetInstance() + class Trigger Top(wpi::EventLoop* loop = CommandScheduler::GetInstance() .GetDefaultButtonLoop()) const; /** * Get the magnitude of the vector formed by the joystick's @@ -69,9 +69,9 @@ class CommandJoystick : public CommandGenericHID { * * @return The direction of the vector. */ - units::radian_t GetDirection() const; + wpi::units::radian_t GetDirection() const; private: - frc::Joystick m_hid; + wpi::Joystick m_hid; }; -} // namespace frc2 +} // namespace wpi::cmd diff --git a/commandsv2/src/main/native/include/wpi/commands2/button/JoystickButton.hpp b/commandsv2/src/main/native/include/wpi/commands2/button/JoystickButton.hpp index dba99aef6c..5fe86fe0d2 100644 --- a/commandsv2/src/main/native/include/wpi/commands2/button/JoystickButton.hpp +++ b/commandsv2/src/main/native/include/wpi/commands2/button/JoystickButton.hpp @@ -6,7 +6,7 @@ #include "wpi/commands2/button/Trigger.hpp" #include "wpi/driverstation/GenericHID.hpp" -namespace frc2 { +namespace wpi::cmd { /** * A class used to bind command scheduling to joystick button presses. Can be * composed with other buttons with the operators in Trigger. @@ -23,9 +23,9 @@ class JoystickButton : public Trigger { * @param joystick The joystick on which the button is located. * @param buttonNumber The number of the button on the joystick. */ - explicit JoystickButton(frc::GenericHID* joystick, int buttonNumber) + explicit JoystickButton(wpi::GenericHID* joystick, int buttonNumber) : Trigger([joystick, buttonNumber] { return joystick->GetRawButton(buttonNumber); }) {} }; -} // namespace frc2 +} // namespace wpi::cmd diff --git a/commandsv2/src/main/native/include/wpi/commands2/button/NetworkButton.hpp b/commandsv2/src/main/native/include/wpi/commands2/button/NetworkButton.hpp index 6021747f04..135a9728e1 100644 --- a/commandsv2/src/main/native/include/wpi/commands2/button/NetworkButton.hpp +++ b/commandsv2/src/main/native/include/wpi/commands2/button/NetworkButton.hpp @@ -12,7 +12,7 @@ #include "wpi/nt/NetworkTable.hpp" #include "wpi/nt/NetworkTableInstance.hpp" -namespace frc2 { +namespace wpi::cmd { /** * A Button that uses a NetworkTable boolean field. * @@ -25,14 +25,14 @@ class NetworkButton : public Trigger { * * @param topic The boolean topic that contains the value. */ - explicit NetworkButton(nt::BooleanTopic topic); + explicit NetworkButton(wpi::nt::BooleanTopic topic); /** * Creates a NetworkButton that commands can be bound to. * * @param sub The boolean subscriber that provides the value. */ - explicit NetworkButton(nt::BooleanSubscriber sub); + explicit NetworkButton(wpi::nt::BooleanSubscriber sub); /** * Creates a NetworkButton that commands can be bound to. @@ -40,7 +40,7 @@ class NetworkButton : public Trigger { * @param table The table where the networktable value is located. * @param field The field that is the value. */ - NetworkButton(std::shared_ptr table, + NetworkButton(std::shared_ptr table, std::string_view field); /** @@ -58,7 +58,7 @@ class NetworkButton : public Trigger { * @param table The table where the networktable value is located. * @param field The field that is the value. */ - NetworkButton(nt::NetworkTableInstance inst, std::string_view table, + NetworkButton(wpi::nt::NetworkTableInstance inst, std::string_view table, std::string_view field); }; -} // namespace frc2 +} // namespace wpi::cmd diff --git a/commandsv2/src/main/native/include/wpi/commands2/button/POVButton.hpp b/commandsv2/src/main/native/include/wpi/commands2/button/POVButton.hpp index 3ae8f5d6a0..ad9992044c 100644 --- a/commandsv2/src/main/native/include/wpi/commands2/button/POVButton.hpp +++ b/commandsv2/src/main/native/include/wpi/commands2/button/POVButton.hpp @@ -8,7 +8,7 @@ #include "wpi/driverstation/DriverStation.hpp" #include "wpi/driverstation/GenericHID.hpp" -namespace frc2 { +namespace wpi::cmd { /** * A class used to bind command scheduling to joystick POV presses. Can be * composed with other buttons with the operators in Trigger. @@ -26,10 +26,10 @@ class POVButton : public Trigger { * @param angle The angle of the POV corresponding to a button press. * @param povNumber The number of the POV on the joystick. */ - POVButton(frc::GenericHID* joystick, frc::DriverStation::POVDirection angle, + POVButton(wpi::GenericHID* joystick, wpi::DriverStation::POVDirection angle, int povNumber = 0) : Trigger([joystick, angle, povNumber] { return joystick->GetPOV(povNumber) == angle; }) {} }; -} // namespace frc2 +} // namespace wpi::cmd diff --git a/commandsv2/src/main/native/include/wpi/commands2/button/RobotModeTriggers.hpp b/commandsv2/src/main/native/include/wpi/commands2/button/RobotModeTriggers.hpp index 19163d7aa9..6171640a4d 100644 --- a/commandsv2/src/main/native/include/wpi/commands2/button/RobotModeTriggers.hpp +++ b/commandsv2/src/main/native/include/wpi/commands2/button/RobotModeTriggers.hpp @@ -6,7 +6,7 @@ #include "wpi/commands2/button/Trigger.hpp" -namespace frc2 { +namespace wpi::cmd { /** * A class containing static Trigger factories for running callbacks when robot @@ -47,4 +47,4 @@ class RobotModeTriggers { static Trigger Test(); }; -} // namespace frc2 +} // namespace wpi::cmd diff --git a/commandsv2/src/main/native/include/wpi/commands2/button/Trigger.hpp b/commandsv2/src/main/native/include/wpi/commands2/button/Trigger.hpp index 3292003802..ac3ffe3bbf 100644 --- a/commandsv2/src/main/native/include/wpi/commands2/button/Trigger.hpp +++ b/commandsv2/src/main/native/include/wpi/commands2/button/Trigger.hpp @@ -15,7 +15,7 @@ #include "wpi/units/time.hpp" #include "wpi/util/FunctionExtras.hpp" -namespace frc2 { +namespace wpi::cmd { class Command; /** * This class provides an easy way to link commands to conditions. @@ -47,7 +47,7 @@ class Trigger { * @param loop The loop instance that polls this trigger. * @param condition the condition represented by this trigger */ - Trigger(frc::EventLoop* loop, std::function condition) + Trigger(wpi::EventLoop* loop, std::function condition) : m_loop{loop}, m_condition{std::move(condition)} {} /** @@ -279,9 +279,9 @@ class Trigger { * @param type The debounce type. * @return The debounced trigger. */ - Trigger Debounce(units::second_t debounceTime, - frc::Debouncer::DebounceType type = - frc::Debouncer::DebounceType::kRising); + Trigger Debounce(wpi::units::second_t debounceTime, + wpi::math::Debouncer::DebounceType type = + wpi::math::Debouncer::DebounceType::kRising); /** * Returns the current state of this trigger. @@ -296,9 +296,9 @@ class Trigger { * * @param body The body of the binding to add. */ - void AddBinding(wpi::unique_function&& body); + void AddBinding(wpi::util::unique_function&& body); - frc::EventLoop* m_loop; + wpi::EventLoop* m_loop; std::function m_condition; }; -} // namespace frc2 +} // namespace wpi::cmd diff --git a/commandsv2/src/main/native/include/wpi/commands2/sysid/SysIdRoutine.hpp b/commandsv2/src/main/native/include/wpi/commands2/sysid/SysIdRoutine.hpp index 049d13ff12..c555199338 100644 --- a/commandsv2/src/main/native/include/wpi/commands2/sysid/SysIdRoutine.hpp +++ b/commandsv2/src/main/native/include/wpi/commands2/sysid/SysIdRoutine.hpp @@ -14,10 +14,10 @@ #include "wpi/sysid/SysIdRoutineLog.hpp" #include "wpi/system/Timer.hpp" -namespace frc2::sysid { +namespace wpi::cmd::sysid { -using ramp_rate_t = units::unit_t< - units::compound_unit>>; +using ramp_rate_t = wpi::units::unit_t< + wpi::units::compound_unit>>; /** Hardware-independent configuration for a SysId test routine. */ class Config { @@ -26,14 +26,14 @@ class Config { ramp_rate_t m_rampRate{1_V / 1_s}; /// The step voltage output used for dynamic test routines. - units::volt_t m_stepVoltage{7_V}; + wpi::units::volt_t m_stepVoltage{7_V}; /// Safety timeout for the test routine commands. - units::second_t m_timeout{10_s}; + wpi::units::second_t m_timeout{10_s}; /// Optional handle for recording test state in a third-party logging /// solution. - std::function m_recordState; + std::function m_recordState; /** * Create a new configuration for a SysId test routine. @@ -49,9 +49,9 @@ class Config { * passed to this callback instead of logged in WPILog. */ Config(std::optional rampRate, - std::optional stepVoltage, - std::optional timeout, - std::function recordState) + std::optional stepVoltage, + std::optional timeout, + std::function recordState) : m_recordState{std::move(recordState)} { if (rampRate) { m_rampRate = rampRate.value(); @@ -69,15 +69,15 @@ class Mechanism { public: /// Sends the SysId-specified drive signal to the mechanism motors during test /// routines. - std::function m_drive; + std::function m_drive; /// Returns measured data (voltages, positions, velocities) of the mechanism /// motors during test routines. - std::function m_log; + std::function m_log; /// The subsystem containing the motor(s) that is (or are) being /// characterized. - frc2::Subsystem* m_subsystem; + wpi::cmd::Subsystem* m_subsystem; /// The name of the mechanism being tested. Will be appended to the log entry /// title for the routine's test state, e.g. "sysid-test-state-mechanism". @@ -102,11 +102,11 @@ class Mechanism { * "sysid-test-state-mechanism". Defaults to the name of the subsystem if * left null. */ - Mechanism(std::function drive, - std::function log, - frc2::Subsystem* subsystem, std::string_view name) + Mechanism(std::function drive, + std::function log, + wpi::cmd::Subsystem* subsystem, std::string_view name) : m_drive{std::move(drive)}, - m_log{log ? std::move(log) : [](frc::sysid::SysIdRoutineLog* log) {}}, + m_log{log ? std::move(log) : [](wpi::sysid::SysIdRoutineLog* log) {}}, m_subsystem{subsystem}, m_name{name} {} @@ -127,11 +127,11 @@ class Mechanism { * test commands. The subsystem's `name` will be appended to the log entry * title for the routine's test state, e.g. "sysid-test-state-subsystem". */ - Mechanism(std::function drive, - std::function log, - frc2::Subsystem* subsystem) + Mechanism(std::function drive, + std::function log, + wpi::cmd::Subsystem* subsystem) : m_drive{std::move(drive)}, - m_log{log ? std::move(log) : [](frc::sysid::SysIdRoutineLog* log) {}}, + m_log{log ? std::move(log) : [](wpi::sysid::SysIdRoutineLog* log) {}}, m_subsystem{subsystem}, m_name{m_subsystem->GetName()} {} }; @@ -167,7 +167,7 @@ enum Direction { * times in a single logfile, the user will need to select which of the tests to * use for the fit in the analysis tool. */ -class SysIdRoutine : public frc::sysid::SysIdRoutineLog { +class SysIdRoutine : public wpi::sysid::SysIdRoutineLog { public: /** * Create a new SysId characterization routine. @@ -180,18 +180,18 @@ class SysIdRoutine : public frc::sysid::SysIdRoutineLog { m_config(config), m_mechanism(mechanism), m_recordState(config.m_recordState ? config.m_recordState - : [this](frc::sysid::State state) { + : [this](wpi::sysid::State state) { this->RecordState(state); }) {} - frc2::CommandPtr Quasistatic(Direction direction); - frc2::CommandPtr Dynamic(Direction direction); + wpi::cmd::CommandPtr Quasistatic(Direction direction); + wpi::cmd::CommandPtr Dynamic(Direction direction); private: Config m_config; Mechanism m_mechanism; - units::volt_t m_outputVolts{0}; - std::function m_recordState; - frc::Timer timer; + wpi::units::volt_t m_outputVolts{0}; + std::function m_recordState; + wpi::Timer timer; }; -} // namespace frc2::sysid +} // namespace wpi::cmd::sysid diff --git a/commandsv2/src/test/native/cpp/wpi/command/AddRequirementsTest.cpp b/commandsv2/src/test/native/cpp/wpi/command/AddRequirementsTest.cpp index a4f5d4b7cd..e1fd07592d 100644 --- a/commandsv2/src/test/native/cpp/wpi/command/AddRequirementsTest.cpp +++ b/commandsv2/src/test/native/cpp/wpi/command/AddRequirementsTest.cpp @@ -7,7 +7,7 @@ #include "wpi/commands2/RunCommand.hpp" #include "wpi/util/array.hpp" -using namespace frc2; +using namespace wpi::cmd; // Class to verify the overload resolution of Command::AddRequirements. This // does not derive from Command because AddRequirements is non-virtual, @@ -15,7 +15,7 @@ using namespace frc2; class MockAddRequirements { public: MOCK_METHOD(void, AddRequirements, (Requirements), ()); - MOCK_METHOD(void, AddRequirements, ((wpi::SmallSet)), ()); + MOCK_METHOD(void, AddRequirements, ((wpi::util::SmallSet)), ()); MOCK_METHOD(void, AddRequirements, (Subsystem*), ()); }; @@ -40,12 +40,12 @@ TEST(AddRequirementsTest, SpanOverloadResolution) { } TEST(AddRequirementsTest, SmallSetOverloadResolution) { - wpi::SmallSet requirementsSet; + wpi::util::SmallSet requirementsSet; MockAddRequirements overloadResolver; EXPECT_CALL(overloadResolver, - AddRequirements(testing::An>())); + AddRequirements(testing::An>())); overloadResolver.AddRequirements(requirementsSet); } @@ -84,7 +84,7 @@ TEST(AddRequirementsTest, SpanSemantics) { TestSubsystem requirement1; TestSubsystem requirement2; - wpi::array requirementsArray(&requirement1, + wpi::util::array requirementsArray(&requirement1, &requirement2); RunCommand command([] {}); @@ -97,7 +97,7 @@ TEST(AddRequirementsTest, SpanSemantics) { TEST(AddRequirementsTest, SpanDuplicatesSemantics) { TestSubsystem requirement; - wpi::array requirementsArray(&requirement, &requirement); + wpi::util::array requirementsArray(&requirement, &requirement); RunCommand command([] {}); command.AddRequirements(std::span{requirementsArray}); @@ -109,7 +109,7 @@ TEST(AddRequirementsTest, SmallSetSemantics) { TestSubsystem requirement1; TestSubsystem requirement2; - wpi::SmallSet requirementsSet; + wpi::util::SmallSet requirementsSet; requirementsSet.insert(&requirement1); requirementsSet.insert(&requirement2); diff --git a/commandsv2/src/test/native/cpp/wpi/command/CommandDecoratorTest.cpp b/commandsv2/src/test/native/cpp/wpi/command/CommandDecoratorTest.cpp index 539886c9eb..ab8acbcd1c 100644 --- a/commandsv2/src/test/native/cpp/wpi/command/CommandDecoratorTest.cpp +++ b/commandsv2/src/test/native/cpp/wpi/command/CommandDecoratorTest.cpp @@ -13,13 +13,13 @@ #include "wpi/commands2/WaitUntilCommand.hpp" #include "wpi/simulation/SimHooks.hpp" -using namespace frc2; +using namespace wpi::cmd; class CommandDecoratorTest : public CommandTestBase {}; TEST_F(CommandDecoratorTest, WithTimeout) { CommandScheduler scheduler = GetScheduler(); - frc::sim::PauseTiming(); + wpi::sim::PauseTiming(); auto command = cmd::Idle().WithTimeout(100_ms); @@ -28,13 +28,13 @@ TEST_F(CommandDecoratorTest, WithTimeout) { EXPECT_TRUE(scheduler.IsScheduled(command)); - frc::sim::StepTiming(150_ms); + wpi::sim::StepTiming(150_ms); scheduler.Run(); EXPECT_FALSE(scheduler.IsScheduled(command)); - frc::sim::ResumeTiming(); + wpi::sim::ResumeTiming(); } TEST_F(CommandDecoratorTest, Until) { diff --git a/commandsv2/src/test/native/cpp/wpi/command/CommandPtrTest.cpp b/commandsv2/src/test/native/cpp/wpi/command/CommandPtrTest.cpp index 48a1c2bbcb..c9b0761250 100644 --- a/commandsv2/src/test/native/cpp/wpi/command/CommandPtrTest.cpp +++ b/commandsv2/src/test/native/cpp/wpi/command/CommandPtrTest.cpp @@ -10,7 +10,7 @@ #include "wpi/commands2/Commands.hpp" #include "wpi/system/Errors.hpp" -using namespace frc2; +using namespace wpi::cmd; class CommandPtrTest : public CommandTestBase {}; TEST_F(CommandPtrTest, MovedFrom) { @@ -27,16 +27,16 @@ TEST_F(CommandPtrTest, MovedFrom) { EXPECT_EQ(1, counter); EXPECT_NO_FATAL_FAILURE(scheduler.Cancel(movedTo)); - EXPECT_THROW(scheduler.Schedule(movedFrom), frc::RuntimeError); + EXPECT_THROW(scheduler.Schedule(movedFrom), wpi::RuntimeError); // NOLINTNEXTLINE(clang-analyzer-cplusplus.Move) - EXPECT_THROW(movedFrom.IsScheduled(), frc::RuntimeError); + EXPECT_THROW(movedFrom.IsScheduled(), wpi::RuntimeError); EXPECT_THROW(static_cast(std::move(movedFrom).Repeatedly()), - frc::RuntimeError); + wpi::RuntimeError); EXPECT_EQ(1, counter); } TEST_F(CommandPtrTest, NullInitialization) { EXPECT_THROW(auto cmd = CommandPtr{std::unique_ptr{}}, - frc::RuntimeError); + wpi::RuntimeError); } diff --git a/commandsv2/src/test/native/cpp/wpi/command/CommandRequirementsTest.cpp b/commandsv2/src/test/native/cpp/wpi/command/CommandRequirementsTest.cpp index ff8cdaf574..1cf58cf11b 100644 --- a/commandsv2/src/test/native/cpp/wpi/command/CommandRequirementsTest.cpp +++ b/commandsv2/src/test/native/cpp/wpi/command/CommandRequirementsTest.cpp @@ -9,7 +9,7 @@ #include "wpi/commands2/FunctionalCommand.hpp" #include "wpi/system/Errors.hpp" -using namespace frc2; +using namespace wpi::cmd; class CommandRequirementsTest : public CommandTestBase {}; TEST_F(CommandRequirementsTest, RequirementInterrupt) { @@ -81,5 +81,5 @@ TEST_F(CommandRequirementsTest, DefaultCommandRequirementError) { MockCommand command1; ASSERT_THROW(requirement1.SetDefaultCommand(std::move(command1)), - frc::RuntimeError); + wpi::RuntimeError); } diff --git a/commandsv2/src/test/native/cpp/wpi/command/CommandScheduleTest.cpp b/commandsv2/src/test/native/cpp/wpi/command/CommandScheduleTest.cpp index fe01fa793e..15073f79cf 100644 --- a/commandsv2/src/test/native/cpp/wpi/command/CommandScheduleTest.cpp +++ b/commandsv2/src/test/native/cpp/wpi/command/CommandScheduleTest.cpp @@ -9,7 +9,7 @@ #include "wpi/nt/NetworkTableInstance.hpp" #include "wpi/smartdashboard/SmartDashboard.hpp" -using namespace frc2; +using namespace wpi::cmd; class CommandScheduleTest : public CommandTestBase {}; TEST_F(CommandScheduleTest, InstantSchedule) { @@ -100,8 +100,8 @@ TEST_F(CommandScheduleTest, SchedulerCancel) { TEST_F(CommandScheduleTest, CommandKnowsWhenItEnded) { CommandScheduler scheduler = GetScheduler(); - frc2::FunctionalCommand* commandPtr = nullptr; - auto command = frc2::FunctionalCommand( + wpi::cmd::FunctionalCommand* commandPtr = nullptr; + auto command = wpi::cmd::FunctionalCommand( [] {}, [] {}, [&](auto isForced) { EXPECT_FALSE(scheduler.IsScheduled(commandPtr)) @@ -120,10 +120,10 @@ TEST_F(CommandScheduleTest, CommandKnowsWhenItEnded) { TEST_F(CommandScheduleTest, ScheduleCommandInCommand) { CommandScheduler scheduler = GetScheduler(); int counter = 0; - frc2::InstantCommand commandToGetScheduled{[&counter] { counter++; }}; + wpi::cmd::InstantCommand commandToGetScheduled{[&counter] { counter++; }}; auto command = - frc2::RunCommand([&counter, &scheduler, &commandToGetScheduled] { + wpi::cmd::RunCommand([&counter, &scheduler, &commandToGetScheduled] { scheduler.Schedule(&commandToGetScheduled); EXPECT_EQ(counter, 1) << "Scheduled command's init was not run immediately " @@ -151,21 +151,21 @@ TEST_F(CommandScheduleTest, NotScheduledCancel) { TEST_F(CommandScheduleTest, SmartDashboardCancel) { CommandScheduler scheduler = GetScheduler(); - frc::SmartDashboard::PutData("Scheduler", &scheduler); - frc::SmartDashboard::UpdateValues(); + wpi::SmartDashboard::PutData("Scheduler", &scheduler); + wpi::SmartDashboard::UpdateValues(); MockCommand command; scheduler.Schedule(&command); scheduler.Run(); - frc::SmartDashboard::UpdateValues(); + wpi::SmartDashboard::UpdateValues(); EXPECT_TRUE(scheduler.IsScheduled(&command)); uintptr_t ptrTmp = reinterpret_cast(&command); - nt::NetworkTableInstance::GetDefault() + wpi::nt::NetworkTableInstance::GetDefault() .GetEntry("/SmartDashboard/Scheduler/Cancel") .SetIntegerArray( std::span{{static_cast(ptrTmp)}}); - frc::SmartDashboard::UpdateValues(); + wpi::SmartDashboard::UpdateValues(); scheduler.Run(); EXPECT_FALSE(scheduler.IsScheduled(&command)); } diff --git a/commandsv2/src/test/native/cpp/wpi/command/CommandSendableButtonTest.cpp b/commandsv2/src/test/native/cpp/wpi/command/CommandSendableButtonTest.cpp index f072cfe99a..1e84dd8d63 100644 --- a/commandsv2/src/test/native/cpp/wpi/command/CommandSendableButtonTest.cpp +++ b/commandsv2/src/test/native/cpp/wpi/command/CommandSendableButtonTest.cpp @@ -8,37 +8,37 @@ #include "wpi/nt/NetworkTableInstance.hpp" #include "wpi/smartdashboard/SmartDashboard.hpp" -using namespace frc2; +using namespace wpi::cmd; class CommandSendableButtonTest : public CommandTestBase { protected: int m_schedule; int m_cancel; - nt::BooleanPublisher m_publish; + wpi::nt::BooleanPublisher m_publish; std::optional m_command; void SetUp() override { m_schedule = 0; m_cancel = 0; m_command = cmd::StartEnd([this] { m_schedule++; }, [this] { m_cancel++; }); - m_publish = nt::NetworkTableInstance::GetDefault() + m_publish = wpi::nt::NetworkTableInstance::GetDefault() .GetBooleanTopic("/SmartDashboard/command/running") .Publish(); - frc::SmartDashboard::PutData("command", m_command->get()); - frc::SmartDashboard::UpdateValues(); + wpi::SmartDashboard::PutData("command", m_command->get()); + wpi::SmartDashboard::UpdateValues(); } }; TEST_F(CommandSendableButtonTest, trueAndNotScheduledSchedules) { // Not scheduled and true -> scheduled GetScheduler().Run(); - frc::SmartDashboard::UpdateValues(); + wpi::SmartDashboard::UpdateValues(); EXPECT_FALSE(m_command->IsScheduled()); EXPECT_EQ(0, m_schedule); EXPECT_EQ(0, m_cancel); m_publish.Set(true); - frc::SmartDashboard::UpdateValues(); + wpi::SmartDashboard::UpdateValues(); GetScheduler().Run(); EXPECT_TRUE(m_command->IsScheduled()); EXPECT_EQ(1, m_schedule); @@ -47,15 +47,15 @@ TEST_F(CommandSendableButtonTest, trueAndNotScheduledSchedules) { TEST_F(CommandSendableButtonTest, trueAndScheduledNoOp) { // Scheduled and true -> no-op - frc2::CommandScheduler::GetInstance().Schedule(m_command.value()); + wpi::cmd::CommandScheduler::GetInstance().Schedule(m_command.value()); GetScheduler().Run(); - frc::SmartDashboard::UpdateValues(); + wpi::SmartDashboard::UpdateValues(); EXPECT_TRUE(m_command->IsScheduled()); EXPECT_EQ(1, m_schedule); EXPECT_EQ(0, m_cancel); m_publish.Set(true); - frc::SmartDashboard::UpdateValues(); + wpi::SmartDashboard::UpdateValues(); GetScheduler().Run(); EXPECT_TRUE(m_command->IsScheduled()); EXPECT_EQ(1, m_schedule); @@ -65,13 +65,13 @@ TEST_F(CommandSendableButtonTest, trueAndScheduledNoOp) { TEST_F(CommandSendableButtonTest, falseAndNotScheduledNoOp) { // Not scheduled and false -> no-op GetScheduler().Run(); - frc::SmartDashboard::UpdateValues(); + wpi::SmartDashboard::UpdateValues(); EXPECT_FALSE(m_command->IsScheduled()); EXPECT_EQ(0, m_schedule); EXPECT_EQ(0, m_cancel); m_publish.Set(false); - frc::SmartDashboard::UpdateValues(); + wpi::SmartDashboard::UpdateValues(); GetScheduler().Run(); EXPECT_FALSE(m_command->IsScheduled()); EXPECT_EQ(0, m_schedule); @@ -80,15 +80,15 @@ TEST_F(CommandSendableButtonTest, falseAndNotScheduledNoOp) { TEST_F(CommandSendableButtonTest, falseAndScheduledCancel) { // Scheduled and false -> cancel - frc2::CommandScheduler::GetInstance().Schedule(m_command.value()); + wpi::cmd::CommandScheduler::GetInstance().Schedule(m_command.value()); GetScheduler().Run(); - frc::SmartDashboard::UpdateValues(); + wpi::SmartDashboard::UpdateValues(); EXPECT_TRUE(m_command->IsScheduled()); EXPECT_EQ(1, m_schedule); EXPECT_EQ(0, m_cancel); m_publish.Set(false); - frc::SmartDashboard::UpdateValues(); + wpi::SmartDashboard::UpdateValues(); GetScheduler().Run(); EXPECT_FALSE(m_command->IsScheduled()); EXPECT_EQ(1, m_schedule); diff --git a/commandsv2/src/test/native/cpp/wpi/command/CommandTestBase.cpp b/commandsv2/src/test/native/cpp/wpi/command/CommandTestBase.cpp index 026c14a344..8b2bc29540 100644 --- a/commandsv2/src/test/native/cpp/wpi/command/CommandTestBase.cpp +++ b/commandsv2/src/test/native/cpp/wpi/command/CommandTestBase.cpp @@ -4,7 +4,7 @@ #include "CommandTestBase.hpp" -using namespace frc2; +using namespace wpi::cmd; CommandTestBase::CommandTestBase() { auto& scheduler = CommandScheduler::GetInstance(); @@ -26,7 +26,7 @@ CommandScheduler CommandTestBase::GetScheduler() { } void CommandTestBase::SetDSEnabled(bool enabled) { - frc::sim::DriverStationSim::SetDsAttached(true); - frc::sim::DriverStationSim::SetEnabled(enabled); - frc::sim::DriverStationSim::NotifyNewData(); + wpi::sim::DriverStationSim::SetDsAttached(true); + wpi::sim::DriverStationSim::SetEnabled(enabled); + wpi::sim::DriverStationSim::NotifyNewData(); } diff --git a/commandsv2/src/test/native/cpp/wpi/command/CommandTestBase.hpp b/commandsv2/src/test/native/cpp/wpi/command/CommandTestBase.hpp index 8a298e351b..2bef6a1bf0 100644 --- a/commandsv2/src/test/native/cpp/wpi/command/CommandTestBase.hpp +++ b/commandsv2/src/test/native/cpp/wpi/command/CommandTestBase.hpp @@ -16,7 +16,7 @@ #include "wpi/commands2/SubsystemBase.hpp" #include "wpi/simulation/DriverStationSim.hpp" -namespace frc2 { +namespace wpi::cmd { class TestSubsystem : public SubsystemBase { public: @@ -33,7 +33,7 @@ class TestSubsystem : public SubsystemBase { */ class MockCommand : public CommandHelper { public: - MOCK_CONST_METHOD0(GetRequirements, wpi::SmallSet()); + MOCK_CONST_METHOD0(GetRequirements, wpi::util::SmallSet()); MOCK_METHOD0(IsFinished, bool()); MOCK_CONST_METHOD0(RunsWhenDisabled, bool()); MOCK_METHOD0(Initialize, void()); @@ -83,7 +83,7 @@ class MockCommand : public CommandHelper { } private: - wpi::SmallSet m_requirements; + wpi::util::SmallSet m_requirements; }; class CommandTestBase : public ::testing::Test { @@ -120,10 +120,10 @@ class CommandTestBaseWithParam : public ::testing::TestWithParam { CommandScheduler GetScheduler() { return CommandScheduler(); } void SetDSEnabled(bool enabled) { - frc::sim::DriverStationSim::SetDsAttached(true); - frc::sim::DriverStationSim::SetEnabled(enabled); - frc::sim::DriverStationSim::NotifyNewData(); + wpi::sim::DriverStationSim::SetDsAttached(true); + wpi::sim::DriverStationSim::SetEnabled(enabled); + wpi::sim::DriverStationSim::NotifyNewData(); } }; -} // namespace frc2 +} // namespace wpi::cmd diff --git a/commandsv2/src/test/native/cpp/wpi/command/CompositionTestBase.hpp b/commandsv2/src/test/native/cpp/wpi/command/CompositionTestBase.hpp index 019298e21c..e9bfde73bd 100644 --- a/commandsv2/src/test/native/cpp/wpi/command/CompositionTestBase.hpp +++ b/commandsv2/src/test/native/cpp/wpi/command/CompositionTestBase.hpp @@ -13,7 +13,7 @@ #include "make_vector.hpp" #include "wpi/commands2/Commands.hpp" -namespace frc2 { +namespace wpi::cmd { inline namespace single { template @@ -182,4 +182,4 @@ REGISTER_TYPED_TEST_SUITE_P(MultiCompositionInterruptibilityTest, AllCancelSelf, INSTANTIATE_TYPED_TEST_SUITE_P(Suite, MultiCompositionRunsWhenDisabledTest, \ CompositionType) } // namespace multi -} // namespace frc2 +} // namespace wpi::cmd diff --git a/commandsv2/src/test/native/cpp/wpi/command/ConditionalCommandTest.cpp b/commandsv2/src/test/native/cpp/wpi/command/ConditionalCommandTest.cpp index 84c707e767..12555f4ab5 100644 --- a/commandsv2/src/test/native/cpp/wpi/command/ConditionalCommandTest.cpp +++ b/commandsv2/src/test/native/cpp/wpi/command/ConditionalCommandTest.cpp @@ -10,7 +10,7 @@ #include "wpi/commands2/ConditionalCommand.hpp" #include "wpi/commands2/InstantCommand.hpp" -using namespace frc2; +using namespace wpi::cmd; class ConditionalCommandTest : public CommandTestBase {}; TEST_F(ConditionalCommandTest, ConditionalCommandSchedule) { diff --git a/commandsv2/src/test/native/cpp/wpi/command/DefaultCommandTest.cpp b/commandsv2/src/test/native/cpp/wpi/command/DefaultCommandTest.cpp index 619da45985..e2df9f7a29 100644 --- a/commandsv2/src/test/native/cpp/wpi/command/DefaultCommandTest.cpp +++ b/commandsv2/src/test/native/cpp/wpi/command/DefaultCommandTest.cpp @@ -8,7 +8,7 @@ #include "wpi/commands2/Commands.hpp" #include "wpi/commands2/RunCommand.hpp" -using namespace frc2; +using namespace wpi::cmd; class DefaultCommandTest : public CommandTestBase {}; TEST_F(DefaultCommandTest, DefaultCommandSchedule) { diff --git a/commandsv2/src/test/native/cpp/wpi/command/DeferredCommandTest.cpp b/commandsv2/src/test/native/cpp/wpi/command/DeferredCommandTest.cpp index b464af9f13..62457e694f 100644 --- a/commandsv2/src/test/native/cpp/wpi/command/DeferredCommandTest.cpp +++ b/commandsv2/src/test/native/cpp/wpi/command/DeferredCommandTest.cpp @@ -7,7 +7,7 @@ #include "wpi/commands2/DeferredCommand.hpp" #include "wpi/commands2/FunctionalCommand.hpp" -using namespace frc2; +using namespace wpi::cmd; class DeferredFunctionsTest : public CommandTestBaseWithParam {}; diff --git a/commandsv2/src/test/native/cpp/wpi/command/FunctionalCommandTest.cpp b/commandsv2/src/test/native/cpp/wpi/command/FunctionalCommandTest.cpp index d471bdc677..b5852e7073 100644 --- a/commandsv2/src/test/native/cpp/wpi/command/FunctionalCommandTest.cpp +++ b/commandsv2/src/test/native/cpp/wpi/command/FunctionalCommandTest.cpp @@ -5,7 +5,7 @@ #include "CommandTestBase.hpp" #include "wpi/commands2/FunctionalCommand.hpp" -using namespace frc2; +using namespace wpi::cmd; class FunctionalCommandTest : public CommandTestBase {}; TEST_F(FunctionalCommandTest, FunctionalCommandSchedule) { diff --git a/commandsv2/src/test/native/cpp/wpi/command/InstantCommandTest.cpp b/commandsv2/src/test/native/cpp/wpi/command/InstantCommandTest.cpp index 387f22cb90..24b3a01c30 100644 --- a/commandsv2/src/test/native/cpp/wpi/command/InstantCommandTest.cpp +++ b/commandsv2/src/test/native/cpp/wpi/command/InstantCommandTest.cpp @@ -6,7 +6,7 @@ #include "wpi/commands2/Commands.hpp" #include "wpi/commands2/InstantCommand.hpp" -using namespace frc2; +using namespace wpi::cmd; class InstantCommandTest : public CommandTestBase {}; TEST_F(InstantCommandTest, InstantCommandSchedule) { diff --git a/commandsv2/src/test/native/cpp/wpi/command/NotifierCommandTest.cpp b/commandsv2/src/test/native/cpp/wpi/command/NotifierCommandTest.cpp index 0aaae24157..5597093439 100644 --- a/commandsv2/src/test/native/cpp/wpi/command/NotifierCommandTest.cpp +++ b/commandsv2/src/test/native/cpp/wpi/command/NotifierCommandTest.cpp @@ -6,7 +6,7 @@ #include "wpi/commands2/NotifierCommand.hpp" #include "wpi/simulation/SimHooks.hpp" -using namespace frc2; +using namespace wpi::cmd; using namespace std::chrono_literals; class NotifierCommandTest : public CommandTestBase {}; @@ -14,18 +14,18 @@ class NotifierCommandTest : public CommandTestBase {}; TEST_F(NotifierCommandTest, NotifierCommandSchedule) { CommandScheduler scheduler = GetScheduler(); - frc::sim::PauseTiming(); + wpi::sim::PauseTiming(); int counter = 0; NotifierCommand command([&] { counter++; }, 10_ms, {}); scheduler.Schedule(&command); for (int i = 0; i < 5; ++i) { - frc::sim::StepTiming(5_ms); + wpi::sim::StepTiming(5_ms); } scheduler.Cancel(&command); - frc::sim::ResumeTiming(); + wpi::sim::ResumeTiming(); EXPECT_EQ(counter, 2); } diff --git a/commandsv2/src/test/native/cpp/wpi/command/POVButtonTest.cpp b/commandsv2/src/test/native/cpp/wpi/command/POVButtonTest.cpp index ac3b0db493..01f4cc4086 100644 --- a/commandsv2/src/test/native/cpp/wpi/command/POVButtonTest.cpp +++ b/commandsv2/src/test/native/cpp/wpi/command/POVButtonTest.cpp @@ -13,12 +13,12 @@ #include "wpi/driverstation/Joystick.hpp" #include "wpi/simulation/JoystickSim.hpp" -using namespace frc2; +using namespace wpi::cmd; class POVButtonTest : public CommandTestBase {}; TEST_F(POVButtonTest, SetPOV) { - frc::sim::JoystickSim joysim(1); - joysim.SetPOV(frc::DriverStation::kUp); + wpi::sim::JoystickSim joysim(1); + joysim.SetPOV(wpi::DriverStation::kUp); joysim.NotifyNewData(); auto& scheduler = CommandScheduler::GetInstance(); @@ -26,12 +26,12 @@ TEST_F(POVButtonTest, SetPOV) { WaitUntilCommand command([&finished] { return finished; }); - frc::Joystick joy(1); - POVButton(&joy, frc::DriverStation::kRight).OnTrue(&command); + wpi::Joystick joy(1); + POVButton(&joy, wpi::DriverStation::kRight).OnTrue(&command); scheduler.Run(); EXPECT_FALSE(scheduler.IsScheduled(&command)); - joysim.SetPOV(frc::DriverStation::kRight); + joysim.SetPOV(wpi::DriverStation::kRight); joysim.NotifyNewData(); scheduler.Run(); diff --git a/commandsv2/src/test/native/cpp/wpi/command/ParallelCommandGroupTest.cpp b/commandsv2/src/test/native/cpp/wpi/command/ParallelCommandGroupTest.cpp index 00f8f61001..9eaec16cd0 100644 --- a/commandsv2/src/test/native/cpp/wpi/command/ParallelCommandGroupTest.cpp +++ b/commandsv2/src/test/native/cpp/wpi/command/ParallelCommandGroupTest.cpp @@ -11,7 +11,7 @@ #include "wpi/commands2/ParallelCommandGroup.hpp" #include "wpi/commands2/WaitUntilCommand.hpp" -using namespace frc2; +using namespace wpi::cmd; class ParallelCommandGroupTest : public CommandTestBase {}; TEST_F(ParallelCommandGroupTest, ParallelGroupSchedule) { diff --git a/commandsv2/src/test/native/cpp/wpi/command/ParallelDeadlineGroupTest.cpp b/commandsv2/src/test/native/cpp/wpi/command/ParallelDeadlineGroupTest.cpp index c40e839c03..a74e7c1cdb 100644 --- a/commandsv2/src/test/native/cpp/wpi/command/ParallelDeadlineGroupTest.cpp +++ b/commandsv2/src/test/native/cpp/wpi/command/ParallelDeadlineGroupTest.cpp @@ -12,7 +12,7 @@ #include "wpi/commands2/ParallelDeadlineGroup.hpp" #include "wpi/commands2/WaitUntilCommand.hpp" -using namespace frc2; +using namespace wpi::cmd; class ParallelDeadlineGroupTest : public CommandTestBase {}; TEST_F(ParallelDeadlineGroupTest, DeadlineGroupSchedule) { diff --git a/commandsv2/src/test/native/cpp/wpi/command/ParallelRaceGroupTest.cpp b/commandsv2/src/test/native/cpp/wpi/command/ParallelRaceGroupTest.cpp index e4ad75bcd8..8c0343d2e6 100644 --- a/commandsv2/src/test/native/cpp/wpi/command/ParallelRaceGroupTest.cpp +++ b/commandsv2/src/test/native/cpp/wpi/command/ParallelRaceGroupTest.cpp @@ -12,7 +12,7 @@ #include "wpi/commands2/SequentialCommandGroup.hpp" #include "wpi/commands2/WaitUntilCommand.hpp" -using namespace frc2; +using namespace wpi::cmd; class ParallelRaceGroupTest : public CommandTestBase {}; TEST_F(ParallelRaceGroupTest, ParallelRaceSchedule) { diff --git a/commandsv2/src/test/native/cpp/wpi/command/PrintCommandTest.cpp b/commandsv2/src/test/native/cpp/wpi/command/PrintCommandTest.cpp index a2b02e1549..0d8ca526b3 100644 --- a/commandsv2/src/test/native/cpp/wpi/command/PrintCommandTest.cpp +++ b/commandsv2/src/test/native/cpp/wpi/command/PrintCommandTest.cpp @@ -8,7 +8,7 @@ #include "wpi/commands2/Commands.hpp" #include "wpi/commands2/PrintCommand.hpp" -using namespace frc2; +using namespace wpi::cmd; class PrintCommandTest : public CommandTestBase {}; TEST_F(PrintCommandTest, PrintCommandSchedule) { diff --git a/commandsv2/src/test/native/cpp/wpi/command/ProxyCommandTest.cpp b/commandsv2/src/test/native/cpp/wpi/command/ProxyCommandTest.cpp index a2192d893e..214a4ba2e8 100644 --- a/commandsv2/src/test/native/cpp/wpi/command/ProxyCommandTest.cpp +++ b/commandsv2/src/test/native/cpp/wpi/command/ProxyCommandTest.cpp @@ -11,7 +11,7 @@ #include "wpi/commands2/ProxyCommand.hpp" #include "wpi/commands2/WaitUntilCommand.hpp" -using namespace frc2; +using namespace wpi::cmd; class ProxyCommandTest : public CommandTestBase {}; TEST_F(ProxyCommandTest, NonOwningCommandSchedule) { diff --git a/commandsv2/src/test/native/cpp/wpi/command/RepeatCommandTest.cpp b/commandsv2/src/test/native/cpp/wpi/command/RepeatCommandTest.cpp index 2fde7602f7..1504ef0c30 100644 --- a/commandsv2/src/test/native/cpp/wpi/command/RepeatCommandTest.cpp +++ b/commandsv2/src/test/native/cpp/wpi/command/RepeatCommandTest.cpp @@ -7,7 +7,7 @@ #include "wpi/commands2/FunctionalCommand.hpp" #include "wpi/commands2/RepeatCommand.hpp" -using namespace frc2; +using namespace wpi::cmd; class RepeatCommandTest : public CommandTestBase {}; TEST_F(RepeatCommandTest, CallsMethodsCorrectly) { diff --git a/commandsv2/src/test/native/cpp/wpi/command/RobotDisabledCommandTest.cpp b/commandsv2/src/test/native/cpp/wpi/command/RobotDisabledCommandTest.cpp index 34ac2beec6..7f1dc53056 100644 --- a/commandsv2/src/test/native/cpp/wpi/command/RobotDisabledCommandTest.cpp +++ b/commandsv2/src/test/native/cpp/wpi/command/RobotDisabledCommandTest.cpp @@ -10,7 +10,7 @@ #include "wpi/commands2/SelectCommand.hpp" #include "wpi/commands2/SequentialCommandGroup.hpp" -using namespace frc2; +using namespace wpi::cmd; class RobotDisabledCommandTest : public CommandTestBase {}; TEST_F(RobotDisabledCommandTest, RobotDisabledCommandCancel) { diff --git a/commandsv2/src/test/native/cpp/wpi/command/RunCommandTest.cpp b/commandsv2/src/test/native/cpp/wpi/command/RunCommandTest.cpp index 307760bff5..6da6204d55 100644 --- a/commandsv2/src/test/native/cpp/wpi/command/RunCommandTest.cpp +++ b/commandsv2/src/test/native/cpp/wpi/command/RunCommandTest.cpp @@ -6,7 +6,7 @@ #include "wpi/commands2/Commands.hpp" #include "wpi/commands2/RunCommand.hpp" -using namespace frc2; +using namespace wpi::cmd; class RunCommandTest : public CommandTestBase {}; TEST_F(RunCommandTest, RunCommandSchedule) { diff --git a/commandsv2/src/test/native/cpp/wpi/command/ScheduleCommandTest.cpp b/commandsv2/src/test/native/cpp/wpi/command/ScheduleCommandTest.cpp index d6393c11e7..2121a5056c 100644 --- a/commandsv2/src/test/native/cpp/wpi/command/ScheduleCommandTest.cpp +++ b/commandsv2/src/test/native/cpp/wpi/command/ScheduleCommandTest.cpp @@ -9,7 +9,7 @@ #include "wpi/commands2/ScheduleCommand.hpp" #include "wpi/commands2/SequentialCommandGroup.hpp" -using namespace frc2; +using namespace wpi::cmd; class ScheduleCommandTest : public CommandTestBase {}; TEST_F(ScheduleCommandTest, ScheduleCommandSchedule) { diff --git a/commandsv2/src/test/native/cpp/wpi/command/SchedulerTest.cpp b/commandsv2/src/test/native/cpp/wpi/command/SchedulerTest.cpp index d1fef110f0..0082578dbb 100644 --- a/commandsv2/src/test/native/cpp/wpi/command/SchedulerTest.cpp +++ b/commandsv2/src/test/native/cpp/wpi/command/SchedulerTest.cpp @@ -10,7 +10,7 @@ #include "wpi/commands2/RunCommand.hpp" #include "wpi/commands2/StartEndCommand.hpp" -using namespace frc2; +using namespace wpi::cmd; class SchedulerTest : public CommandTestBase {}; TEST_F(SchedulerTest, SchedulerLambdaTestNoInterrupt) { @@ -176,9 +176,9 @@ TEST_F(SchedulerTest, ScheduleScheduledNoOp) { } class TrackDestroyCommand - : public frc2::CommandHelper { + : public wpi::cmd::CommandHelper { public: - explicit TrackDestroyCommand(wpi::unique_function deleteFunc) + explicit TrackDestroyCommand(wpi::util::unique_function deleteFunc) : m_deleteFunc{std::move(deleteFunc)} {} TrackDestroyCommand(TrackDestroyCommand&& other) : m_deleteFunc{std::exchange(other.m_deleteFunc, [] {})} {} @@ -189,7 +189,7 @@ class TrackDestroyCommand ~TrackDestroyCommand() override { m_deleteFunc(); } private: - wpi::unique_function m_deleteFunc; + wpi::util::unique_function m_deleteFunc; }; TEST_F(SchedulerTest, ScheduleCommandPtr) { @@ -203,7 +203,7 @@ TEST_F(SchedulerTest, ScheduleCommandPtr) { auto commandPtr = TrackDestroyCommand([&destructionCounter] { destructionCounter++; }) .AlongWith( - frc2::InstantCommand([&runCounter] { runCounter++; }).ToPtr()) + wpi::cmd::InstantCommand([&runCounter] { runCounter++; }).ToPtr()) .Until([&finish] { return finish; }); EXPECT_EQ(destructionCounter, 0) << "Composition should not delete command"; diff --git a/commandsv2/src/test/native/cpp/wpi/command/SchedulingRecursionTest.cpp b/commandsv2/src/test/native/cpp/wpi/command/SchedulingRecursionTest.cpp index a3d6300685..2f15e4e11b 100644 --- a/commandsv2/src/test/native/cpp/wpi/command/SchedulingRecursionTest.cpp +++ b/commandsv2/src/test/native/cpp/wpi/command/SchedulingRecursionTest.cpp @@ -13,7 +13,7 @@ #include "wpi/commands2/FunctionalCommand.hpp" #include "wpi/commands2/RunCommand.hpp" -using namespace frc2; +using namespace wpi::cmd; class SchedulingRecursionTest : public CommandTestBaseWithParam {}; @@ -343,15 +343,15 @@ TEST_F(SchedulingRecursionTest, CancelDefaultCommandFromEnd) { TEST_F(SchedulingRecursionTest, CancelNextCommandFromCommand) { CommandScheduler scheduler = GetScheduler(); - frc2::RunCommand* command1Ptr = nullptr; - frc2::RunCommand* command2Ptr = nullptr; + wpi::cmd::RunCommand* command1Ptr = nullptr; + wpi::cmd::RunCommand* command2Ptr = nullptr; int counter = 0; - auto command1 = frc2::RunCommand([&counter, &command2Ptr, &scheduler] { + auto command1 = wpi::cmd::RunCommand([&counter, &command2Ptr, &scheduler] { scheduler.Cancel(command2Ptr); counter++; }); - auto command2 = frc2::RunCommand([&counter, &command1Ptr, &scheduler] { + auto command2 = wpi::cmd::RunCommand([&counter, &command1Ptr, &scheduler] { scheduler.Cancel(command1Ptr); counter++; }); diff --git a/commandsv2/src/test/native/cpp/wpi/command/SelectCommandTest.cpp b/commandsv2/src/test/native/cpp/wpi/command/SelectCommandTest.cpp index c0a658c950..406267ba0e 100644 --- a/commandsv2/src/test/native/cpp/wpi/command/SelectCommandTest.cpp +++ b/commandsv2/src/test/native/cpp/wpi/command/SelectCommandTest.cpp @@ -11,7 +11,7 @@ #include "wpi/commands2/InstantCommand.hpp" #include "wpi/commands2/SelectCommand.hpp" -using namespace frc2; +using namespace wpi::cmd; class SelectCommandTest : public CommandTestBase {}; TEST_F(SelectCommandTest, SelectCommand) { diff --git a/commandsv2/src/test/native/cpp/wpi/command/SequentialCommandGroupTest.cpp b/commandsv2/src/test/native/cpp/wpi/command/SequentialCommandGroupTest.cpp index 40925f3b33..dcd69bf048 100644 --- a/commandsv2/src/test/native/cpp/wpi/command/SequentialCommandGroupTest.cpp +++ b/commandsv2/src/test/native/cpp/wpi/command/SequentialCommandGroupTest.cpp @@ -11,7 +11,7 @@ #include "wpi/commands2/SequentialCommandGroup.hpp" #include "wpi/commands2/WaitUntilCommand.hpp" -using namespace frc2; +using namespace wpi::cmd; class SequentialCommandGroupTest : public CommandTestBase {}; TEST_F(SequentialCommandGroupTest, SequentialGroupSchedule) { diff --git a/commandsv2/src/test/native/cpp/wpi/command/StartEndCommandTest.cpp b/commandsv2/src/test/native/cpp/wpi/command/StartEndCommandTest.cpp index d2997f0133..6e1ce9b46f 100644 --- a/commandsv2/src/test/native/cpp/wpi/command/StartEndCommandTest.cpp +++ b/commandsv2/src/test/native/cpp/wpi/command/StartEndCommandTest.cpp @@ -6,7 +6,7 @@ #include "wpi/commands2/Commands.hpp" #include "wpi/commands2/StartEndCommand.hpp" -using namespace frc2; +using namespace wpi::cmd; class StartEndCommandTest : public CommandTestBase {}; TEST_F(StartEndCommandTest, StartEndCommandSchedule) { diff --git a/commandsv2/src/test/native/cpp/wpi/command/WaitCommandTest.cpp b/commandsv2/src/test/native/cpp/wpi/command/WaitCommandTest.cpp index 91848df916..2b59dfcdb4 100644 --- a/commandsv2/src/test/native/cpp/wpi/command/WaitCommandTest.cpp +++ b/commandsv2/src/test/native/cpp/wpi/command/WaitCommandTest.cpp @@ -8,11 +8,11 @@ #include "wpi/commands2/WaitUntilCommand.hpp" #include "wpi/simulation/SimHooks.hpp" -using namespace frc2; +using namespace wpi::cmd; class WaitCommandTest : public CommandTestBase {}; TEST_F(WaitCommandTest, WaitCommandSchedule) { - frc::sim::PauseTiming(); + wpi::sim::PauseTiming(); CommandScheduler scheduler = GetScheduler(); @@ -21,9 +21,9 @@ TEST_F(WaitCommandTest, WaitCommandSchedule) { scheduler.Schedule(command); scheduler.Run(); EXPECT_TRUE(scheduler.IsScheduled(command)); - frc::sim::StepTiming(110_ms); + wpi::sim::StepTiming(110_ms); scheduler.Run(); EXPECT_FALSE(scheduler.IsScheduled(command)); - frc::sim::ResumeTiming(); + wpi::sim::ResumeTiming(); } diff --git a/commandsv2/src/test/native/cpp/wpi/command/WaitUntilCommandTest.cpp b/commandsv2/src/test/native/cpp/wpi/command/WaitUntilCommandTest.cpp index e09e1bb642..3f2cf88a08 100644 --- a/commandsv2/src/test/native/cpp/wpi/command/WaitUntilCommandTest.cpp +++ b/commandsv2/src/test/native/cpp/wpi/command/WaitUntilCommandTest.cpp @@ -6,7 +6,7 @@ #include "wpi/commands2/Commands.hpp" #include "wpi/commands2/WaitUntilCommand.hpp" -using namespace frc2; +using namespace wpi::cmd; class WaitUntilCommandTest : public CommandTestBase {}; TEST_F(WaitUntilCommandTest, WaitUntilCommandSchedule) { diff --git a/commandsv2/src/test/native/cpp/wpi/command/button/NetworkButtonTest.cpp b/commandsv2/src/test/native/cpp/wpi/command/button/NetworkButtonTest.cpp index b780c0b98f..e76e5ca57b 100644 --- a/commandsv2/src/test/native/cpp/wpi/command/button/NetworkButtonTest.cpp +++ b/commandsv2/src/test/native/cpp/wpi/command/button/NetworkButtonTest.cpp @@ -11,18 +11,18 @@ #include "wpi/commands2/button/NetworkButton.hpp" #include "wpi/nt/NetworkTableInstance.hpp" -using namespace frc2; +using namespace wpi::cmd; class NetworkButtonTest : public CommandTestBase { public: NetworkButtonTest() { - inst = nt::NetworkTableInstance::Create(); + inst = wpi::nt::NetworkTableInstance::Create(); inst.StartLocal(); } - ~NetworkButtonTest() override { nt::NetworkTableInstance::Destroy(inst); } + ~NetworkButtonTest() override { wpi::nt::NetworkTableInstance::Destroy(inst); } - nt::NetworkTableInstance inst; + wpi::nt::NetworkTableInstance inst; }; TEST_F(NetworkButtonTest, SetNetworkButton) { diff --git a/commandsv2/src/test/native/cpp/wpi/command/button/RobotModeTriggersTest.cpp b/commandsv2/src/test/native/cpp/wpi/command/button/RobotModeTriggersTest.cpp index ad461dfa41..b23ffa3e03 100644 --- a/commandsv2/src/test/native/cpp/wpi/command/button/RobotModeTriggersTest.cpp +++ b/commandsv2/src/test/native/cpp/wpi/command/button/RobotModeTriggersTest.cpp @@ -8,8 +8,8 @@ #include "wpi/driverstation/DriverStation.hpp" #include "wpi/simulation/DriverStationSim.hpp" -using namespace frc2; -using namespace frc::sim; +using namespace wpi::cmd; +using namespace wpi::sim; class RobotModeTriggersTest : public CommandTestBase {}; TEST(RobotModeTriggersTest, Autonomous) { diff --git a/commandsv2/src/test/native/cpp/wpi/command/button/TriggerTest.cpp b/commandsv2/src/test/native/cpp/wpi/command/button/TriggerTest.cpp index 9872a5f9d1..3792d34602 100644 --- a/commandsv2/src/test/native/cpp/wpi/command/button/TriggerTest.cpp +++ b/commandsv2/src/test/native/cpp/wpi/command/button/TriggerTest.cpp @@ -15,7 +15,7 @@ #include "wpi/commands2/button/Trigger.hpp" #include "wpi/simulation/SimHooks.hpp" -using namespace frc2; +using namespace wpi::cmd; class TriggerTest : public CommandTestBase {}; TEST_F(TriggerTest, OnTrue) { @@ -242,7 +242,7 @@ TEST_F(TriggerTest, Debounce) { scheduler.Run(); EXPECT_FALSE(scheduler.IsScheduled(&command)); - frc::sim::StepTiming(300_ms); + wpi::sim::StepTiming(300_ms); scheduler.Run(); EXPECT_TRUE(scheduler.IsScheduled(&command)); diff --git a/commandsv2/src/test/native/cpp/wpi/command/make_vector.hpp b/commandsv2/src/test/native/cpp/wpi/command/make_vector.hpp index 8dbf7544ac..5e161484c9 100644 --- a/commandsv2/src/test/native/cpp/wpi/command/make_vector.hpp +++ b/commandsv2/src/test/native/cpp/wpi/command/make_vector.hpp @@ -8,7 +8,7 @@ #include #include -namespace frc2 { +namespace wpi::cmd { template make_vector(Args&&... args) { } } -} // namespace frc2 +} // namespace wpi::cmd diff --git a/commandsv2/src/test/native/cpp/wpi/command/sysid/SysIdRoutineTest.cpp b/commandsv2/src/test/native/cpp/wpi/command/sysid/SysIdRoutineTest.cpp index 1efa380e7a..f88893870f 100644 --- a/commandsv2/src/test/native/cpp/wpi/command/sysid/SysIdRoutineTest.cpp +++ b/commandsv2/src/test/native/cpp/wpi/command/sysid/SysIdRoutineTest.cpp @@ -14,7 +14,7 @@ #include "wpi/units/math.hpp" #define EXPECT_NEAR_UNITS(val1, val2, eps) \ - EXPECT_LE(units::math::abs(val1 - val2), eps) + EXPECT_LE(wpi::units::math::abs(val1 - val2), eps) enum StateTest { Invalid, @@ -30,79 +30,79 @@ enum StateTest { class SysIdRoutineTest : public ::testing::Test { protected: std::vector currentStateList{}; - std::vector sentVoltages{}; - frc2::Subsystem m_subsystem{}; - frc2::sysid::SysIdRoutine m_sysidRoutine{ - frc2::sysid::Config{ + std::vector sentVoltages{}; + wpi::cmd::Subsystem m_subsystem{}; + wpi::cmd::sysid::SysIdRoutine m_sysidRoutine{ + wpi::cmd::sysid::Config{ std::nullopt, std::nullopt, std::nullopt, - [this](frc::sysid::State state) { + [this](wpi::sysid::State state) { switch (state) { - case frc::sysid::State::kQuasistaticForward: + case wpi::sysid::State::kQuasistaticForward: currentStateList.emplace_back(StateTest::InRecordStateQf); break; - case frc::sysid::State::kQuasistaticReverse: + case wpi::sysid::State::kQuasistaticReverse: currentStateList.emplace_back(StateTest::InRecordStateQr); break; - case frc::sysid::State::kDynamicForward: + case wpi::sysid::State::kDynamicForward: currentStateList.emplace_back(StateTest::InRecordStateDf); break; - case frc::sysid::State::kDynamicReverse: + case wpi::sysid::State::kDynamicReverse: currentStateList.emplace_back(StateTest::InRecordStateDr); break; - case frc::sysid::State::kNone: + case wpi::sysid::State::kNone: currentStateList.emplace_back(StateTest::DoneWithRecordState); break; } }}, - frc2::sysid::Mechanism{ - [this](units::volt_t driveVoltage) { + wpi::cmd::sysid::Mechanism{ + [this](wpi::units::volt_t driveVoltage) { sentVoltages.emplace_back(driveVoltage); currentStateList.emplace_back(StateTest::InDrive); }, - [this](frc::sysid::SysIdRoutineLog* log) { + [this](wpi::sysid::SysIdRoutineLog* log) { currentStateList.emplace_back(StateTest::InLog); log->Motor("Mock Motor").position(0_m).velocity(0_mps).voltage(0_V); }, &m_subsystem}}; - frc2::CommandPtr m_quasistaticForward{ - m_sysidRoutine.Quasistatic(frc2::sysid::Direction::kForward)}; - frc2::CommandPtr m_quasistaticReverse{ - m_sysidRoutine.Quasistatic(frc2::sysid::Direction::kReverse)}; - frc2::CommandPtr m_dynamicForward{ - m_sysidRoutine.Dynamic(frc2::sysid::Direction::kForward)}; - frc2::CommandPtr m_dynamicReverse{ - m_sysidRoutine.Dynamic(frc2::sysid::Direction::kReverse)}; + wpi::cmd::CommandPtr m_quasistaticForward{ + m_sysidRoutine.Quasistatic(wpi::cmd::sysid::Direction::kForward)}; + wpi::cmd::CommandPtr m_quasistaticReverse{ + m_sysidRoutine.Quasistatic(wpi::cmd::sysid::Direction::kReverse)}; + wpi::cmd::CommandPtr m_dynamicForward{ + m_sysidRoutine.Dynamic(wpi::cmd::sysid::Direction::kForward)}; + wpi::cmd::CommandPtr m_dynamicReverse{ + m_sysidRoutine.Dynamic(wpi::cmd::sysid::Direction::kReverse)}; - frc2::sysid::SysIdRoutine m_emptySysidRoutine{ - frc2::sysid::Config{std::nullopt, std::nullopt, std::nullopt, nullptr}, - frc2::sysid::Mechanism{[](units::volt_t driveVoltage) {}, nullptr, + wpi::cmd::sysid::SysIdRoutine m_emptySysidRoutine{ + wpi::cmd::sysid::Config{std::nullopt, std::nullopt, std::nullopt, nullptr}, + wpi::cmd::sysid::Mechanism{[](wpi::units::volt_t driveVoltage) {}, nullptr, &m_subsystem}}; - frc2::CommandPtr m_emptyRoutineForward{ - m_emptySysidRoutine.Quasistatic(frc2::sysid::Direction::kForward)}; + wpi::cmd::CommandPtr m_emptyRoutineForward{ + m_emptySysidRoutine.Quasistatic(wpi::cmd::sysid::Direction::kForward)}; - void RunCommand(frc2::CommandPtr command) { + void RunCommand(wpi::cmd::CommandPtr command) { command.get()->Initialize(); command.get()->Execute(); - frc::sim::StepTiming(1_s); + wpi::sim::StepTiming(1_s); command.get()->Execute(); command.get()->End(true); } void SetUp() override { - frc::sim::PauseTiming(); - frc2::CommandPtr m_quasistaticForward{ - m_sysidRoutine.Quasistatic(frc2::sysid::Direction::kForward)}; - frc2::CommandPtr m_quasistaticReverse{ - m_sysidRoutine.Quasistatic(frc2::sysid::Direction::kReverse)}; - frc2::CommandPtr m_dynamicForward{ - m_sysidRoutine.Dynamic(frc2::sysid::Direction::kForward)}; - frc2::CommandPtr m_dynamicReverse{ - m_sysidRoutine.Dynamic(frc2::sysid::Direction::kReverse)}; + wpi::sim::PauseTiming(); + wpi::cmd::CommandPtr m_quasistaticForward{ + m_sysidRoutine.Quasistatic(wpi::cmd::sysid::Direction::kForward)}; + wpi::cmd::CommandPtr m_quasistaticReverse{ + m_sysidRoutine.Quasistatic(wpi::cmd::sysid::Direction::kReverse)}; + wpi::cmd::CommandPtr m_dynamicForward{ + m_sysidRoutine.Dynamic(wpi::cmd::sysid::Direction::kForward)}; + wpi::cmd::CommandPtr m_dynamicReverse{ + m_sysidRoutine.Dynamic(wpi::cmd::sysid::Direction::kReverse)}; } - void TearDown() override { frc::sim::ResumeTiming(); } + void TearDown() override { wpi::sim::ResumeTiming(); } }; TEST_F(SysIdRoutineTest, RecordStateBookendsMotorLogging) { @@ -151,28 +151,28 @@ TEST_F(SysIdRoutineTest, DeclareCorrectState) { TEST_F(SysIdRoutineTest, OutputCorrectVoltage) { RunCommand(std::move(m_quasistaticForward)); - std::vector expectedVoltages{1_V, 0_V}; + std::vector expectedVoltages{1_V, 0_V}; EXPECT_NEAR_UNITS(expectedVoltages[0], sentVoltages[0], 1e-6_V); EXPECT_NEAR_UNITS(expectedVoltages[1], sentVoltages[1], 1e-6_V); currentStateList.clear(); sentVoltages.clear(); RunCommand(std::move(m_quasistaticReverse)); - expectedVoltages = std::vector{-1_V, 0_V}; + expectedVoltages = std::vector{-1_V, 0_V}; EXPECT_NEAR_UNITS(expectedVoltages[0], sentVoltages[0], 1e-6_V); EXPECT_NEAR_UNITS(expectedVoltages[1], sentVoltages[1], 1e-6_V); currentStateList.clear(); sentVoltages.clear(); RunCommand(std::move(m_dynamicForward)); - expectedVoltages = std::vector{7_V, 0_V}; + expectedVoltages = std::vector{7_V, 0_V}; EXPECT_NEAR_UNITS(expectedVoltages[0], sentVoltages[0], 1e-6_V); EXPECT_NEAR_UNITS(expectedVoltages[1], sentVoltages[1], 1e-6_V); currentStateList.clear(); sentVoltages.clear(); RunCommand(std::move(m_dynamicReverse)); - expectedVoltages = std::vector{-7_V, 0_V}; + expectedVoltages = std::vector{-7_V, 0_V}; EXPECT_NEAR_UNITS(expectedVoltages[0], sentVoltages[0], 1e-6_V); EXPECT_NEAR_UNITS(expectedVoltages[1], sentVoltages[1], 1e-6_V); currentStateList.clear(); diff --git a/cscore/examples/enum_usb/enum_usb.cpp b/cscore/examples/enum_usb/enum_usb.cpp index 4108630b81..7c4cee7236 100644 --- a/cscore/examples/enum_usb/enum_usb.cpp +++ b/cscore/examples/enum_usb/enum_usb.cpp @@ -10,39 +10,39 @@ int main() { CS_Status status = 0; - for (const auto& caminfo : cs::EnumerateUsbCameras(&status)) { - wpi::print("{}: {} ({})\n", caminfo.dev, caminfo.path, caminfo.name); + for (const auto& caminfo : wpi::cs::EnumerateUsbCameras(&status)) { + wpi::util::print("{}: {} ({})\n", caminfo.dev, caminfo.path, caminfo.name); if (!caminfo.otherPaths.empty()) { std::puts("Other device paths:"); for (auto&& path : caminfo.otherPaths) { - wpi::print(" {}\n", path); + wpi::util::print(" {}\n", path); } } - cs::UsbCamera camera{"usbcam", caminfo.dev}; + wpi::cs::UsbCamera camera{"usbcam", caminfo.dev}; std::puts("Properties:"); for (const auto& prop : camera.EnumerateProperties()) { - wpi::print(" {}", prop.GetName()); + wpi::util::print(" {}", prop.GetName()); switch (prop.GetKind()) { - case cs::VideoProperty::kBoolean: - wpi::print(" (bool): value={} default={}", prop.Get(), + case wpi::cs::VideoProperty::kBoolean: + wpi::util::print(" (bool): value={} default={}", prop.Get(), prop.GetDefault()); break; - case cs::VideoProperty::kInteger: - wpi::print(" (int): value={} min={} max={} step={} default={}", + case wpi::cs::VideoProperty::kInteger: + wpi::util::print(" (int): value={} min={} max={} step={} default={}", prop.Get(), prop.GetMin(), prop.GetMax(), prop.GetStep(), prop.GetDefault()); break; - case cs::VideoProperty::kString: - wpi::print(" (string): {}", prop.GetString()); + case wpi::cs::VideoProperty::kString: + wpi::util::print(" (string): {}", prop.GetString()); break; - case cs::VideoProperty::kEnum: { - wpi::print(" (enum): value={}", prop.Get()); + case wpi::cs::VideoProperty::kEnum: { + wpi::util::print(" (enum): value={}", prop.Get()); auto choices = prop.GetChoices(); for (size_t i = 0; i < choices.size(); ++i) { if (!choices[i].empty()) { - wpi::print("\n {}: {}", i, choices[i]); + wpi::util::print("\n {}: {}", i, choices[i]); } } break; @@ -57,20 +57,20 @@ int main() { for (const auto& mode : camera.EnumerateVideoModes()) { const char* pixelFormat; switch (mode.pixelFormat) { - case cs::VideoMode::kMJPEG: + case wpi::cs::VideoMode::kMJPEG: pixelFormat = "MJPEG"; break; - case cs::VideoMode::kYUYV: + case wpi::cs::VideoMode::kYUYV: pixelFormat = "YUYV"; break; - case cs::VideoMode::kRGB565: + case wpi::cs::VideoMode::kRGB565: pixelFormat = "RGB565"; break; default: pixelFormat = "Unknown"; break; } - wpi::print(" PixelFormat:{} Width:{} Height:{} FPS:{}\n", pixelFormat, + wpi::util::print(" PixelFormat:{} Width:{} Height:{} FPS:{}\n", pixelFormat, mode.width, mode.height, mode.fps); } } diff --git a/cscore/examples/httpcvstream/httpcvstream.cpp b/cscore/examples/httpcvstream/httpcvstream.cpp index 3366e84a14..508fecf445 100644 --- a/cscore/examples/httpcvstream/httpcvstream.cpp +++ b/cscore/examples/httpcvstream/httpcvstream.cpp @@ -11,12 +11,12 @@ #include "wpi/util/print.hpp" int main() { - cs::HttpCamera camera{"httpcam", "http://localhost:8081/?action=stream"}; - camera.SetVideoMode(cs::VideoMode::kMJPEG, 320, 240, 30); - cs::CvSink cvsink{"cvsink"}; + wpi::cs::HttpCamera camera{"httpcam", "http://localhost:8081/?action=stream"}; + camera.SetVideoMode(wpi::cs::VideoMode::kMJPEG, 320, 240, 30); + wpi::cs::CvSink cvsink{"cvsink"}; cvsink.SetSource(camera); - cs::CvSource cvsource{"cvsource", cs::VideoMode::kMJPEG, 320, 240, 30}; - cs::MjpegServer cvMjpegServer{"cvhttpserver", 8083}; + wpi::cs::CvSource cvsource{"cvsource", wpi::cs::VideoMode::kMJPEG, 320, 240, 30}; + wpi::cs::MjpegServer cvMjpegServer{"cvhttpserver", 8083}; cvMjpegServer.SetSource(cvsource); cv::Mat test; @@ -24,10 +24,10 @@ int main() { for (;;) { uint64_t time = cvsink.GrabFrame(test); if (time == 0) { - wpi::print("error: {}\n", cvsink.GetError()); + wpi::util::print("error: {}\n", cvsink.GetError()); continue; } - wpi::print("got frame at time {} size ({}, {})\n", time, test.size().width, + wpi::util::print("got frame at time {} size ({}, {})\n", time, test.size().width, test.size().height); cv::flip(test, flip, 0); cvsource.PutFrame(flip); diff --git a/cscore/examples/settings/settings.cpp b/cscore/examples/settings/settings.cpp index 3ab28f7621..2e1ac6b6ab 100644 --- a/cscore/examples/settings/settings.cpp +++ b/cscore/examples/settings/settings.cpp @@ -19,14 +19,14 @@ int main(int argc, char** argv) { } int id; - if (auto v = wpi::parse_integer(argv[1], 10)) { + if (auto v = wpi::util::parse_integer(argv[1], 10)) { id = v.value(); } else { std::fputs("Expected number for camera\n", stderr); return 2; } - cs::UsbCamera camera{"usbcam", id}; + wpi::cs::UsbCamera camera{"usbcam", id}; // Set prior to connect int arg = 2; @@ -36,7 +36,7 @@ int main(int argc, char** argv) { propName = argv[arg]; } else { std::string_view propVal{argv[arg]}; - if (auto v = wpi::parse_integer(propVal, 10)) { + if (auto v = wpi::util::parse_integer(propVal, 10)) { camera.GetProperty(propName).Set(v.value()); } else { camera.GetProperty(propName).SetString(propVal); @@ -60,7 +60,7 @@ int main(int argc, char** argv) { propName = argv[arg]; } else { std::string_view propVal{argv[arg]}; - if (auto v = wpi::parse_integer(propVal, 10)) { + if (auto v = wpi::util::parse_integer(propVal, 10)) { camera.GetProperty(propName).Set(v.value()); } else { camera.GetProperty(propName).SetString(propVal); @@ -72,26 +72,26 @@ int main(int argc, char** argv) { // Print settings std::puts("Properties:"); for (const auto& prop : camera.EnumerateProperties()) { - wpi::print(" {}", prop.GetName()); + wpi::util::print(" {}", prop.GetName()); switch (prop.GetKind()) { - case cs::VideoProperty::kBoolean: - wpi::print(" (bool): value={} default={}", prop.Get(), + case wpi::cs::VideoProperty::kBoolean: + wpi::util::print(" (bool): value={} default={}", prop.Get(), prop.GetDefault()); break; - case cs::VideoProperty::kInteger: - wpi::print(" (int): value={} min={} max={} step={} default={}", + case wpi::cs::VideoProperty::kInteger: + wpi::util::print(" (int): value={} min={} max={} step={} default={}", prop.Get(), prop.GetMin(), prop.GetMax(), prop.GetStep(), prop.GetDefault()); break; - case cs::VideoProperty::kString: - wpi::print(" (string): {}", prop.GetString()); + case wpi::cs::VideoProperty::kString: + wpi::util::print(" (string): {}", prop.GetString()); break; - case cs::VideoProperty::kEnum: { - wpi::print(" (enum): value={}", prop.Get()); + case wpi::cs::VideoProperty::kEnum: { + wpi::util::print(" (enum): value={}", prop.Get()); auto choices = prop.GetChoices(); for (size_t i = 0; i < choices.size(); ++i) { if (!choices[i].empty()) { - wpi::print("\n {}: {}", i, choices[i]); + wpi::util::print("\n {}: {}", i, choices[i]); } } break; diff --git a/cscore/examples/usbcvstream/usbcvstream.cpp b/cscore/examples/usbcvstream/usbcvstream.cpp index 6376ae8729..34f6ac04eb 100644 --- a/cscore/examples/usbcvstream/usbcvstream.cpp +++ b/cscore/examples/usbcvstream/usbcvstream.cpp @@ -8,14 +8,14 @@ #include "wpi/util/print.hpp" int main() { - cs::UsbCamera camera{"usbcam", 0}; - camera.SetVideoMode(cs::VideoMode::kMJPEG, 320, 240, 30); - cs::MjpegServer mjpegServer{"httpserver", 8081}; + wpi::cs::UsbCamera camera{"usbcam", 0}; + camera.SetVideoMode(wpi::cs::VideoMode::kMJPEG, 320, 240, 30); + wpi::cs::MjpegServer mjpegServer{"httpserver", 8081}; mjpegServer.SetSource(camera); - cs::CvSink cvsink{"cvsink"}; + wpi::cs::CvSink cvsink{"cvsink"}; cvsink.SetSource(camera); - cs::CvSource cvsource{"cvsource", cs::VideoMode::kMJPEG, 320, 240, 30}; - cs::MjpegServer cvMjpegServer{"cvhttpserver", 8082}; + wpi::cs::CvSource cvsource{"cvsource", wpi::cs::VideoMode::kMJPEG, 320, 240, 30}; + wpi::cs::MjpegServer cvMjpegServer{"cvhttpserver", 8082}; cvMjpegServer.SetSource(cvsource); cv::Mat test; @@ -23,10 +23,10 @@ int main() { for (;;) { uint64_t time = cvsink.GrabFrame(test); if (time == 0) { - wpi::print("error: {}\n", cvsink.GetError()); + wpi::util::print("error: {}\n", cvsink.GetError()); continue; } - wpi::print("got frame at time {} size ({}, {})\n", time, test.size().width, + wpi::util::print("got frame at time {} size ({}, {})\n", time, test.size().width, test.size().height); cv::flip(test, flip, 0); cvsource.PutFrame(flip); diff --git a/cscore/examples/usbstream/usbstream.cpp b/cscore/examples/usbstream/usbstream.cpp index 1ca051a16a..eea7bd3b38 100644 --- a/cscore/examples/usbstream/usbstream.cpp +++ b/cscore/examples/usbstream/usbstream.cpp @@ -8,24 +8,24 @@ #include "wpi/util/print.hpp" int main() { - wpi::print("hostname: {}\n", cs::GetHostname()); + wpi::util::print("hostname: {}\n", wpi::cs::GetHostname()); std::puts("IPv4 network addresses:"); - for (const auto& addr : cs::GetNetworkInterfaces()) { - wpi::print(" {}\n", addr); + for (const auto& addr : wpi::cs::GetNetworkInterfaces()) { + wpi::util::print(" {}\n", addr); } - cs::UsbCamera camera{"usbcam", 0}; - camera.SetVideoMode(cs::VideoMode::kMJPEG, 320, 240, 30); - cs::MjpegServer mjpegServer{"httpserver", 8081}; + wpi::cs::UsbCamera camera{"usbcam", 0}; + camera.SetVideoMode(wpi::cs::VideoMode::kMJPEG, 320, 240, 30); + wpi::cs::MjpegServer mjpegServer{"httpserver", 8081}; mjpegServer.SetSource(camera); CS_Status status = 0; - cs::AddListener( - [&](const cs::RawEvent& event) { - wpi::print("FPS={} MBPS={}\n", camera.GetActualFPS(), + wpi::cs::AddListener( + [&](const wpi::cs::RawEvent& event) { + wpi::util::print("FPS={} MBPS={}\n", camera.GetActualFPS(), (camera.GetActualDataRate() / 1000000.0)); }, - cs::RawEvent::kTelemetryUpdated, false, &status); - cs::SetTelemetryPeriod(1.0); + wpi::cs::RawEvent::kTelemetryUpdated, false, &status); + wpi::cs::SetTelemetryPeriod(1.0); std::getchar(); } diff --git a/cscore/examples/usbviewer/usbviewer.cpp b/cscore/examples/usbviewer/usbviewer.cpp index afd55eed47..42adf8e487 100644 --- a/cscore/examples/usbviewer/usbviewer.cpp +++ b/cscore/examples/usbviewer/usbviewer.cpp @@ -24,15 +24,15 @@ namespace gui = wpi::gui; int main() { - wpi::spinlock latestFrameMutex; + wpi::util::spinlock latestFrameMutex; std::unique_ptr latestFrame; - wpi::mutex freeListMutex; + wpi::util::mutex freeListMutex; std::vector> freeList; std::atomic stopCamera{false}; - cs::UsbCamera camera{"usbcam", 0}; - camera.SetVideoMode(cs::VideoMode::kMJPEG, 640, 480, 30); - cs::CvSink cvsink{"cvsink"}; + wpi::cs::UsbCamera camera{"usbcam", 0}; + camera.SetVideoMode(wpi::cs::VideoMode::kMJPEG, 640, 480, 30); + wpi::cs::CvSink cvsink{"cvsink"}; cvsink.SetSource(camera); std::thread thr([&] { @@ -41,7 +41,7 @@ int main() { // get frame from camera uint64_t time = cvsink.GrabFrame(frame); if (time == 0) { - wpi::print("error: {}\n", cvsink.GetError()); + wpi::util::print("error: {}\n", cvsink.GetError()); continue; } diff --git a/cscore/src/dev/native/cpp/main.cpp b/cscore/src/dev/native/cpp/main.cpp index eb649c043d..270b145024 100644 --- a/cscore/src/dev/native/cpp/main.cpp +++ b/cscore/src/dev/native/cpp/main.cpp @@ -6,5 +6,5 @@ #include "wpi/util/print.hpp" int main() { - wpi::print("{}\n", cs::GetHostname()); + wpi::util::print("{}\n", wpi::cs::GetHostname()); } diff --git a/cscore/src/main/native/cpp/ConfigurableSourceImpl.cpp b/cscore/src/main/native/cpp/ConfigurableSourceImpl.cpp index 6b4fd27a0e..1f65955d7a 100644 --- a/cscore/src/main/native/cpp/ConfigurableSourceImpl.cpp +++ b/cscore/src/main/native/cpp/ConfigurableSourceImpl.cpp @@ -12,10 +12,10 @@ #include "Notifier.hpp" #include "wpi/util/timestamp.h" -using namespace cs; +using namespace wpi::cs; ConfigurableSourceImpl::ConfigurableSourceImpl(std::string_view name, - wpi::Logger& logger, + wpi::util::Logger& logger, Notifier& notifier, Telemetry& telemetry, const VideoMode& mode) @@ -52,7 +52,7 @@ void ConfigurableSourceImpl::NumSinksEnabledChanged() { } void ConfigurableSourceImpl::NotifyError(std::string_view msg) { - PutError(msg, wpi::Now()); + PutError(msg, wpi::util::Now()); } int ConfigurableSourceImpl::CreateProperty(std::string_view name, @@ -106,7 +106,7 @@ void ConfigurableSourceImpl::SetEnumPropertyChoices( prop->value, {}); } -namespace cs { +namespace wpi::cs { static constexpr unsigned SourceMask = CS_SOURCE_CV | CS_SOURCE_RAW; void NotifySourceError(CS_Source source, std::string_view msg, @@ -195,23 +195,23 @@ void SetSourceEnumPropertyChoices(CS_Source source, CS_Property property, .SetEnumPropertyChoices(propertyIndex, choices, status); } -} // namespace cs +} // namespace wpi::cs extern "C" { void CS_NotifySourceError(CS_Source source, const struct WPI_String* msg, CS_Status* status) { - return cs::NotifySourceError(source, wpi::to_string_view(msg), status); + return wpi::cs::NotifySourceError(source, wpi::util::to_string_view(msg), status); } void CS_SetSourceConnected(CS_Source source, CS_Bool connected, CS_Status* status) { - return cs::SetSourceConnected(source, connected, status); + return wpi::cs::SetSourceConnected(source, connected, status); } void CS_SetSourceDescription(CS_Source source, const struct WPI_String* description, CS_Status* status) { - return cs::SetSourceDescription(source, wpi::to_string_view(description), + return wpi::cs::SetSourceDescription(source, wpi::util::to_string_view(description), status); } @@ -220,7 +220,7 @@ CS_Property CS_CreateSourceProperty(CS_Source source, enum CS_PropertyKind kind, int minimum, int maximum, int step, int defaultValue, int value, CS_Status* status) { - return cs::CreateSourceProperty(source, wpi::to_string_view(name), kind, + return wpi::cs::CreateSourceProperty(source, wpi::util::to_string_view(name), kind, minimum, maximum, step, defaultValue, value, status); } @@ -229,7 +229,7 @@ CS_Property CS_CreateSourcePropertyCallback( CS_Source source, const char* name, enum CS_PropertyKind kind, int minimum, int maximum, int step, int defaultValue, int value, void* data, void (*onChange)(void* data, CS_Property property), CS_Status* status) { - return cs::CreateSourcePropertyCallback( + return wpi::cs::CreateSourcePropertyCallback( source, name, kind, minimum, maximum, step, defaultValue, value, [=](CS_Property property) { onChange(data, property); }, status); } @@ -237,12 +237,12 @@ CS_Property CS_CreateSourcePropertyCallback( void CS_SetSourceEnumPropertyChoices(CS_Source source, CS_Property property, const struct WPI_String* choices, int count, CS_Status* status) { - wpi::SmallVector vec; + wpi::util::SmallVector vec; vec.reserve(count); for (int i = 0; i < count; ++i) { - vec.emplace_back(wpi::to_string_view(&choices[i])); + vec.emplace_back(wpi::util::to_string_view(&choices[i])); } - return cs::SetSourceEnumPropertyChoices(source, property, vec, status); + return wpi::cs::SetSourceEnumPropertyChoices(source, property, vec, status); } } // extern "C" diff --git a/cscore/src/main/native/cpp/ConfigurableSourceImpl.hpp b/cscore/src/main/native/cpp/ConfigurableSourceImpl.hpp index 65f94c4da4..b04f7f09bb 100644 --- a/cscore/src/main/native/cpp/ConfigurableSourceImpl.hpp +++ b/cscore/src/main/native/cpp/ConfigurableSourceImpl.hpp @@ -15,11 +15,11 @@ #include "SourceImpl.hpp" -namespace cs { +namespace wpi::cs { class ConfigurableSourceImpl : public SourceImpl { protected: - ConfigurableSourceImpl(std::string_view name, wpi::Logger& logger, + ConfigurableSourceImpl(std::string_view name, wpi::util::Logger& logger, Notifier& notifier, Telemetry& telemetry, const VideoMode& mode); @@ -48,6 +48,6 @@ class ConfigurableSourceImpl : public SourceImpl { std::atomic_bool m_connected{true}; }; -} // namespace cs +} // namespace wpi::cs #endif // CSCORE_CONFIGURABLESOURCEIMPL_HPP_ diff --git a/cscore/src/main/native/cpp/Frame.cpp b/cscore/src/main/native/cpp/Frame.cpp index 9ffd9d51bb..6d21969550 100644 --- a/cscore/src/main/native/cpp/Frame.cpp +++ b/cscore/src/main/native/cpp/Frame.cpp @@ -14,7 +14,7 @@ #include "Instance.hpp" #include "SourceImpl.hpp" -using namespace cs; +using namespace wpi::cs; Frame::Frame(SourceImpl& source, std::string_view error, Time time, WPI_TimestampSource timeSrc) @@ -802,8 +802,8 @@ void Frame::ReleaseFrame() { m_impl = nullptr; } -namespace cs { -std::unique_ptr CreateImageFromBGRA(cs::SourceImpl* source, size_t width, +namespace wpi::cs { +std::unique_ptr CreateImageFromBGRA(wpi::cs::SourceImpl* source, size_t width, size_t height, size_t stride, const uint8_t* data) { cv::Mat finalImage{static_cast(height), static_cast(width), CV_8UC4, @@ -813,4 +813,4 @@ std::unique_ptr CreateImageFromBGRA(cs::SourceImpl* source, size_t width, cv::cvtColor(finalImage, dest->AsMat(), cv::COLOR_BGRA2BGR); return dest; } -} // namespace cs +} // namespace wpi::cs diff --git a/cscore/src/main/native/cpp/Frame.hpp b/cscore/src/main/native/cpp/Frame.hpp index ebb7e73ba7..5552a2fce9 100644 --- a/cscore/src/main/native/cpp/Frame.hpp +++ b/cscore/src/main/native/cpp/Frame.hpp @@ -17,11 +17,11 @@ #include "wpi/util/SmallVector.hpp" #include "wpi/util/mutex.hpp" -namespace cs { +namespace wpi::cs { class SourceImpl; -std::unique_ptr CreateImageFromBGRA(cs::SourceImpl* source, size_t width, +std::unique_ptr CreateImageFromBGRA(wpi::cs::SourceImpl* source, size_t width, size_t height, size_t stride, const uint8_t* data); @@ -35,13 +35,13 @@ class Frame { struct Impl { explicit Impl(SourceImpl& source_) : source(source_) {} - wpi::recursive_mutex mutex; + wpi::util::recursive_mutex mutex; std::atomic_int refcount{0}; Time time{0}; WPI_TimestampSource timeSource{WPI_TIMESRC_UNKNOWN}; SourceImpl& source; std::string error; - wpi::SmallVector images; + wpi::util::SmallVector images; std::vector compressionParams; }; @@ -250,6 +250,6 @@ class Frame { Impl* m_impl{nullptr}; }; -} // namespace cs +} // namespace wpi::cs #endif // CSCORE_FRAME_HPP_ diff --git a/cscore/src/main/native/cpp/Handle.hpp b/cscore/src/main/native/cpp/Handle.hpp index ce8133985c..94aa99b2fd 100644 --- a/cscore/src/main/native/cpp/Handle.hpp +++ b/cscore/src/main/native/cpp/Handle.hpp @@ -8,7 +8,7 @@ #include "wpi/cs/cscore_c.h" #include "wpi/util/Synchronization.h" -namespace cs { +namespace wpi::cs { // Handle data layout: // Bits 0-15: Handle index @@ -19,7 +19,7 @@ class Handle { public: enum Type { kUndefined = 0, - kProperty = wpi::kHandleTypeCSBase, + kProperty = wpi::util::kHandleTypeCSBase, kSource, kSink, kListener, @@ -63,6 +63,6 @@ class Handle { CS_Handle m_handle; }; -} // namespace cs +} // namespace wpi::cs #endif // CSCORE_HANDLE_HPP_ diff --git a/cscore/src/main/native/cpp/HttpCameraImpl.cpp b/cscore/src/main/native/cpp/HttpCameraImpl.cpp index 7d1a3a852c..342c981f49 100644 --- a/cscore/src/main/native/cpp/HttpCameraImpl.cpp +++ b/cscore/src/main/native/cpp/HttpCameraImpl.cpp @@ -22,10 +22,10 @@ #include "wpi/util/StringExtras.hpp" #include "wpi/util/timestamp.h" -using namespace cs; +using namespace wpi::cs; HttpCameraImpl::HttpCameraImpl(std::string_view name, CS_HttpCameraKind kind, - wpi::Logger& logger, Notifier& notifier, + wpi::util::Logger& logger, Notifier& notifier, Telemetry& telemetry) : SourceImpl{name, logger, notifier, telemetry}, m_kind{kind} {} @@ -123,8 +123,8 @@ void HttpCameraImpl::StreamThreadMain() { } // connect - wpi::SmallString<64> boundary; - wpi::HttpConnection* conn = DeviceStreamConnect(boundary); + wpi::util::SmallString<64> boundary; + wpi::net::HttpConnection* conn = DeviceStreamConnect(boundary); if (!m_active) { break; @@ -150,10 +150,10 @@ void HttpCameraImpl::StreamThreadMain() { SetConnected(false); } -wpi::HttpConnection* HttpCameraImpl::DeviceStreamConnect( - wpi::SmallVectorImpl& boundary) { +wpi::net::HttpConnection* HttpCameraImpl::DeviceStreamConnect( + wpi::util::SmallVectorImpl& boundary) { // Build the request - wpi::HttpRequest req; + wpi::net::HttpRequest req; { std::scoped_lock lock(m_mutex); if (m_locations.empty()) { @@ -164,20 +164,20 @@ wpi::HttpConnection* HttpCameraImpl::DeviceStreamConnect( if (m_nextLocation >= m_locations.size()) { m_nextLocation = 0; } - req = wpi::HttpRequest{m_locations[m_nextLocation++], m_streamSettings}; + req = wpi::net::HttpRequest{m_locations[m_nextLocation++], m_streamSettings}; m_streamSettingsUpdated = false; } // Try to connect auto stream = - wpi::TCPConnector::connect(req.host.c_str(), req.port, m_logger, 1); + wpi::net::TCPConnector::connect(req.host.c_str(), req.port, m_logger, 1); if (!m_active || !stream) { return nullptr; } - auto connPtr = std::make_unique(std::move(stream), 1); - wpi::HttpConnection* conn = connPtr.get(); + auto connPtr = std::make_unique(std::move(stream), 1); + wpi::net::HttpConnection* conn = connPtr.get(); // update m_streamConn { @@ -195,8 +195,8 @@ wpi::HttpConnection* HttpCameraImpl::DeviceStreamConnect( } // Parse Content-Type header to get the boundary - auto [mediaType, contentType] = wpi::split(conn->contentType.str(), ';'); - mediaType = wpi::trim(mediaType); + auto [mediaType, contentType] = wpi::util::split(conn->contentType.str(), ';'); + mediaType = wpi::util::trim(mediaType); if (mediaType != "multipart/x-mixed-replace") { SWARNING("\"{}\": unrecognized Content-Type \"{}\"", req.host.str(), mediaType); @@ -209,13 +209,13 @@ wpi::HttpConnection* HttpCameraImpl::DeviceStreamConnect( boundary.clear(); while (!contentType.empty()) { std::string_view keyvalue; - std::tie(keyvalue, contentType) = wpi::split(contentType, ';'); - contentType = wpi::ltrim(contentType); - auto [key, value] = wpi::split(keyvalue, '='); - if (wpi::trim(key) == "boundary") { - value = wpi::trim(wpi::trim(value), '"'); // value may be quoted - if (wpi::starts_with(value, "--")) { - value = wpi::substr(value, 2); + std::tie(keyvalue, contentType) = wpi::util::split(contentType, ';'); + contentType = wpi::util::ltrim(contentType); + auto [key, value] = wpi::util::split(keyvalue, '='); + if (wpi::util::trim(key) == "boundary") { + value = wpi::util::trim(wpi::util::trim(value), '"'); // value may be quoted + if (wpi::util::starts_with(value, "--")) { + value = wpi::util::substr(value, 2); } boundary.append(value.begin(), value.end()); } @@ -232,7 +232,7 @@ wpi::HttpConnection* HttpCameraImpl::DeviceStreamConnect( return conn; } -void HttpCameraImpl::DeviceStream(wpi::raw_istream& is, +void HttpCameraImpl::DeviceStream(wpi::util::raw_istream& is, std::string_view boundary) { // Stored here so we reuse it from frame to frame std::string imageBuf; @@ -244,7 +244,7 @@ void HttpCameraImpl::DeviceStream(wpi::raw_istream& is, // streaming loop while (m_active && !is.has_error() && IsEnabled() && numErrors < 3 && !m_streamSettingsUpdated) { - if (!FindMultipartBoundary(is, boundary, nullptr)) { + if (!wpi::net::FindMultipartBoundary(is, boundary, nullptr)) { break; } @@ -274,29 +274,29 @@ void HttpCameraImpl::DeviceStream(wpi::raw_istream& is, } } -bool HttpCameraImpl::DeviceStreamFrame(wpi::raw_istream& is, +bool HttpCameraImpl::DeviceStreamFrame(wpi::util::raw_istream& is, std::string& imageBuf) { // Read the headers - wpi::SmallString<64> contentTypeBuf; - wpi::SmallString<64> contentLengthBuf; - if (!ParseHttpHeaders(is, &contentTypeBuf, &contentLengthBuf)) { + wpi::util::SmallString<64> contentTypeBuf; + wpi::util::SmallString<64> contentLengthBuf; + if (!wpi::net::ParseHttpHeaders(is, &contentTypeBuf, &contentLengthBuf)) { SWARNING("disconnected during headers"); - PutError("disconnected during headers", wpi::Now()); + PutError("disconnected during headers", wpi::util::Now()); return false; } // Check the content type (if present) if (!contentTypeBuf.str().empty() && - !wpi::starts_with(contentTypeBuf, "image/jpeg")) { + !wpi::util::starts_with(contentTypeBuf, "image/jpeg")) { auto errMsg = fmt::format("received unknown Content-Type \"{}\"", contentTypeBuf.str()); SWARNING("{}", errMsg); - PutError(errMsg, wpi::Now()); + PutError(errMsg, wpi::util::Now()); return false; } int width, height; - if (auto v = wpi::parse_integer(contentLengthBuf, 10)) { + if (auto v = wpi::util::parse_integer(contentLengthBuf, 10)) { // We know how big it is! Just get a frame of the right size and read // the data directly into it. unsigned int contentLength = v.value(); @@ -308,21 +308,21 @@ bool HttpCameraImpl::DeviceStreamFrame(wpi::raw_istream& is, } if (!GetJpegSize(image->str(), &width, &height)) { SWARNING("did not receive a JPEG image"); - PutError("did not receive a JPEG image", wpi::Now()); + PutError("did not receive a JPEG image", wpi::util::Now()); return false; } image->width = width; image->height = height; - PutFrame(std::move(image), wpi::Now()); + PutFrame(std::move(image), wpi::util::Now()); } else { // Ugh, no Content-Length? Read the blocks of the JPEG file. if (!ReadJpeg(is, imageBuf, &width, &height)) { SWARNING("did not receive a JPEG image"); - PutError("did not receive a JPEG image", wpi::Now()); + PutError("did not receive a JPEG image", wpi::util::Now()); return false; } PutFrame(VideoMode::PixelFormat::kMJPEG, width, height, imageBuf, - wpi::Now()); + wpi::util::Now()); } ++m_frameCount; @@ -340,7 +340,7 @@ bool HttpCameraImpl::DeviceStreamFrame(wpi::raw_istream& is, void HttpCameraImpl::SettingsThreadMain() { for (;;) { - wpi::HttpRequest req; + wpi::net::HttpRequest req; { std::unique_lock lock(m_mutex); m_settingsCond.wait(lock, [=, this] { @@ -351,7 +351,7 @@ void HttpCameraImpl::SettingsThreadMain() { } // Build the request - req = wpi::HttpRequest{m_locations[m_prefLocation], m_settings}; + req = wpi::net::HttpRequest{m_locations[m_prefLocation], m_settings}; } DeviceSendSettings(req); @@ -360,17 +360,17 @@ void HttpCameraImpl::SettingsThreadMain() { SDEBUG("Settings Thread exiting"); } -void HttpCameraImpl::DeviceSendSettings(wpi::HttpRequest& req) { +void HttpCameraImpl::DeviceSendSettings(wpi::net::HttpRequest& req) { // Try to connect auto stream = - wpi::TCPConnector::connect(req.host.c_str(), req.port, m_logger, 1); + wpi::net::TCPConnector::connect(req.host.c_str(), req.port, m_logger, 1); if (!m_active || !stream) { return; } - auto connPtr = std::make_unique(std::move(stream), 1); - wpi::HttpConnection* conn = connPtr.get(); + auto connPtr = std::make_unique(std::move(stream), 1); + wpi::net::HttpConnection* conn = connPtr.get(); // update m_settingsConn { @@ -394,7 +394,7 @@ CS_HttpCameraKind HttpCameraImpl::GetKind() const { bool HttpCameraImpl::SetUrls(std::span urls, CS_Status* status) { - std::vector locations; + std::vector locations; for (const auto& url : urls) { bool error = false; std::string errorMsg; @@ -573,7 +573,7 @@ bool AxisCameraImpl::CacheProperties(CS_Status* status) const { return true; } -namespace cs { +namespace wpi::cs { CS_Source CreateHttpCamera(std::string_view name, std::string_view url, CS_HttpCameraKind kind, CS_Status* status) { @@ -645,49 +645,49 @@ std::vector GetHttpCameraUrls(CS_Source source, return static_cast(*data->source).GetUrls(); } -} // namespace cs +} // namespace wpi::cs extern "C" { CS_Source CS_CreateHttpCamera(const struct WPI_String* name, const struct WPI_String* url, CS_HttpCameraKind kind, CS_Status* status) { - return cs::CreateHttpCamera(wpi::to_string_view(name), - wpi::to_string_view(url), kind, status); + return wpi::cs::CreateHttpCamera(wpi::util::to_string_view(name), + wpi::util::to_string_view(url), kind, status); } CS_Source CS_CreateHttpCameraMulti(const struct WPI_String* name, const struct WPI_String* urls, int count, CS_HttpCameraKind kind, CS_Status* status) { - wpi::SmallVector vec; + wpi::util::SmallVector vec; vec.reserve(count); for (int i = 0; i < count; ++i) { - vec.emplace_back(wpi::to_string_view(&urls[i])); + vec.emplace_back(wpi::util::to_string_view(&urls[i])); } - return cs::CreateHttpCamera(wpi::to_string_view(name), vec, kind, status); + return wpi::cs::CreateHttpCamera(wpi::util::to_string_view(name), vec, kind, status); } CS_HttpCameraKind CS_GetHttpCameraKind(CS_Source source, CS_Status* status) { - return cs::GetHttpCameraKind(source, status); + return wpi::cs::GetHttpCameraKind(source, status); } void CS_SetHttpCameraUrls(CS_Source source, const struct WPI_String* urls, int count, CS_Status* status) { - wpi::SmallVector vec; + wpi::util::SmallVector vec; vec.reserve(count); for (int i = 0; i < count; ++i) { - vec.emplace_back(wpi::to_string_view(&urls[i])); + vec.emplace_back(wpi::util::to_string_view(&urls[i])); } - cs::SetHttpCameraUrls(source, vec, status); + wpi::cs::SetHttpCameraUrls(source, vec, status); } WPI_String* CS_GetHttpCameraUrls(CS_Source source, int* count, CS_Status* status) { - auto urls = cs::GetHttpCameraUrls(source, status); + auto urls = wpi::cs::GetHttpCameraUrls(source, status); WPI_String* out = WPI_AllocateStringArray(urls.size()); *count = urls.size(); for (size_t i = 0; i < urls.size(); ++i) { - cs::ConvertToC(&out[i], urls[i]); + wpi::cs::ConvertToC(&out[i], urls[i]); } return out; } diff --git a/cscore/src/main/native/cpp/HttpCameraImpl.hpp b/cscore/src/main/native/cpp/HttpCameraImpl.hpp index a7ce5780c9..0a5e1e6080 100644 --- a/cscore/src/main/native/cpp/HttpCameraImpl.hpp +++ b/cscore/src/main/native/cpp/HttpCameraImpl.hpp @@ -23,12 +23,12 @@ #include "wpi/util/condition_variable.hpp" #include "wpi/util/raw_istream.hpp" -namespace cs { +namespace wpi::cs { class HttpCameraImpl : public SourceImpl { public: HttpCameraImpl(std::string_view name, CS_HttpCameraKind kind, - wpi::Logger& logger, Notifier& notifier, Telemetry& telemetry); + wpi::util::Logger& logger, Notifier& notifier, Telemetry& telemetry); ~HttpCameraImpl() override; void Start() override; @@ -99,14 +99,14 @@ class HttpCameraImpl : public SourceImpl { void StreamThreadMain(); // Functions used by StreamThreadMain() - wpi::HttpConnection* DeviceStreamConnect( - wpi::SmallVectorImpl& boundary); - void DeviceStream(wpi::raw_istream& is, std::string_view boundary); - bool DeviceStreamFrame(wpi::raw_istream& is, std::string& imageBuf); + wpi::net::HttpConnection* DeviceStreamConnect( + wpi::util::SmallVectorImpl& boundary); + void DeviceStream(wpi::util::raw_istream& is, std::string_view boundary); + bool DeviceStreamFrame(wpi::util::raw_istream& is, std::string& imageBuf); // The camera settings thread void SettingsThreadMain(); - void DeviceSendSettings(wpi::HttpRequest& req); + void DeviceSendSettings(wpi::net::HttpRequest& req); // The monitor thread void MonitorThreadMain(); @@ -122,31 +122,31 @@ class HttpCameraImpl : public SourceImpl { // // The camera connections - std::unique_ptr m_streamConn; - std::unique_ptr m_settingsConn; + std::unique_ptr m_streamConn; + std::unique_ptr m_settingsConn; CS_HttpCameraKind m_kind; - std::vector m_locations; + std::vector m_locations; size_t m_nextLocation{0}; int m_prefLocation{-1}; // preferred location std::atomic_int m_frameCount{0}; - wpi::condition_variable m_sinkEnabledCond; + wpi::util::condition_variable m_sinkEnabledCond; - wpi::StringMap m_settings; - wpi::condition_variable m_settingsCond; + wpi::util::StringMap m_settings; + wpi::util::condition_variable m_settingsCond; - wpi::StringMap m_streamSettings; + wpi::util::StringMap m_streamSettings; std::atomic_bool m_streamSettingsUpdated{false}; - wpi::condition_variable m_monitorCond; + wpi::util::condition_variable m_monitorCond; }; class AxisCameraImpl : public HttpCameraImpl { public: - AxisCameraImpl(std::string_view name, wpi::Logger& logger, Notifier& notifier, + AxisCameraImpl(std::string_view name, wpi::util::Logger& logger, Notifier& notifier, Telemetry& telemetry) : HttpCameraImpl{name, CS_HTTP_AXIS, logger, notifier, telemetry} {} #if 0 @@ -158,6 +158,6 @@ class AxisCameraImpl : public HttpCameraImpl { bool CacheProperties(CS_Status* status) const override; }; -} // namespace cs +} // namespace wpi::cs #endif // CSCORE_HTTPCAMERAIMPL_HPP_ diff --git a/cscore/src/main/native/cpp/Image.hpp b/cscore/src/main/native/cpp/Image.hpp index 993f7d44d3..867cacf00d 100644 --- a/cscore/src/main/native/cpp/Image.hpp +++ b/cscore/src/main/native/cpp/Image.hpp @@ -13,7 +13,7 @@ #include "default_init_allocator.hpp" #include "wpi/cs/cscore_cpp.hpp" -namespace cs { +namespace wpi::cs { class Frame; @@ -129,6 +129,6 @@ class Image { int jpegQuality{-1}; }; -} // namespace cs +} // namespace wpi::cs #endif // CSCORE_IMAGE_HPP_ diff --git a/cscore/src/main/native/cpp/Instance.cpp b/cscore/src/main/native/cpp/Instance.cpp index 22b0496df5..e4baccbddb 100644 --- a/cscore/src/main/native/cpp/Instance.cpp +++ b/cscore/src/main/native/cpp/Instance.cpp @@ -13,12 +13,12 @@ #include "wpi/util/fs.hpp" #include "wpi/util/print.hpp" -using namespace cs; +using namespace wpi::cs; static void def_log_func(unsigned int level, const char* file, unsigned int line, const char* msg) { if (level == 20) { - wpi::print(stderr, "CS: {}\n", msg); + wpi::util::print(stderr, "CS: {}\n", msg); return; } @@ -32,7 +32,7 @@ static void def_log_func(unsigned int level, const char* file, } else { return; } - wpi::print(stderr, "CS: {}: {} ({}:{})\n", levelmsg, msg, + wpi::util::print(stderr, "CS: {}: {} ({}:{})\n", levelmsg, msg, // NOLINTNEXTLINE(build/include_what_you_use) fs::path{file}.filename().string(), line); } diff --git a/cscore/src/main/native/cpp/Instance.hpp b/cscore/src/main/native/cpp/Instance.hpp index 679c9c9db4..93224e56bf 100644 --- a/cscore/src/main/native/cpp/Instance.hpp +++ b/cscore/src/main/native/cpp/Instance.hpp @@ -20,7 +20,7 @@ #include "UsbCameraListener.hpp" #include "wpi/util/Logger.hpp" -namespace cs { +namespace wpi::cs { struct SourceData { SourceData(CS_SourceKind kind_, std::shared_ptr source_) @@ -51,7 +51,7 @@ class Instance { void Shutdown(); - wpi::Logger logger; + wpi::util::Logger logger; Notifier notifier; Telemetry telemetry; NetworkListener networkListener; @@ -62,7 +62,7 @@ class Instance { UnlimitedHandleResource m_sinks; public: - wpi::EventLoopRunner eventLoop; + wpi::net::EventLoopRunner eventLoop; std::pair> FindSink(const SinkImpl& sink); std::pair> FindSource( @@ -87,16 +87,16 @@ class Instance { void DestroySink(CS_Sink handle); std::span EnumerateSourceHandles( - wpi::SmallVectorImpl& vec) { + wpi::util::SmallVectorImpl& vec) { return m_sources.GetAll(vec); } - std::span EnumerateSinkHandles(wpi::SmallVectorImpl& vec) { + std::span EnumerateSinkHandles(wpi::util::SmallVectorImpl& vec) { return m_sinks.GetAll(vec); } std::span EnumerateSourceSinks(CS_Source source, - wpi::SmallVectorImpl& vec) { + wpi::util::SmallVectorImpl& vec) { vec.clear(); m_sinks.ForEach([&](CS_Sink sinkHandle, const SinkData& data) { if (source == data.sourceHandle.load()) { @@ -110,6 +110,6 @@ class Instance { Instance(); }; -} // namespace cs +} // namespace wpi::cs #endif // CSCORE_INSTANCE_HPP_ diff --git a/cscore/src/main/native/cpp/JpegUtil.cpp b/cscore/src/main/native/cpp/JpegUtil.cpp index 50b8e50384..90e6c6c446 100644 --- a/cscore/src/main/native/cpp/JpegUtil.cpp +++ b/cscore/src/main/native/cpp/JpegUtil.cpp @@ -9,7 +9,7 @@ #include "wpi/util/StringExtras.hpp" #include "wpi/util/raw_istream.hpp" -namespace cs { +namespace wpi::cs { // DHT data for MJPEG images that don't have it. static const unsigned char dhtData[] = { @@ -67,7 +67,7 @@ bool GetJpegSize(std::string_view data, int* width, int* height) { return false; } - data = wpi::substr(data, 2); // Get to the first block + data = wpi::util::substr(data, 2); // Get to the first block for (;;) { if (data.size() < 4) { return false; // EOF @@ -92,7 +92,7 @@ bool GetJpegSize(std::string_view data, int* width, int* height) { return true; } // Go to the next block - data = wpi::substr(data, bytes[2] * 256 + bytes[3] + 2); + data = wpi::util::substr(data, bytes[2] * 256 + bytes[3] + 2); } } @@ -105,7 +105,7 @@ bool JpegNeedsDHT(const char* data, size_t* size, size_t* locSOF) { *locSOF = *size; // Search until SOS for DHT tag - sdata = wpi::substr(sdata, 2); // Get to the first block + sdata = wpi::util::substr(sdata, 2); // Get to the first block for (;;) { if (sdata.size() < 4) { return false; // EOF @@ -124,7 +124,7 @@ bool JpegNeedsDHT(const char* data, size_t* size, size_t* locSOF) { *locSOF = sdata.data() - data; // SOF } // Go to the next block - sdata = wpi::substr(sdata, bytes[2] * 256 + bytes[3] + 2); + sdata = wpi::util::substr(sdata, bytes[2] * 256 + bytes[3] + 2); } // Only add DHT if we also found SOF (insertion point) @@ -139,14 +139,14 @@ std::string_view JpegGetDHT() { return {reinterpret_cast(dhtData), sizeof(dhtData)}; } -static inline void ReadInto(wpi::raw_istream& is, std::string& buf, +static inline void ReadInto(wpi::util::raw_istream& is, std::string& buf, size_t len) { size_t oldSize = buf.size(); buf.resize(oldSize + len); is.read(&(*buf.begin()) + oldSize, len); } -bool ReadJpeg(wpi::raw_istream& is, std::string& buf, int* width, int* height) { +bool ReadJpeg(wpi::util::raw_istream& is, std::string& buf, int* width, int* height) { // in case we don't get a SOF *width = 0; *height = 0; @@ -234,4 +234,4 @@ bool ReadJpeg(wpi::raw_istream& is, std::string& buf, int* width, int* height) { } } -} // namespace cs +} // namespace wpi::cs diff --git a/cscore/src/main/native/cpp/JpegUtil.hpp b/cscore/src/main/native/cpp/JpegUtil.hpp index d43c3dcaf9..16bf34d683 100644 --- a/cscore/src/main/native/cpp/JpegUtil.hpp +++ b/cscore/src/main/native/cpp/JpegUtil.hpp @@ -8,11 +8,11 @@ #include #include -namespace wpi { +namespace wpi::util { class raw_istream; } // namespace wpi -namespace cs { +namespace wpi::cs { bool IsJpeg(std::string_view data); @@ -22,8 +22,8 @@ bool JpegNeedsDHT(const char* data, size_t* size, size_t* locSOF); std::string_view JpegGetDHT(); -bool ReadJpeg(wpi::raw_istream& is, std::string& buf, int* width, int* height); +bool ReadJpeg(wpi::util::raw_istream& is, std::string& buf, int* width, int* height); -} // namespace cs +} // namespace wpi::cs #endif // CSCORE_JPEGUTIL_HPP_ diff --git a/cscore/src/main/native/cpp/Log.cpp b/cscore/src/main/native/cpp/Log.cpp index 4a249ec3f8..4bde2d2ee2 100644 --- a/cscore/src/main/native/cpp/Log.cpp +++ b/cscore/src/main/native/cpp/Log.cpp @@ -4,7 +4,7 @@ #include "Log.hpp" -void cs::NamedLogV(wpi::Logger& logger, unsigned int level, const char* file, +void wpi::cs::NamedLogV(wpi::util::Logger& logger, unsigned int level, const char* file, unsigned int line, std::string_view name, fmt::string_view format, fmt::format_args args) { fmt::memory_buffer out; diff --git a/cscore/src/main/native/cpp/Log.hpp b/cscore/src/main/native/cpp/Log.hpp index d5f2371853..cff3606199 100644 --- a/cscore/src/main/native/cpp/Log.hpp +++ b/cscore/src/main/native/cpp/Log.hpp @@ -9,14 +9,14 @@ #include "wpi/util/Logger.hpp" -namespace cs { +namespace wpi::cs { -void NamedLogV(wpi::Logger& logger, unsigned int level, const char* file, +void NamedLogV(wpi::util::Logger& logger, unsigned int level, const char* file, unsigned int line, std::string_view name, fmt::string_view format, fmt::format_args args); template -inline void NamedLog(wpi::Logger& logger, unsigned int level, const char* file, +inline void NamedLog(wpi::util::Logger& logger, unsigned int level, const char* file, unsigned int line, std::string_view name, const S& format, Args&&... args) { if (logger.HasLogger() && level >= logger.min_level()) { @@ -25,7 +25,7 @@ inline void NamedLog(wpi::Logger& logger, unsigned int level, const char* file, } } -} // namespace cs +} // namespace wpi::cs #define LOG(level, format, ...) \ WPI_LOG(m_logger, level, format __VA_OPT__(, ) __VA_ARGS__) @@ -53,11 +53,11 @@ inline void NamedLog(wpi::Logger& logger, unsigned int level, const char* file, format __VA_OPT__(, ) __VA_ARGS__) #define SERROR(format, ...) \ - SLOG(::wpi::WPI_LOG_ERROR, format __VA_OPT__(, ) __VA_ARGS__) + SLOG(::wpi::util::WPI_LOG_ERROR, format __VA_OPT__(, ) __VA_ARGS__) #define SWARNING(format, ...) \ - SLOG(::wpi::WPI_LOG_WARNING, format __VA_OPT__(, ) __VA_ARGS__) + SLOG(::wpi::util::WPI_LOG_WARNING, format __VA_OPT__(, ) __VA_ARGS__) #define SINFO(format, ...) \ - SLOG(::wpi::WPI_LOG_INFO, format __VA_OPT__(, ) __VA_ARGS__) + SLOG(::wpi::util::WPI_LOG_INFO, format __VA_OPT__(, ) __VA_ARGS__) #ifdef NDEBUG #define SDEBUG(format, ...) \ @@ -77,15 +77,15 @@ inline void NamedLog(wpi::Logger& logger, unsigned int level, const char* file, } while (0) #else #define SDEBUG(format, ...) \ - SLOG(::wpi::WPI_LOG_DEBUG, format __VA_OPT__(, ) __VA_ARGS__) + SLOG(::wpi::util::WPI_LOG_DEBUG, format __VA_OPT__(, ) __VA_ARGS__) #define SDEBUG1(format, ...) \ - SLOG(::wpi::WPI_LOG_DEBUG1, format __VA_OPT__(, ) __VA_ARGS__) + SLOG(::wpi::util::WPI_LOG_DEBUG1, format __VA_OPT__(, ) __VA_ARGS__) #define SDEBUG2(format, ...) \ - SLOG(::wpi::WPI_LOG_DEBUG2, format __VA_OPT__(, ) __VA_ARGS__) + SLOG(::wpi::util::WPI_LOG_DEBUG2, format __VA_OPT__(, ) __VA_ARGS__) #define SDEBUG3(format, ...) \ - SLOG(::wpi::WPI_LOG_DEBUG3, format __VA_OPT__(, ) __VA_ARGS__) + SLOG(::wpi::util::WPI_LOG_DEBUG3, format __VA_OPT__(, ) __VA_ARGS__) #define SDEBUG4(format, ...) \ - SLOG(::wpi::WPI_LOG_DEBUG4, format __VA_OPT__(, ) __VA_ARGS__) + SLOG(::wpi::util::WPI_LOG_DEBUG4, format __VA_OPT__(, ) __VA_ARGS__) #endif #endif // CSCORE_LOG_HPP_ diff --git a/cscore/src/main/native/cpp/MjpegServerImpl.cpp b/cscore/src/main/native/cpp/MjpegServerImpl.cpp index 990dbc5d8a..c3f0292586 100644 --- a/cscore/src/main/native/cpp/MjpegServerImpl.cpp +++ b/cscore/src/main/native/cpp/MjpegServerImpl.cpp @@ -26,7 +26,7 @@ #include "wpi/util/fmt/raw_ostream.hpp" #include "wpi/util/print.hpp" -using namespace cs; +using namespace wpi::cs; // The boundary used for the M-JPEG stream. // It separates the multipart stream of pictures @@ -75,22 +75,22 @@ static const char* startRootPage = "
\n"; static const char* endRootPage = "
"; -class MjpegServerImpl::ConnThread : public wpi::SafeThread { +class MjpegServerImpl::ConnThread : public wpi::util::SafeThread { public: - explicit ConnThread(std::string_view name, wpi::Logger& logger) + explicit ConnThread(std::string_view name, wpi::util::Logger& logger) : m_name(name), m_logger(logger) {} void Main() override; - bool ProcessCommand(wpi::raw_ostream& os, SourceImpl& source, + bool ProcessCommand(wpi::util::raw_ostream& os, SourceImpl& source, std::string_view parameters, bool respond); - void SendJSON(wpi::raw_ostream& os, SourceImpl& source, bool header); - void SendHTMLHeadTitle(wpi::raw_ostream& os) const; - void SendHTML(wpi::raw_ostream& os, SourceImpl& source, bool header); - void SendStream(wpi::raw_socket_ostream& os); + void SendJSON(wpi::util::raw_ostream& os, SourceImpl& source, bool header); + void SendHTMLHeadTitle(wpi::util::raw_ostream& os) const; + void SendHTML(wpi::util::raw_ostream& os, SourceImpl& source, bool header); + void SendStream(wpi::net::raw_socket_ostream& os); void ProcessRequest(); - std::unique_ptr m_stream; + std::unique_ptr m_stream; std::shared_ptr m_source; bool m_streaming = false; bool m_noStreaming = false; @@ -102,7 +102,7 @@ class MjpegServerImpl::ConnThread : public wpi::SafeThread { private: std::string m_name; - wpi::Logger& m_logger; + wpi::util::Logger& m_logger; std::string_view GetName() { return m_name; } @@ -134,10 +134,10 @@ class MjpegServerImpl::ConnThread : public wpi::SafeThread { // A browser should connect for each file and not serve files from its cache. // Using cached pictures would lead to showing old/outdated pictures. // Many browsers seem to ignore, or at least not always obey, those headers. -static void SendHeader(wpi::raw_ostream& os, int code, +static void SendHeader(wpi::util::raw_ostream& os, int code, std::string_view codeText, std::string_view contentType, std::string_view extra = {}) { - wpi::print(os, "HTTP/1.0 {} {}\r\n", code, codeText); + wpi::util::print(os, "HTTP/1.0 {} {}\r\n", code, codeText); os << "Connection: close\r\n" "Server: CameraServer/1.0\r\n" "Cache-Control: no-store, no-cache, must-revalidate, pre-check=0, " @@ -155,7 +155,7 @@ static void SendHeader(wpi::raw_ostream& os, int code, // Send error header and message // @param code HTTP error code (e.g. 404) // @param message Additional message text -static void SendError(wpi::raw_ostream& os, int code, +static void SendError(wpi::util::raw_ostream& os, int code, std::string_view message) { std::string_view codeText, extra, baseMessage; switch (code) { @@ -195,21 +195,21 @@ static void SendError(wpi::raw_ostream& os, int code, } // Perform a command specified by HTTP GET parameters. -bool MjpegServerImpl::ConnThread::ProcessCommand(wpi::raw_ostream& os, +bool MjpegServerImpl::ConnThread::ProcessCommand(wpi::util::raw_ostream& os, SourceImpl& source, std::string_view parameters, bool respond) { - wpi::SmallString<256> responseBuf; - wpi::raw_svector_ostream response{responseBuf}; + wpi::util::SmallString<256> responseBuf; + wpi::util::raw_svector_ostream response{responseBuf}; // command format: param1=value1¶m2=value2... while (!parameters.empty()) { // split out next param and value std::string_view rawParam, rawValue; - std::tie(rawParam, parameters) = wpi::split(parameters, '&'); + std::tie(rawParam, parameters) = wpi::util::split(parameters, '&'); if (rawParam.empty()) { continue; // ignore "&&" } - std::tie(rawParam, rawValue) = wpi::split(rawParam, '='); + std::tie(rawParam, rawValue) = wpi::util::split(rawParam, '='); if (rawParam.empty() || rawValue.empty()) { continue; // ignore "param=" } @@ -217,8 +217,8 @@ bool MjpegServerImpl::ConnThread::ProcessCommand(wpi::raw_ostream& os, // unescape param bool error = false; - wpi::SmallString<64> paramBuf; - std::string_view param = wpi::UnescapeURI(rawParam, paramBuf, &error); + wpi::util::SmallString<64> paramBuf; + std::string_view param = wpi::net::UnescapeURI(rawParam, paramBuf, &error); if (error) { auto estr = fmt::format("could not unescape parameter \"{}\"", rawParam); SendError(os, 500, estr); @@ -227,8 +227,8 @@ bool MjpegServerImpl::ConnThread::ProcessCommand(wpi::raw_ostream& os, } // unescape value - wpi::SmallString<64> valueBuf; - std::string_view value = wpi::UnescapeURI(rawValue, valueBuf, &error); + wpi::util::SmallString<64> valueBuf; + std::string_view value = wpi::net::UnescapeURI(rawValue, valueBuf, &error); if (error) { auto estr = fmt::format("could not unescape value \"{}\"", rawValue); SendError(os, 500, estr); @@ -239,9 +239,9 @@ bool MjpegServerImpl::ConnThread::ProcessCommand(wpi::raw_ostream& os, // Handle resolution, compression, and FPS. These are handled locally // rather than passed to the source. if (param == "resolution") { - auto [widthStr, heightStr] = wpi::split(value, 'x'); - int width = wpi::parse_integer(widthStr, 10).value_or(-1); - int height = wpi::parse_integer(heightStr, 10).value_or(-1); + auto [widthStr, heightStr] = wpi::util::split(value, 'x'); + int width = wpi::util::parse_integer(widthStr, 10).value_or(-1); + int height = wpi::util::parse_integer(heightStr, 10).value_or(-1); if (width < 0) { response << param << ": \"width is not an integer\"\r\n"; SWARNING("HTTP parameter \"{}\" width \"{}\" is not an integer", param, @@ -261,7 +261,7 @@ bool MjpegServerImpl::ConnThread::ProcessCommand(wpi::raw_ostream& os, } if (param == "fps") { - if (auto v = wpi::parse_integer(value, 10)) { + if (auto v = wpi::util::parse_integer(value, 10)) { m_fps = v.value(); response << param << ": \"ok\"\r\n"; } else { @@ -273,7 +273,7 @@ bool MjpegServerImpl::ConnThread::ProcessCommand(wpi::raw_ostream& os, } if (param == "compression") { - if (auto v = wpi::parse_integer(value, 10)) { + if (auto v = wpi::util::parse_integer(value, 10)) { m_compression = v.value(); response << param << ": \"ok\"\r\n"; } else { @@ -303,8 +303,8 @@ bool MjpegServerImpl::ConnThread::ProcessCommand(wpi::raw_ostream& os, case CS_PROP_BOOLEAN: case CS_PROP_INTEGER: case CS_PROP_ENUM: { - if (auto v = wpi::parse_integer(value, 10)) { - wpi::print(response, "{}: {}\r\n", param, v.value()); + if (auto v = wpi::util::parse_integer(value, 10)) { + wpi::util::print(response, "{}: {}\r\n", param, v.value()); SDEBUG4("HTTP parameter \"{}\" value {}", param, value); source.SetProperty(prop, v.value(), &status); } else { @@ -335,13 +335,13 @@ bool MjpegServerImpl::ConnThread::ProcessCommand(wpi::raw_ostream& os, } void MjpegServerImpl::ConnThread::SendHTMLHeadTitle( - wpi::raw_ostream& os) const { + wpi::util::raw_ostream& os) const { os << "" << m_name << " CameraServer" << ""; } // Send the root html file with controls for all the settable properties. -void MjpegServerImpl::ConnThread::SendHTML(wpi::raw_ostream& os, +void MjpegServerImpl::ConnThread::SendHTML(wpi::util::raw_ostream& os, SourceImpl& source, bool header) { if (header) { SendHeader(os, 200, "OK", "text/html"); @@ -349,19 +349,19 @@ void MjpegServerImpl::ConnThread::SendHTML(wpi::raw_ostream& os, SendHTMLHeadTitle(os); os << startRootPage; - wpi::SmallVector properties_vec; + wpi::util::SmallVector properties_vec; CS_Status status = 0; for (auto prop : source.EnumerateProperties(properties_vec, &status)) { - wpi::SmallString<128> name_buf; + wpi::util::SmallString<128> name_buf; auto name = source.GetPropertyName(prop, name_buf, &status); - if (wpi::starts_with(name, "raw_")) { + if (wpi::util::starts_with(name, "raw_")) { continue; } auto kind = source.GetPropertyKind(prop); - wpi::print(os, "

\n", name); + wpi::util::print(os, "

\n", name); switch (kind) { case CS_PROP_BOOLEAN: - wpi::print(os, + wpi::util::print(os, "\n", name, min, max, valI, step); - wpi::print(os, "{1}\n", name, + wpi::util::print(os, "{1}\n", name, valI); break; } @@ -395,29 +395,29 @@ void MjpegServerImpl::ConnThread::SendHTML(wpi::raw_ostream& os, continue; // skip empty choices } // replace any non-printable characters in name with spaces - wpi::SmallString<128> ch_name; + wpi::util::SmallString<128> ch_name; for (char ch : *choice) { - ch_name.push_back(wpi::isPrint(ch) ? ch : ' '); + ch_name.push_back(wpi::util::isPrint(ch) ? ch : ' '); } - wpi::print(os, + wpi::util::print(os, "\n", name, j, + wpi::util::print(os, " />\n", name, j, ch_name.str()); } break; } case CS_PROP_STRING: { - wpi::SmallString<128> strval_buf; - wpi::print(os, + wpi::util::SmallString<128> strval_buf; + wpi::util::print(os, "\n", name, source.GetStringProperty(prop, strval_buf, &status)); - wpi::print(os, + wpi::util::print(os, "\n", name); @@ -473,7 +473,7 @@ void MjpegServerImpl::ConnThread::SendHTML(wpi::raw_ostream& os, os << "unknown"; break; } - wpi::print(os, "{}{}{}", mode.width, + wpi::util::print(os, "{}{}{}", mode.width, mode.height, mode.fps); } os << "\n"; @@ -482,14 +482,14 @@ void MjpegServerImpl::ConnThread::SendHTML(wpi::raw_ostream& os, } // Send a JSON file which is contains information about the source parameters. -void MjpegServerImpl::ConnThread::SendJSON(wpi::raw_ostream& os, +void MjpegServerImpl::ConnThread::SendJSON(wpi::util::raw_ostream& os, SourceImpl& source, bool header) { if (header) { SendHeader(os, 200, "OK", "application/json"); } os << "{\n\"controls\": [\n"; - wpi::SmallVector properties_vec; + wpi::util::SmallVector properties_vec; bool first = true; CS_Status status = 0; for (auto prop : source.EnumerateProperties(properties_vec, &status)) { @@ -499,27 +499,27 @@ void MjpegServerImpl::ConnThread::SendJSON(wpi::raw_ostream& os, os << ",\n"; } os << '{'; - wpi::SmallString<128> name_buf; + wpi::util::SmallString<128> name_buf; auto name = source.GetPropertyName(prop, name_buf, &status); auto kind = source.GetPropertyKind(prop); - wpi::print(os, "\n\"name\": \"{}\"", name); - wpi::print(os, ",\n\"id\": \"{}\"", prop); - wpi::print(os, ",\n\"type\": \"{}\"", static_cast(kind)); - wpi::print(os, ",\n\"min\": \"{}\"", source.GetPropertyMin(prop, &status)); - wpi::print(os, ",\n\"max\": \"{}\"", source.GetPropertyMax(prop, &status)); - wpi::print(os, ",\n\"step\": \"{}\"", + wpi::util::print(os, "\n\"name\": \"{}\"", name); + wpi::util::print(os, ",\n\"id\": \"{}\"", prop); + wpi::util::print(os, ",\n\"type\": \"{}\"", static_cast(kind)); + wpi::util::print(os, ",\n\"min\": \"{}\"", source.GetPropertyMin(prop, &status)); + wpi::util::print(os, ",\n\"max\": \"{}\"", source.GetPropertyMax(prop, &status)); + wpi::util::print(os, ",\n\"step\": \"{}\"", source.GetPropertyStep(prop, &status)); - wpi::print(os, ",\n\"default\": \"{}\"", + wpi::util::print(os, ",\n\"default\": \"{}\"", source.GetPropertyDefault(prop, &status)); os << ",\n\"value\": \""; switch (kind) { case CS_PROP_BOOLEAN: case CS_PROP_INTEGER: case CS_PROP_ENUM: - wpi::print(os, "{}", source.GetProperty(prop, &status)); + wpi::util::print(os, "{}", source.GetProperty(prop, &status)); break; case CS_PROP_STRING: { - wpi::SmallString<128> strval_buf; + wpi::util::SmallString<128> strval_buf; os << source.GetStringProperty(prop, strval_buf, &status); break; } @@ -542,11 +542,11 @@ void MjpegServerImpl::ConnThread::SendJSON(wpi::raw_ostream& os, os << ", "; } // replace any non-printable characters in name with spaces - wpi::SmallString<128> ch_name; + wpi::util::SmallString<128> ch_name; for (char ch : *choice) { ch_name.push_back(std::isprint(ch) ? ch : ' '); } - wpi::print(os, "\"{}\": \"{}\"", j, ch_name.str()); + wpi::util::print(os, "\"{}\": \"{}\"", j, ch_name.str()); } os << "}\n"; } @@ -588,19 +588,19 @@ void MjpegServerImpl::ConnThread::SendJSON(wpi::raw_ostream& os, os << "unknown"; break; } - wpi::print(os, "\",\n\"width\": \"{}\"", mode.width); - wpi::print(os, ",\n\"height\": \"{}\"", mode.height); - wpi::print(os, ",\n\"fps\": \"{}\"", mode.fps); + wpi::util::print(os, "\",\n\"width\": \"{}\"", mode.width); + wpi::util::print(os, ",\n\"height\": \"{}\"", mode.height); + wpi::util::print(os, ",\n\"fps\": \"{}\"", mode.fps); os << '}'; } os << "\n]\n}\n"; os.flush(); } -MjpegServerImpl::MjpegServerImpl(std::string_view name, wpi::Logger& logger, +MjpegServerImpl::MjpegServerImpl(std::string_view name, wpi::util::Logger& logger, Notifier& notifier, Telemetry& telemetry, std::string_view listenAddress, int port, - std::unique_ptr acceptor) + std::unique_ptr acceptor) : SinkImpl{name, logger, notifier, telemetry}, m_listenAddress(listenAddress), m_port(port), @@ -663,7 +663,7 @@ void MjpegServerImpl::Stop() { } // Send HTTP response and a stream of JPG-frames -void MjpegServerImpl::ConnThread::SendStream(wpi::raw_socket_ostream& os) { +void MjpegServerImpl::ConnThread::SendStream(wpi::net::raw_socket_ostream& os) { if (m_noStreaming) { SERROR("Too many simultaneous client streams"); SendError(os, 503, "Too many simultaneous streams"); @@ -672,8 +672,8 @@ void MjpegServerImpl::ConnThread::SendStream(wpi::raw_socket_ostream& os) { os.SetUnbuffered(); - wpi::SmallString<256> header; - wpi::raw_svector_ostream oss{header}; + wpi::util::SmallString<256> header; + wpi::util::raw_svector_ostream oss{header}; SendHeader(oss, 200, "OK", "multipart/x-mixed-replace;boundary=" BOUNDARY); os << oss.str(); @@ -774,8 +774,8 @@ void MjpegServerImpl::ConnThread::SendStream(wpi::raw_socket_ostream& os) { double timestamp = lastFrameTime / 1000000.0; header.clear(); oss << "\r\n--" BOUNDARY "\r\n" << "Content-Type: image/jpeg\r\n"; - wpi::print(oss, "Content-Length: {}\r\n", size); - wpi::print(oss, "X-Timestamp: {}\r\n", timestamp); + wpi::util::print(oss, "Content-Length: {}\r\n", size); + wpi::util::print(oss, "X-Timestamp: {}\r\n", timestamp); oss << "\r\n"; os << oss.str(); if (addDHT) { @@ -792,11 +792,11 @@ void MjpegServerImpl::ConnThread::SendStream(wpi::raw_socket_ostream& os) { } void MjpegServerImpl::ConnThread::ProcessRequest() { - wpi::raw_socket_istream is{*m_stream}; - wpi::raw_socket_ostream os{*m_stream, true}; + wpi::net::raw_socket_istream is{*m_stream}; + wpi::net::raw_socket_ostream os{*m_stream, true}; // Read the request string from the stream - wpi::SmallString<128> reqBuf; + wpi::util::SmallString<128> reqBuf; std::string_view req = is.getline(reqBuf, 4096); if (is.has_error()) { SDEBUG("error getting request string"); @@ -813,14 +813,14 @@ void MjpegServerImpl::ConnThread::ProcessRequest() { // compatibility, others are for Axis camera compatibility. if ((pos = req.find("POST /stream")) != std::string_view::npos) { kind = kStream; - parameters = wpi::substr(wpi::substr(req, req.find('?', pos + 12)), 1); + parameters = wpi::util::substr(wpi::util::substr(req, req.find('?', pos + 12)), 1); } else if ((pos = req.find("GET /?action=stream")) != std::string_view::npos) { kind = kStream; - parameters = wpi::substr(wpi::substr(req, req.find('&', pos + 19)), 1); + parameters = wpi::util::substr(wpi::util::substr(req, req.find('&', pos + 19)), 1); } else if ((pos = req.find("GET /stream.mjpg")) != std::string_view::npos) { kind = kStream; - parameters = wpi::substr(wpi::substr(req, req.find('?', pos + 16)), 1); + parameters = wpi::util::substr(wpi::util::substr(req, req.find('?', pos + 16)), 1); } else if (req.find("GET /settings") != std::string_view::npos && req.find(".json") != std::string_view::npos) { kind = kGetSettings; @@ -836,7 +836,7 @@ void MjpegServerImpl::ConnThread::ProcessRequest() { } else if ((pos = req.find("GET /?action=command")) != std::string_view::npos) { kind = kCommand; - parameters = wpi::substr(wpi::substr(req, req.find('&', pos + 20)), 1); + parameters = wpi::util::substr(wpi::util::substr(req, req.find('&', pos + 20)), 1); } else if (req.find("GET / ") != std::string_view::npos || req == "GET /\n") { kind = kRootPage; } else { @@ -849,14 +849,14 @@ void MjpegServerImpl::ConnThread::ProcessRequest() { pos = parameters.find_first_not_of( "abcdefghijklmnopqrstuvwxyzABCDEFGHIJKLMNOPQRSTUVWXYZ_" "-=&1234567890%./"); - parameters = wpi::substr(parameters, 0, pos); + parameters = wpi::util::substr(parameters, 0, pos); SDEBUG("command parameters: \"{}\"", parameters); // Read the rest of the HTTP request. // The end of the request is marked by a single, empty line - wpi::SmallString<128> lineBuf; + wpi::util::SmallString<128> lineBuf; for (;;) { - if (wpi::starts_with(is.getline(lineBuf, 4096), "\n")) { + if (wpi::util::starts_with(is.getline(lineBuf, 4096), "\n")) { break; } if (is.has_error()) { @@ -960,7 +960,7 @@ void MjpegServerImpl::ServerThreadMain() { std::scoped_lock lock(m_mutex); // Find unoccupied worker thread, or create one if necessary auto it = std::find_if(m_connThreads.begin(), m_connThreads.end(), - [](const wpi::SafeThreadOwner& owner) { + [](const wpi::util::SafeThreadOwner& owner) { auto thr = owner.GetThread(); return !thr || !thr->m_stream; }); @@ -974,7 +974,7 @@ void MjpegServerImpl::ServerThreadMain() { auto nstreams = std::count_if(m_connThreads.begin(), m_connThreads.end(), - [](const wpi::SafeThreadOwner& owner) { + [](const wpi::util::SafeThreadOwner& owner) { auto thr = owner.GetThread(); return thr && thr->m_streaming; }); @@ -1013,7 +1013,7 @@ void MjpegServerImpl::SetSourceImpl(std::shared_ptr source) { } } -namespace cs { +namespace wpi::cs { CS_Sink CreateMjpegServer(std::string_view name, std::string_view listenAddress, int port, CS_Status* status) { @@ -1022,8 +1022,8 @@ CS_Sink CreateMjpegServer(std::string_view name, std::string_view listenAddress, CS_SINK_MJPEG, std::make_shared( name, inst.logger, inst.notifier, inst.telemetry, listenAddress, port, - std::unique_ptr( - new wpi::TCPAcceptor(port, listenAddress, inst.logger)))); + std::unique_ptr( + new wpi::net::TCPAcceptor(port, listenAddress, inst.logger)))); } std::string GetMjpegServerListenAddress(CS_Sink sink, CS_Status* status) { @@ -1044,25 +1044,25 @@ int GetMjpegServerPort(CS_Sink sink, CS_Status* status) { return static_cast(*data->sink).GetPort(); } -} // namespace cs +} // namespace wpi::cs extern "C" { CS_Sink CS_CreateMjpegServer(const struct WPI_String* name, const struct WPI_String* listenAddress, int port, CS_Status* status) { - return cs::CreateMjpegServer(wpi::to_string_view(name), - wpi::to_string_view(listenAddress), port, + return wpi::cs::CreateMjpegServer(wpi::util::to_string_view(name), + wpi::util::to_string_view(listenAddress), port, status); } void CS_GetMjpegServerListenAddress(CS_Sink sink, WPI_String* listenAddress, CS_Status* status) { - cs::ConvertToC(listenAddress, cs::GetMjpegServerListenAddress(sink, status)); + wpi::cs::ConvertToC(listenAddress, wpi::cs::GetMjpegServerListenAddress(sink, status)); } int CS_GetMjpegServerPort(CS_Sink sink, CS_Status* status) { - return cs::GetMjpegServerPort(sink, status); + return wpi::cs::GetMjpegServerPort(sink, status); } } // extern "C" diff --git a/cscore/src/main/native/cpp/MjpegServerImpl.hpp b/cscore/src/main/native/cpp/MjpegServerImpl.hpp index 1f216ab008..c15019f5ae 100644 --- a/cscore/src/main/native/cpp/MjpegServerImpl.hpp +++ b/cscore/src/main/native/cpp/MjpegServerImpl.hpp @@ -22,16 +22,16 @@ #include "wpi/util/raw_istream.hpp" #include "wpi/util/raw_ostream.hpp" -namespace cs { +namespace wpi::cs { class SourceImpl; class MjpegServerImpl : public SinkImpl { public: - MjpegServerImpl(std::string_view name, wpi::Logger& logger, + MjpegServerImpl(std::string_view name, wpi::util::Logger& logger, Notifier& notifier, Telemetry& telemetry, std::string_view listenAddress, int port, - std::unique_ptr acceptor); + std::unique_ptr acceptor); ~MjpegServerImpl() override; void Stop(); @@ -49,11 +49,11 @@ class MjpegServerImpl : public SinkImpl { std::string m_listenAddress; int m_port; - std::unique_ptr m_acceptor; + std::unique_ptr m_acceptor; std::atomic_bool m_active; // set to false to terminate threads std::thread m_serverThread; - std::vector> m_connThreads; + std::vector> m_connThreads; // property indices int m_widthProp; @@ -63,6 +63,6 @@ class MjpegServerImpl : public SinkImpl { int m_fpsProp; }; -} // namespace cs +} // namespace wpi::cs #endif // CSCORE_MJPEGSERVERIMPL_HPP_ diff --git a/cscore/src/main/native/cpp/NetworkListener.hpp b/cscore/src/main/native/cpp/NetworkListener.hpp index ec79792792..4eb3c0cd97 100644 --- a/cscore/src/main/native/cpp/NetworkListener.hpp +++ b/cscore/src/main/native/cpp/NetworkListener.hpp @@ -9,13 +9,13 @@ #include "wpi/util/Logger.hpp" -namespace cs { +namespace wpi::cs { class Notifier; class NetworkListener { public: - NetworkListener(wpi::Logger& logger, Notifier& notifier); + NetworkListener(wpi::util::Logger& logger, Notifier& notifier); ~NetworkListener(); void Start(); @@ -26,6 +26,6 @@ class NetworkListener { std::unique_ptr m_impl; }; -} // namespace cs +} // namespace wpi::cs #endif // CSCORE_NETWORKLISTENER_HPP_ diff --git a/cscore/src/main/native/cpp/Notifier.cpp b/cscore/src/main/native/cpp/Notifier.cpp index c5808285a1..851d5fc657 100644 --- a/cscore/src/main/native/cpp/Notifier.cpp +++ b/cscore/src/main/native/cpp/Notifier.cpp @@ -11,7 +11,7 @@ #include "SinkImpl.hpp" #include "SourceImpl.hpp" -using namespace cs; +using namespace wpi::cs; Notifier::Notifier() {} diff --git a/cscore/src/main/native/cpp/Notifier.hpp b/cscore/src/main/native/cpp/Notifier.hpp index c5e2975228..580c5ca623 100644 --- a/cscore/src/main/native/cpp/Notifier.hpp +++ b/cscore/src/main/native/cpp/Notifier.hpp @@ -12,14 +12,14 @@ #include "wpi/cs/cscore_cpp.hpp" #include "wpi/util/CallbackManager.hpp" -namespace cs { +namespace wpi::cs { class SinkImpl; class SourceImpl; namespace impl { -struct ListenerData : public wpi::CallbackListenerData< +struct ListenerData : public wpi::util::CallbackListenerData< std::function> { ListenerData() = default; ListenerData(std::function callback_, @@ -32,7 +32,7 @@ struct ListenerData : public wpi::CallbackListenerData< }; class NotifierThread - : public wpi::CallbackThread { + : public wpi::util::CallbackThread { public: NotifierThread(std::function on_start, std::function on_exit) : CallbackThread(std::move(on_start), std::move(on_exit)) {} @@ -53,7 +53,7 @@ class NotifierThread } // namespace impl -class Notifier : public wpi::CallbackManager { +class Notifier : public wpi::util::CallbackManager { friend class NotifierTest; public: @@ -87,6 +87,6 @@ class Notifier : public wpi::CallbackManager { void NotifyUsbCamerasChanged(); }; -} // namespace cs +} // namespace wpi::cs #endif // CSCORE_NOTIFIER_HPP_ diff --git a/cscore/src/main/native/cpp/PropertyContainer.cpp b/cscore/src/main/native/cpp/PropertyContainer.cpp index 84fd6acc8e..0a2d2d8cb3 100644 --- a/cscore/src/main/native/cpp/PropertyContainer.cpp +++ b/cscore/src/main/native/cpp/PropertyContainer.cpp @@ -13,7 +13,7 @@ #include "wpi/util/SmallVector.hpp" #include "wpi/util/json.hpp" -using namespace cs; +using namespace wpi::cs; int PropertyContainer::GetPropertyIndex(std::string_view name) const { // We can't fail, so instead we create a new index if caching fails. @@ -32,7 +32,7 @@ int PropertyContainer::GetPropertyIndex(std::string_view name) const { } std::span PropertyContainer::EnumerateProperties( - wpi::SmallVectorImpl& vec, CS_Status* status) const { + wpi::util::SmallVectorImpl& vec, CS_Status* status) const { if (!m_properties_cached && !CacheProperties(status)) { return {}; } @@ -59,7 +59,7 @@ CS_PropertyKind PropertyContainer::GetPropertyKind(int property) const { } std::string_view PropertyContainer::GetPropertyName( - int property, wpi::SmallVectorImpl& buf, CS_Status* status) const { + int property, wpi::util::SmallVectorImpl& buf, CS_Status* status) const { if (!m_properties_cached && !CacheProperties(status)) { return {}; } @@ -168,7 +168,7 @@ int PropertyContainer::GetPropertyDefault(int property, } std::string_view PropertyContainer::GetStringProperty( - int property, wpi::SmallVectorImpl& buf, CS_Status* status) const { + int property, wpi::util::SmallVectorImpl& buf, CS_Status* status) const { if (!m_properties_cached && !CacheProperties(status)) { return {}; } @@ -238,15 +238,15 @@ bool PropertyContainer::CacheProperties(CS_Status* status) const { return true; } -bool PropertyContainer::SetPropertiesJson(const wpi::json& config, - wpi::Logger& logger, +bool PropertyContainer::SetPropertiesJson(const wpi::util::json& config, + wpi::util::Logger& logger, std::string_view logName, CS_Status* status) { for (auto&& prop : config) { std::string name; try { name = prop.at("name").get(); - } catch (const wpi::json::exception& e) { + } catch (const wpi::util::json::exception& e) { WPI_WARNING(logger, "{}: SetConfigJson: could not read property name: {}", logName, e.what()); continue; @@ -270,7 +270,7 @@ bool PropertyContainer::SetPropertiesJson(const wpi::json& config, logName, name, val); SetProperty(n, val, status); } - } catch (const wpi::json::exception& e) { + } catch (const wpi::util::json::exception& e) { WPI_WARNING(logger, "{}: SetConfigJson: could not read property value: {}", logName, e.what()); @@ -281,12 +281,12 @@ bool PropertyContainer::SetPropertiesJson(const wpi::json& config, return true; } -wpi::json PropertyContainer::GetPropertiesJsonObject(CS_Status* status) { - wpi::json j; - wpi::SmallVector propVec; +wpi::util::json PropertyContainer::GetPropertiesJsonObject(CS_Status* status) { + wpi::util::json j; + wpi::util::SmallVector propVec; for (int p : EnumerateProperties(propVec, status)) { - wpi::json prop; - wpi::SmallString<128> strBuf; + wpi::util::json prop; + wpi::util::SmallString<128> strBuf; prop.emplace("name", GetPropertyName(p, strBuf, status)); switch (GetPropertyKind(p)) { case CS_PROP_BOOLEAN: diff --git a/cscore/src/main/native/cpp/PropertyContainer.hpp b/cscore/src/main/native/cpp/PropertyContainer.hpp index f830390e76..4cf95ea321 100644 --- a/cscore/src/main/native/cpp/PropertyContainer.hpp +++ b/cscore/src/main/native/cpp/PropertyContainer.hpp @@ -19,24 +19,24 @@ #include "wpi/util/json_fwd.hpp" #include "wpi/util/mutex.hpp" -namespace wpi { +namespace wpi::util { class Logger; template class SmallVectorImpl; } // namespace wpi -namespace cs { +namespace wpi::cs { class PropertyContainer { public: virtual ~PropertyContainer() = default; int GetPropertyIndex(std::string_view name) const; - std::span EnumerateProperties(wpi::SmallVectorImpl& vec, + std::span EnumerateProperties(wpi::util::SmallVectorImpl& vec, CS_Status* status) const; CS_PropertyKind GetPropertyKind(int property) const; std::string_view GetPropertyName(int property, - wpi::SmallVectorImpl& buf, + wpi::util::SmallVectorImpl& buf, CS_Status* status) const; int GetProperty(int property, CS_Status* status) const; virtual void SetProperty(int property, int value, CS_Status* status); @@ -45,16 +45,16 @@ class PropertyContainer { int GetPropertyStep(int property, CS_Status* status) const; int GetPropertyDefault(int property, CS_Status* status) const; std::string_view GetStringProperty(int property, - wpi::SmallVectorImpl& buf, + wpi::util::SmallVectorImpl& buf, CS_Status* status) const; virtual void SetStringProperty(int property, std::string_view value, CS_Status* status); std::vector GetEnumPropertyChoices(int property, CS_Status* status) const; - bool SetPropertiesJson(const wpi::json& config, wpi::Logger& logger, + bool SetPropertiesJson(const wpi::util::json& config, wpi::util::Logger& logger, std::string_view logName, CS_Status* status); - wpi::json GetPropertiesJsonObject(CS_Status* status); + wpi::util::json GetPropertiesJsonObject(CS_Status* status); protected: // Get a property; must be called with m_mutex held. @@ -116,13 +116,13 @@ class PropertyContainer { // should not be called again) mutable std::atomic_bool m_properties_cached{false}; - mutable wpi::mutex m_mutex; + mutable wpi::util::mutex m_mutex; // Cached properties (protected with m_mutex) mutable std::vector> m_propertyData; - mutable wpi::StringMap m_properties; + mutable wpi::util::StringMap m_properties; }; -} // namespace cs +} // namespace wpi::cs #endif // CSCORE_PROPERTYCONTAINER_HPP_ diff --git a/cscore/src/main/native/cpp/PropertyImpl.cpp b/cscore/src/main/native/cpp/PropertyImpl.cpp index 09be1ed6d7..eda385283e 100644 --- a/cscore/src/main/native/cpp/PropertyImpl.cpp +++ b/cscore/src/main/native/cpp/PropertyImpl.cpp @@ -4,7 +4,7 @@ #include "PropertyImpl.hpp" -using namespace cs; +using namespace wpi::cs; PropertyImpl::PropertyImpl(std::string_view name_) : name{name_} {} PropertyImpl::PropertyImpl(std::string_view name_, CS_PropertyKind kind_, diff --git a/cscore/src/main/native/cpp/PropertyImpl.hpp b/cscore/src/main/native/cpp/PropertyImpl.hpp index 06860ed8f2..b53bc98963 100644 --- a/cscore/src/main/native/cpp/PropertyImpl.hpp +++ b/cscore/src/main/native/cpp/PropertyImpl.hpp @@ -12,7 +12,7 @@ #include "wpi/cs/cscore_c.h" #include "wpi/util/Signal.h" -namespace cs { +namespace wpi::cs { // Property data class PropertyImpl { @@ -45,9 +45,9 @@ class PropertyImpl { bool valueSet{false}; // emitted when value changes - wpi::sig::Signal<> changed; + wpi::util::sig::Signal<> changed; }; -} // namespace cs +} // namespace wpi::cs #endif // CSCORE_PROPERTYIMPL_HPP_ diff --git a/cscore/src/main/native/cpp/RawSinkImpl.cpp b/cscore/src/main/native/cpp/RawSinkImpl.cpp index 1d69221b45..b6fa170c78 100644 --- a/cscore/src/main/native/cpp/RawSinkImpl.cpp +++ b/cscore/src/main/native/cpp/RawSinkImpl.cpp @@ -10,16 +10,16 @@ #include "Instance.hpp" #include "wpi/cs/cscore_raw.h" -using namespace cs; +using namespace wpi::cs; -RawSinkImpl::RawSinkImpl(std::string_view name, wpi::Logger& logger, +RawSinkImpl::RawSinkImpl(std::string_view name, wpi::util::Logger& logger, Notifier& notifier, Telemetry& telemetry) : SinkImpl{name, logger, notifier, telemetry} { m_active = true; // m_thread = std::thread(&RawSinkImpl::ThreadMain, this); } -RawSinkImpl::RawSinkImpl(std::string_view name, wpi::Logger& logger, +RawSinkImpl::RawSinkImpl(std::string_view name, wpi::util::Logger& logger, Notifier& notifier, Telemetry& telemetry, std::function processFrame) : SinkImpl{name, logger, notifier, telemetry} {} @@ -151,7 +151,7 @@ void RawSinkImpl::ThreadMain() { Disable(); } -namespace cs { +namespace wpi::cs { static constexpr unsigned SinkMask = CS_SINK_CV | CS_SINK_RAW; CS_Sink CreateRawSink(std::string_view name, bool isCv, CS_Status* status) { @@ -202,30 +202,30 @@ uint64_t GrabSinkFrameTimeoutLastTime(CS_Sink sink, WPI_RawFrame& image, .GrabFrame(image, timeout, lastFrameTime); } -} // namespace cs +} // namespace wpi::cs extern "C" { CS_Sink CS_CreateRawSink(const struct WPI_String* name, CS_Bool isCv, CS_Status* status) { - return cs::CreateRawSink(wpi::to_string_view(name), isCv, status); + return wpi::cs::CreateRawSink(wpi::util::to_string_view(name), isCv, status); } CS_Sink CS_CreateRawSinkCallback( const struct WPI_String* name, CS_Bool isCv, void* data, void (*processFrame)(void* data, uint64_t time), CS_Status* status) { - return cs::CreateRawSinkCallback( - wpi::to_string_view(name), isCv, + return wpi::cs::CreateRawSinkCallback( + wpi::util::to_string_view(name), isCv, [=](uint64_t time) { processFrame(data, time); }, status); } uint64_t CS_GrabRawSinkFrame(CS_Sink sink, struct WPI_RawFrame* image, CS_Status* status) { - return cs::GrabSinkFrame(sink, *image, status); + return wpi::cs::GrabSinkFrame(sink, *image, status); } uint64_t CS_GrabRawSinkFrameTimeout(CS_Sink sink, struct WPI_RawFrame* image, double timeout, CS_Status* status) { - return cs::GrabSinkFrameTimeout(sink, *image, timeout, status); + return wpi::cs::GrabSinkFrameTimeout(sink, *image, timeout, status); } uint64_t CS_GrabRawSinkFrameTimeoutWithFrameTime(CS_Sink sink, @@ -233,7 +233,7 @@ uint64_t CS_GrabRawSinkFrameTimeoutWithFrameTime(CS_Sink sink, double timeout, uint64_t lastFrameTime, CS_Status* status) { - return cs::GrabSinkFrameTimeoutLastTime(sink, *image, timeout, lastFrameTime, + return wpi::cs::GrabSinkFrameTimeoutLastTime(sink, *image, timeout, lastFrameTime, status); } diff --git a/cscore/src/main/native/cpp/RawSinkImpl.hpp b/cscore/src/main/native/cpp/RawSinkImpl.hpp index c356c11215..3e923181d2 100644 --- a/cscore/src/main/native/cpp/RawSinkImpl.hpp +++ b/cscore/src/main/native/cpp/RawSinkImpl.hpp @@ -17,14 +17,14 @@ #include "wpi/cs/cscore_raw.h" #include "wpi/util/condition_variable.hpp" -namespace cs { +namespace wpi::cs { class SourceImpl; class RawSinkImpl : public SinkImpl { public: - RawSinkImpl(std::string_view name, wpi::Logger& logger, Notifier& notifier, + RawSinkImpl(std::string_view name, wpi::util::Logger& logger, Notifier& notifier, Telemetry& telemetry); - RawSinkImpl(std::string_view name, wpi::Logger& logger, Notifier& notifier, + RawSinkImpl(std::string_view name, wpi::util::Logger& logger, Notifier& notifier, Telemetry& telemetry, std::function processFrame); ~RawSinkImpl() override; @@ -48,6 +48,6 @@ class RawSinkImpl : public SinkImpl { std::thread m_thread; std::function m_processFrame; }; -} // namespace cs +} // namespace wpi::cs #endif // CSCORE_RAWSINKIMPL_HPP_ diff --git a/cscore/src/main/native/cpp/RawSourceImpl.cpp b/cscore/src/main/native/cpp/RawSourceImpl.cpp index c8b2130468..edf4d7e961 100644 --- a/cscore/src/main/native/cpp/RawSourceImpl.cpp +++ b/cscore/src/main/native/cpp/RawSourceImpl.cpp @@ -11,9 +11,9 @@ #include "wpi/cs/cscore_raw.h" #include "wpi/util/timestamp.h" -using namespace cs; +using namespace wpi::cs; -RawSourceImpl::RawSourceImpl(std::string_view name, wpi::Logger& logger, +RawSourceImpl::RawSourceImpl(std::string_view name, wpi::util::Logger& logger, Notifier& notifier, Telemetry& telemetry, const VideoMode& mode) : ConfigurableSourceImpl{name, logger, notifier, telemetry, mode} {} @@ -21,13 +21,13 @@ RawSourceImpl::RawSourceImpl(std::string_view name, wpi::Logger& logger, RawSourceImpl::~RawSourceImpl() = default; void RawSourceImpl::PutFrame(const WPI_RawFrame& image) { - auto currentTime = wpi::Now(); + auto currentTime = wpi::util::Now(); std::string_view data_view{reinterpret_cast(image.data), image.size}; SourceImpl::PutFrame(static_cast(image.pixelFormat), image.width, image.height, data_view, currentTime); } -namespace cs { +namespace wpi::cs { static constexpr unsigned SourceMask = CS_SOURCE_CV | CS_SOURCE_RAW; CS_Source CreateRawSource(std::string_view name, bool isCv, @@ -49,18 +49,18 @@ void PutSourceFrame(CS_Source source, const WPI_RawFrame& image, static_cast(*data->source).PutFrame(image); } -} // namespace cs +} // namespace wpi::cs extern "C" { CS_Source CS_CreateRawSource(const struct WPI_String* name, CS_Bool isCv, const CS_VideoMode* mode, CS_Status* status) { - return cs::CreateRawSource(wpi::to_string_view(name), isCv, - static_cast(*mode), status); + return wpi::cs::CreateRawSource(wpi::util::to_string_view(name), isCv, + static_cast(*mode), status); } void CS_PutRawSourceFrame(CS_Source source, const struct WPI_RawFrame* image, CS_Status* status) { - return cs::PutSourceFrame(source, *image, status); + return wpi::cs::PutSourceFrame(source, *image, status); } } // extern "C" diff --git a/cscore/src/main/native/cpp/RawSourceImpl.hpp b/cscore/src/main/native/cpp/RawSourceImpl.hpp index 294080a793..37aec634d2 100644 --- a/cscore/src/main/native/cpp/RawSourceImpl.hpp +++ b/cscore/src/main/native/cpp/RawSourceImpl.hpp @@ -16,11 +16,11 @@ #include "SourceImpl.hpp" #include "wpi/cs/cscore_raw.h" -namespace cs { +namespace wpi::cs { class RawSourceImpl : public ConfigurableSourceImpl { public: - RawSourceImpl(std::string_view name, wpi::Logger& logger, Notifier& notifier, + RawSourceImpl(std::string_view name, wpi::util::Logger& logger, Notifier& notifier, Telemetry& telemetry, const VideoMode& mode); ~RawSourceImpl() override; @@ -31,6 +31,6 @@ class RawSourceImpl : public ConfigurableSourceImpl { std::atomic_bool m_connected{true}; }; -} // namespace cs +} // namespace wpi::cs #endif // CSCORE_RAWSOURCEIMPL_HPP_ diff --git a/cscore/src/main/native/cpp/SinkImpl.cpp b/cscore/src/main/native/cpp/SinkImpl.cpp index 88869e3089..847cbcffae 100644 --- a/cscore/src/main/native/cpp/SinkImpl.cpp +++ b/cscore/src/main/native/cpp/SinkImpl.cpp @@ -13,9 +13,9 @@ #include "wpi/util/SmallString.hpp" #include "wpi/util/json.hpp" -using namespace cs; +using namespace wpi::cs; -SinkImpl::SinkImpl(std::string_view name, wpi::Logger& logger, +SinkImpl::SinkImpl(std::string_view name, wpi::util::Logger& logger, Notifier& notifier, Telemetry& telemetry) : m_logger(logger), m_notifier(notifier), @@ -37,7 +37,7 @@ void SinkImpl::SetDescription(std::string_view description) { } std::string_view SinkImpl::GetDescription( - wpi::SmallVectorImpl& buf) const { + wpi::util::SmallVectorImpl& buf) const { std::scoped_lock lock(m_mutex); buf.append(m_description.begin(), m_description.end()); return {buf.data(), buf.size()}; @@ -113,7 +113,7 @@ std::string SinkImpl::GetError() const { return std::string{m_source->GetCurFrame().GetError()}; } -std::string_view SinkImpl::GetError(wpi::SmallVectorImpl& buf) const { +std::string_view SinkImpl::GetError(wpi::util::SmallVectorImpl& buf) const { std::scoped_lock lock(m_mutex); if (!m_source) { return "no source connected"; @@ -126,10 +126,10 @@ std::string_view SinkImpl::GetError(wpi::SmallVectorImpl& buf) const { } bool SinkImpl::SetConfigJson(std::string_view config, CS_Status* status) { - wpi::json j; + wpi::util::json j; try { - j = wpi::json::parse(config); - } catch (const wpi::json::parse_error& e) { + j = wpi::util::json::parse(config); + } catch (const wpi::util::json::parse_error& e) { SWARNING("SetConfigJson: parse error at byte {}: {}", e.byte, e.what()); *status = CS_PROPERTY_WRITE_FAILED; return false; @@ -137,7 +137,7 @@ bool SinkImpl::SetConfigJson(std::string_view config, CS_Status* status) { return SetConfigJson(j, status); } -bool SinkImpl::SetConfigJson(const wpi::json& config, CS_Status* status) { +bool SinkImpl::SetConfigJson(const wpi::util::json& config, CS_Status* status) { if (config.count("properties") != 0) { SetPropertiesJson(config.at("properties"), m_logger, GetName(), status); } @@ -147,16 +147,16 @@ bool SinkImpl::SetConfigJson(const wpi::json& config, CS_Status* status) { std::string SinkImpl::GetConfigJson(CS_Status* status) { std::string rv; - wpi::raw_string_ostream os(rv); + wpi::util::raw_string_ostream os(rv); GetConfigJsonObject(status).dump(os, 4); os.flush(); return rv; } -wpi::json SinkImpl::GetConfigJsonObject(CS_Status* status) { - wpi::json j; +wpi::util::json SinkImpl::GetConfigJsonObject(CS_Status* status) { + wpi::util::json j; - wpi::json props = GetPropertiesJsonObject(status); + wpi::util::json props = GetPropertiesJsonObject(status); if (props.is_array()) { j.emplace("properties", props); } @@ -199,7 +199,7 @@ void SinkImpl::UpdatePropertyValue(int property, bool setString, int value, void SinkImpl::SetSourceImpl(std::shared_ptr source) {} -namespace cs { +namespace wpi::cs { static constexpr unsigned SinkMask = CS_SINK_CV | CS_SINK_RAW; void SetSinkDescription(CS_Sink sink, std::string_view description, @@ -221,7 +221,7 @@ std::string GetSinkError(CS_Sink sink, CS_Status* status) { return data->sink->GetError(); } -std::string_view GetSinkError(CS_Sink sink, wpi::SmallVectorImpl& buf, +std::string_view GetSinkError(CS_Sink sink, wpi::util::SmallVectorImpl& buf, CS_Status* status) { auto data = Instance::GetInstance().GetSink(sink); if (!data || (data->kind & SinkMask) == 0) { @@ -240,22 +240,22 @@ void SetSinkEnabled(CS_Sink sink, bool enabled, CS_Status* status) { data->sink->SetEnabled(enabled); } -} // namespace cs +} // namespace wpi::cs extern "C" { void CS_SetSinkDescription(CS_Sink sink, const struct WPI_String* description, CS_Status* status) { - return cs::SetSinkDescription(sink, wpi::to_string_view(description), status); + return wpi::cs::SetSinkDescription(sink, wpi::util::to_string_view(description), status); } void CS_GetSinkError(CS_Sink sink, struct WPI_String* error, CS_Status* status) { - wpi::SmallString<128> buf; - cs::ConvertToC(error, cs::GetSinkError(sink, buf, status)); + wpi::util::SmallString<128> buf; + wpi::cs::ConvertToC(error, wpi::cs::GetSinkError(sink, buf, status)); } void CS_SetSinkEnabled(CS_Sink sink, CS_Bool enabled, CS_Status* status) { - return cs::SetSinkEnabled(sink, enabled, status); + return wpi::cs::SetSinkEnabled(sink, enabled, status); } } // extern "C" diff --git a/cscore/src/main/native/cpp/SinkImpl.hpp b/cscore/src/main/native/cpp/SinkImpl.hpp index 910ff14567..60da9a16cc 100644 --- a/cscore/src/main/native/cpp/SinkImpl.hpp +++ b/cscore/src/main/native/cpp/SinkImpl.hpp @@ -14,7 +14,7 @@ #include "wpi/util/json_fwd.hpp" #include "wpi/util/mutex.hpp" -namespace cs { +namespace wpi::cs { class Frame; class Notifier; @@ -22,7 +22,7 @@ class Telemetry; class SinkImpl : public PropertyContainer { public: - explicit SinkImpl(std::string_view name, wpi::Logger& logger, + explicit SinkImpl(std::string_view name, wpi::util::Logger& logger, Notifier& notifier, Telemetry& telemetry); ~SinkImpl() override; SinkImpl(const SinkImpl& queue) = delete; @@ -31,7 +31,7 @@ class SinkImpl : public PropertyContainer { std::string_view GetName() const { return m_name; } void SetDescription(std::string_view description); - std::string_view GetDescription(wpi::SmallVectorImpl& buf) const; + std::string_view GetDescription(wpi::util::SmallVectorImpl& buf) const; void Enable(); void Disable(); @@ -45,12 +45,12 @@ class SinkImpl : public PropertyContainer { } std::string GetError() const; - std::string_view GetError(wpi::SmallVectorImpl& buf) const; + std::string_view GetError(wpi::util::SmallVectorImpl& buf) const; bool SetConfigJson(std::string_view config, CS_Status* status); - virtual bool SetConfigJson(const wpi::json& config, CS_Status* status); + virtual bool SetConfigJson(const wpi::util::json& config, CS_Status* status); std::string GetConfigJson(CS_Status* status); - virtual wpi::json GetConfigJsonObject(CS_Status* status); + virtual wpi::util::json GetConfigJsonObject(CS_Status* status); protected: // PropertyContainer implementation @@ -61,7 +61,7 @@ class SinkImpl : public PropertyContainer { virtual void SetSourceImpl(std::shared_ptr source); protected: - wpi::Logger& m_logger; + wpi::util::Logger& m_logger; Notifier& m_notifier; Telemetry& m_telemetry; @@ -72,6 +72,6 @@ class SinkImpl : public PropertyContainer { int m_enabledCount{0}; }; -} // namespace cs +} // namespace wpi::cs #endif // CSCORE_SINKIMPL_HPP_ diff --git a/cscore/src/main/native/cpp/SourceImpl.cpp b/cscore/src/main/native/cpp/SourceImpl.cpp index 446c3c7bf6..4e06ab53b6 100644 --- a/cscore/src/main/native/cpp/SourceImpl.cpp +++ b/cscore/src/main/native/cpp/SourceImpl.cpp @@ -18,11 +18,11 @@ #include "wpi/util/json.hpp" #include "wpi/util/timestamp.h" -using namespace cs; +using namespace wpi::cs; static constexpr size_t kMaxImagesAvail = 32; -SourceImpl::SourceImpl(std::string_view name, wpi::Logger& logger, +SourceImpl::SourceImpl(std::string_view name, wpi::util::Logger& logger, Notifier& notifier, Telemetry& telemetry) : m_logger(logger), m_notifier(notifier), @@ -50,7 +50,7 @@ void SourceImpl::SetDescription(std::string_view description) { } std::string_view SourceImpl::GetDescription( - wpi::SmallVectorImpl& buf) const { + wpi::util::SmallVectorImpl& buf) const { std::scoped_lock lock(m_mutex); buf.append(m_description.begin(), m_description.end()); return {buf.data(), buf.size()}; @@ -94,7 +94,7 @@ Frame SourceImpl::GetNextFrame(double timeout, Frame::Time lastFrameTime) { if (!m_frameCv.wait_for( lock, std::chrono::milliseconds(static_cast(timeout * 1000)), [=, this] { return m_frame.GetTime() != lastFrameTime; })) { - m_frame = Frame{*this, "timed out getting frame", wpi::Now(), + m_frame = Frame{*this, "timed out getting frame", wpi::util::Now(), WPI_TIMESRC_UNKNOWN}; } return m_frame; @@ -179,10 +179,10 @@ bool SourceImpl::SetFPS(int fps, CS_Status* status) { } bool SourceImpl::SetConfigJson(std::string_view config, CS_Status* status) { - wpi::json j; + wpi::util::json j; try { - j = wpi::json::parse(config); - } catch (const wpi::json::parse_error& e) { + j = wpi::util::json::parse(config); + } catch (const wpi::util::json::parse_error& e) { SWARNING("SetConfigJson: parse error at byte {}: {}", e.byte, e.what()); *status = CS_PROPERTY_WRITE_FAILED; return false; @@ -190,34 +190,34 @@ bool SourceImpl::SetConfigJson(std::string_view config, CS_Status* status) { return SetConfigJson(j, status); } -bool SourceImpl::SetConfigJson(const wpi::json& config, CS_Status* status) { +bool SourceImpl::SetConfigJson(const wpi::util::json& config, CS_Status* status) { VideoMode mode; // pixel format if (config.count("pixel format") != 0) { try { auto str = config.at("pixel format").get(); - if (wpi::equals_lower(str, "mjpeg")) { - mode.pixelFormat = cs::VideoMode::kMJPEG; - } else if (wpi::equals_lower(str, "yuyv")) { - mode.pixelFormat = cs::VideoMode::kYUYV; - } else if (wpi::equals_lower(str, "rgb565")) { - mode.pixelFormat = cs::VideoMode::kRGB565; - } else if (wpi::equals_lower(str, "bgr")) { - mode.pixelFormat = cs::VideoMode::kBGR; - } else if (wpi::equals_lower(str, "bgra")) { - mode.pixelFormat = cs::VideoMode::kBGRA; - } else if (wpi::equals_lower(str, "gray")) { - mode.pixelFormat = cs::VideoMode::kGray; - } else if (wpi::equals_lower(str, "y16")) { - mode.pixelFormat = cs::VideoMode::kY16; - } else if (wpi::equals_lower(str, "uyvy")) { - mode.pixelFormat = cs::VideoMode::kUYVY; + if (wpi::util::equals_lower(str, "mjpeg")) { + mode.pixelFormat = wpi::cs::VideoMode::kMJPEG; + } else if (wpi::util::equals_lower(str, "yuyv")) { + mode.pixelFormat = wpi::cs::VideoMode::kYUYV; + } else if (wpi::util::equals_lower(str, "rgb565")) { + mode.pixelFormat = wpi::cs::VideoMode::kRGB565; + } else if (wpi::util::equals_lower(str, "bgr")) { + mode.pixelFormat = wpi::cs::VideoMode::kBGR; + } else if (wpi::util::equals_lower(str, "bgra")) { + mode.pixelFormat = wpi::cs::VideoMode::kBGRA; + } else if (wpi::util::equals_lower(str, "gray")) { + mode.pixelFormat = wpi::cs::VideoMode::kGray; + } else if (wpi::util::equals_lower(str, "y16")) { + mode.pixelFormat = wpi::cs::VideoMode::kY16; + } else if (wpi::util::equals_lower(str, "uyvy")) { + mode.pixelFormat = wpi::cs::VideoMode::kUYVY; } else { SWARNING("SetConfigJson: could not understand pixel format value '{}'", str); } - } catch (const wpi::json::exception& e) { + } catch (const wpi::util::json::exception& e) { SWARNING("SetConfigJson: could not read pixel format: {}", e.what()); } } @@ -226,7 +226,7 @@ bool SourceImpl::SetConfigJson(const wpi::json& config, CS_Status* status) { if (config.count("width") != 0) { try { mode.width = config.at("width").get(); - } catch (const wpi::json::exception& e) { + } catch (const wpi::util::json::exception& e) { SWARNING("SetConfigJson: could not read width: {}", e.what()); } } @@ -235,7 +235,7 @@ bool SourceImpl::SetConfigJson(const wpi::json& config, CS_Status* status) { if (config.count("height") != 0) { try { mode.height = config.at("height").get(); - } catch (const wpi::json::exception& e) { + } catch (const wpi::util::json::exception& e) { SWARNING("SetConfigJson: could not read height: {}", e.what()); } } @@ -244,7 +244,7 @@ bool SourceImpl::SetConfigJson(const wpi::json& config, CS_Status* status) { if (config.count("fps") != 0) { try { mode.fps = config.at("fps").get(); - } catch (const wpi::json::exception& e) { + } catch (const wpi::util::json::exception& e) { SWARNING("SetConfigJson: could not read fps: {}", e.what()); } } @@ -258,9 +258,9 @@ bool SourceImpl::SetConfigJson(const wpi::json& config, CS_Status* status) { mode.pixelFormat, mode.width, mode.height, mode.fps); SetVideoMode(mode, status); } else { - if (mode.pixelFormat != cs::VideoMode::kUnknown) { + if (mode.pixelFormat != wpi::cs::VideoMode::kUnknown) { SINFO("SetConfigJson: setting pixelFormat {}", mode.pixelFormat); - SetPixelFormat(static_cast(mode.pixelFormat), + SetPixelFormat(static_cast(mode.pixelFormat), status); } if (mode.width != 0 && mode.height != 0) { @@ -280,7 +280,7 @@ bool SourceImpl::SetConfigJson(const wpi::json& config, CS_Status* status) { int val = config.at("brightness").get(); SINFO("SetConfigJson: setting brightness to {}", val); SetBrightness(val, status); - } catch (const wpi::json::exception& e) { + } catch (const wpi::util::json::exception& e) { SWARNING("SetConfigJson: could not read brightness: {}", e.what()); } } @@ -291,10 +291,10 @@ bool SourceImpl::SetConfigJson(const wpi::json& config, CS_Status* status) { auto& setting = config.at("white balance"); if (setting.is_string()) { auto str = setting.get(); - if (wpi::equals_lower(str, "auto")) { + if (wpi::util::equals_lower(str, "auto")) { SINFO("SetConfigJson: setting white balance to {}", "auto"); SetWhiteBalanceAuto(status); - } else if (wpi::equals_lower(str, "hold")) { + } else if (wpi::util::equals_lower(str, "hold")) { SINFO("SetConfigJson: setting white balance to {}", "hold current"); SetWhiteBalanceHoldCurrent(status); } else { @@ -307,7 +307,7 @@ bool SourceImpl::SetConfigJson(const wpi::json& config, CS_Status* status) { SINFO("SetConfigJson: setting white balance to {}", val); SetWhiteBalanceManual(val, status); } - } catch (const wpi::json::exception& e) { + } catch (const wpi::util::json::exception& e) { SWARNING("SetConfigJson: could not read white balance: {}", e.what()); } } @@ -318,10 +318,10 @@ bool SourceImpl::SetConfigJson(const wpi::json& config, CS_Status* status) { auto& setting = config.at("exposure"); if (setting.is_string()) { auto str = setting.get(); - if (wpi::equals_lower(str, "auto")) { + if (wpi::util::equals_lower(str, "auto")) { SINFO("SetConfigJson: setting exposure to {}", "auto"); SetExposureAuto(status); - } else if (wpi::equals_lower(str, "hold")) { + } else if (wpi::util::equals_lower(str, "hold")) { SINFO("SetConfigJson: setting exposure to {}", "hold current"); SetExposureHoldCurrent(status); } else { @@ -333,7 +333,7 @@ bool SourceImpl::SetConfigJson(const wpi::json& config, CS_Status* status) { SINFO("SetConfigJson: setting exposure to {}", val); SetExposureManual(val, status); } - } catch (const wpi::json::exception& e) { + } catch (const wpi::util::json::exception& e) { SWARNING("SetConfigJson: could not read exposure: {}", e.what()); } } @@ -348,14 +348,14 @@ bool SourceImpl::SetConfigJson(const wpi::json& config, CS_Status* status) { std::string SourceImpl::GetConfigJson(CS_Status* status) { std::string rv; - wpi::raw_string_ostream os(rv); + wpi::util::raw_string_ostream os(rv); GetConfigJsonObject(status).dump(os, 4); os.flush(); return rv; } -wpi::json SourceImpl::GetConfigJsonObject(CS_Status* status) { - wpi::json j; +wpi::util::json SourceImpl::GetConfigJsonObject(CS_Status* status) { + wpi::util::json j; // pixel format std::string_view pixelFormat; @@ -409,7 +409,7 @@ wpi::json SourceImpl::GetConfigJsonObject(CS_Status* status) { // TODO: output brightness, white balance, and exposure? // properties - wpi::json props = GetPropertiesJsonObject(status); + wpi::util::json props = GetPropertiesJsonObject(status); if (props.is_array()) { j.emplace("properties", props); } diff --git a/cscore/src/main/native/cpp/SourceImpl.hpp b/cscore/src/main/native/cpp/SourceImpl.hpp index abdcd96649..33842748bb 100644 --- a/cscore/src/main/native/cpp/SourceImpl.hpp +++ b/cscore/src/main/native/cpp/SourceImpl.hpp @@ -23,7 +23,7 @@ #include "wpi/util/json_fwd.hpp" #include "wpi/util/mutex.hpp" -namespace cs { +namespace wpi::cs { class Notifier; class Telemetry; @@ -32,7 +32,7 @@ class SourceImpl : public PropertyContainer { friend class Frame; public: - SourceImpl(std::string_view name, wpi::Logger& logger, Notifier& notifier, + SourceImpl(std::string_view name, wpi::util::Logger& logger, Notifier& notifier, Telemetry& telemetry); ~SourceImpl() override; SourceImpl(const SourceImpl& oth) = delete; @@ -43,7 +43,7 @@ class SourceImpl : public PropertyContainer { std::string_view GetName() const { return m_name; } void SetDescription(std::string_view description); - std::string_view GetDescription(wpi::SmallVectorImpl& buf) const; + std::string_view GetDescription(wpi::util::SmallVectorImpl& buf) const; void SetConnectionStrategy(CS_ConnectionStrategy strategy) { m_strategy = static_cast(strategy); @@ -126,9 +126,9 @@ class SourceImpl : public PropertyContainer { virtual bool SetFPS(int fps, CS_Status* status); bool SetConfigJson(std::string_view config, CS_Status* status); - virtual bool SetConfigJson(const wpi::json& config, CS_Status* status); + virtual bool SetConfigJson(const wpi::util::json& config, CS_Status* status); std::string GetConfigJson(CS_Status* status); - virtual wpi::json GetConfigJsonObject(CS_Status* status); + virtual wpi::util::json GetConfigJsonObject(CS_Status* status); std::vector EnumerateVideoModes(CS_Status* status) const; @@ -159,7 +159,7 @@ class SourceImpl : public PropertyContainer { // Current video mode mutable VideoMode m_mode; - wpi::Logger& m_logger; + wpi::util::Logger& m_logger; Notifier& m_notifier; Telemetry& m_telemetry; @@ -174,13 +174,13 @@ class SourceImpl : public PropertyContainer { std::atomic_int m_strategy{CS_CONNECTION_AUTO_MANAGE}; std::atomic_int m_numSinksEnabled{0}; - wpi::mutex m_frameMutex; - wpi::condition_variable m_frameCv; + wpi::util::mutex m_frameMutex; + wpi::util::condition_variable m_frameCv; bool m_destroyFrames{false}; // Pool of frames/images to reduce malloc traffic. - wpi::mutex m_poolMutex; + wpi::util::mutex m_poolMutex; std::vector> m_framesAvail; std::vector> m_imagesAvail; @@ -193,6 +193,6 @@ class SourceImpl : public PropertyContainer { Frame m_frame; }; -} // namespace cs +} // namespace wpi::cs #endif // CSCORE_SOURCEIMPL_HPP_ diff --git a/cscore/src/main/native/cpp/Telemetry.cpp b/cscore/src/main/native/cpp/Telemetry.cpp index 0b959b3c39..a52720b097 100644 --- a/cscore/src/main/native/cpp/Telemetry.cpp +++ b/cscore/src/main/native/cpp/Telemetry.cpp @@ -14,17 +14,17 @@ #include "wpi/util/DenseMap.hpp" #include "wpi/util/timestamp.h" -using namespace cs; +using namespace wpi::cs; -class Telemetry::Thread : public wpi::SafeThread { +class Telemetry::Thread : public wpi::util::SafeThread { public: explicit Thread(Notifier& notifier) : m_notifier(notifier) {} void Main() override; Notifier& m_notifier; - wpi::DenseMap, int64_t> m_user; - wpi::DenseMap, int64_t> m_current; + wpi::util::DenseMap, int64_t> m_user; + wpi::util::DenseMap, int64_t> m_current; double m_period = 0.0; double m_elapsed = 0.0; bool m_updated = false; diff --git a/cscore/src/main/native/cpp/Telemetry.hpp b/cscore/src/main/native/cpp/Telemetry.hpp index a4955b6c0c..51defeb5f8 100644 --- a/cscore/src/main/native/cpp/Telemetry.hpp +++ b/cscore/src/main/native/cpp/Telemetry.hpp @@ -8,7 +8,7 @@ #include "wpi/cs/cscore_cpp.hpp" #include "wpi/util/SafeThread.hpp" -namespace cs { +namespace wpi::cs { class Notifier; class SourceImpl; @@ -38,9 +38,9 @@ class Telemetry { Notifier& m_notifier; class Thread; - wpi::SafeThreadOwner m_owner; + wpi::util::SafeThreadOwner m_owner; }; -} // namespace cs +} // namespace wpi::cs #endif // CSCORE_TELEMETRY_HPP_ diff --git a/cscore/src/main/native/cpp/UnlimitedHandleResource.hpp b/cscore/src/main/native/cpp/UnlimitedHandleResource.hpp index 5d56167ef8..953d49a3e7 100644 --- a/cscore/src/main/native/cpp/UnlimitedHandleResource.hpp +++ b/cscore/src/main/native/cpp/UnlimitedHandleResource.hpp @@ -13,7 +13,7 @@ #include "wpi/util/SmallVector.hpp" #include "wpi/util/mutex.hpp" -namespace cs { +namespace wpi::cs { // The UnlimitedHandleResource class is a way to track handles. This version // allows an unlimited number of handles that are allocated sequentially. When @@ -34,7 +34,7 @@ namespace cs { // @tparam typeValue The type value stored in the handle // @tparam TMutex The mutex type to use template + typename TMutex = wpi::util::mutex> class UnlimitedHandleResource { public: UnlimitedHandleResource(const UnlimitedHandleResource&) = delete; @@ -50,7 +50,7 @@ class UnlimitedHandleResource { std::shared_ptr Free(THandle handle); template - std::span GetAll(wpi::SmallVectorImpl& vec); + std::span GetAll(wpi::util::SmallVectorImpl& vec); std::vector> FreeAll(); @@ -149,7 +149,7 @@ template template inline std::span UnlimitedHandleResource::GetAll( - wpi::SmallVectorImpl& vec) { + wpi::util::SmallVectorImpl& vec) { ForEach([&](THandle handle, const TStruct&) { vec.push_back(handle); }); return vec; } @@ -189,6 +189,6 @@ UnlimitedHandleResource::FindIf(F func) { return std::pair{0, nullptr}; } -} // namespace cs +} // namespace wpi::cs #endif // CSCORE_UNLIMITEDHANDLERESOURCE_HPP_ diff --git a/cscore/src/main/native/cpp/UsbCameraImplCommon.cpp b/cscore/src/main/native/cpp/UsbCameraImplCommon.cpp index 527960e17a..e6466a8f62 100644 --- a/cscore/src/main/native/cpp/UsbCameraImplCommon.cpp +++ b/cscore/src/main/native/cpp/UsbCameraImplCommon.cpp @@ -8,16 +8,16 @@ #include "wpi/cs/cscore_cpp.hpp" #include "wpi/util/MemAlloc.hpp" -using namespace cs; +using namespace wpi::cs; static void ConvertToC(CS_UsbCameraInfo* out, const UsbCameraInfo& in) { out->dev = in.dev; - cs::ConvertToC(&out->path, in.path); - cs::ConvertToC(&out->name, in.name); + wpi::cs::ConvertToC(&out->path, in.path); + wpi::cs::ConvertToC(&out->name, in.name); out->otherPaths = WPI_AllocateStringArray(in.otherPaths.size()); out->otherPathsCount = in.otherPaths.size(); for (size_t i = 0; i < in.otherPaths.size(); ++i) { - cs::ConvertToC(&out->otherPaths[i], in.otherPaths[i]); + wpi::cs::ConvertToC(&out->otherPaths[i], in.otherPaths[i]); } out->vendorId = in.vendorId; out->productId = in.productId; @@ -35,36 +35,36 @@ extern "C" { CS_Source CS_CreateUsbCameraDev(const struct WPI_String* name, int dev, CS_Status* status) { - return cs::CreateUsbCameraDev(wpi::to_string_view(name), dev, status); + return wpi::cs::CreateUsbCameraDev(wpi::util::to_string_view(name), dev, status); } CS_Source CS_CreateUsbCameraPath(const struct WPI_String* name, const struct WPI_String* path, CS_Status* status) { - return cs::CreateUsbCameraPath(wpi::to_string_view(name), - wpi::to_string_view(path), status); + return wpi::cs::CreateUsbCameraPath(wpi::util::to_string_view(name), + wpi::util::to_string_view(path), status); } void CS_SetUsbCameraPath(CS_Source source, const struct WPI_String* path, CS_Status* status) { - cs::SetUsbCameraPath(source, wpi::to_string_view(path), status); + wpi::cs::SetUsbCameraPath(source, wpi::util::to_string_view(path), status); } void CS_GetUsbCameraPath(CS_Source source, WPI_String* path, CS_Status* status) { - ConvertToC(path, cs::GetUsbCameraPath(source, status)); + ConvertToC(path, wpi::cs::GetUsbCameraPath(source, status)); } void CS_GetUsbCameraInfo(CS_Source source, CS_UsbCameraInfo* info, CS_Status* status) { - auto info_cpp = cs::GetUsbCameraInfo(source, status); + auto info_cpp = wpi::cs::GetUsbCameraInfo(source, status); ConvertToC(info, info_cpp); } CS_UsbCameraInfo* CS_EnumerateUsbCameras(int* count, CS_Status* status) { - auto cameras = cs::EnumerateUsbCameras(status); + auto cameras = wpi::cs::EnumerateUsbCameras(status); CS_UsbCameraInfo* out = static_cast( - wpi::safe_malloc(cameras.size() * sizeof(CS_UsbCameraInfo))); + wpi::util::safe_malloc(cameras.size() * sizeof(CS_UsbCameraInfo))); *count = cameras.size(); for (size_t i = 0; i < cameras.size(); ++i) { ConvertToC(&out[i], cameras[i]); diff --git a/cscore/src/main/native/cpp/UsbCameraListener.hpp b/cscore/src/main/native/cpp/UsbCameraListener.hpp index 467855c3e6..750f6e8444 100644 --- a/cscore/src/main/native/cpp/UsbCameraListener.hpp +++ b/cscore/src/main/native/cpp/UsbCameraListener.hpp @@ -9,13 +9,13 @@ #include "wpi/util/Logger.hpp" -namespace cs { +namespace wpi::cs { class Notifier; class UsbCameraListener { public: - UsbCameraListener(wpi::Logger& logger, Notifier& notifier); + UsbCameraListener(wpi::util::Logger& logger, Notifier& notifier); ~UsbCameraListener(); void Start(); @@ -26,6 +26,6 @@ class UsbCameraListener { std::unique_ptr m_impl; }; -} // namespace cs +} // namespace wpi::cs #endif // CSCORE_USBCAMERALISTENER_HPP_ diff --git a/cscore/src/main/native/cpp/c_util.hpp b/cscore/src/main/native/cpp/c_util.hpp index 7c328b5194..5fc3c46bc3 100644 --- a/cscore/src/main/native/cpp/c_util.hpp +++ b/cscore/src/main/native/cpp/c_util.hpp @@ -10,13 +10,13 @@ #include "wpi/util/string.h" -namespace cs { +namespace wpi::cs { inline void ConvertToC(struct WPI_String* output, std::string_view str) { char* write = WPI_AllocateString(output, str.size()); std::memcpy(write, str.data(), str.size()); } -} // namespace cs +} // namespace wpi::cs #endif // CSCORE_C_UTIL_HPP_ diff --git a/cscore/src/main/native/cpp/cscore_c.cpp b/cscore/src/main/native/cpp/cscore_c.cpp index 941bf78895..083686c417 100644 --- a/cscore/src/main/native/cpp/cscore_c.cpp +++ b/cscore/src/main/native/cpp/cscore_c.cpp @@ -15,17 +15,17 @@ #include "wpi/util/MemAlloc.hpp" #include "wpi/util/SmallString.hpp" -static CS_Event ConvertToC(const cs::RawEvent& rawEvent) { +static CS_Event ConvertToC(const wpi::cs::RawEvent& rawEvent) { CS_Event event; event.kind = static_cast(static_cast(rawEvent.kind)); event.source = rawEvent.sourceHandle; event.sink = rawEvent.sinkHandle; - cs::ConvertToC(&event.name, rawEvent.name); + wpi::cs::ConvertToC(&event.name, rawEvent.name); event.mode = rawEvent.mode; event.property = rawEvent.propertyHandle; event.propertyKind = rawEvent.propertyKind; event.value = rawEvent.value; - cs::ConvertToC(&event.name, rawEvent.valueStr); + wpi::cs::ConvertToC(&event.name, rawEvent.valueStr); event.listener = rawEvent.listener; return event; } @@ -34,7 +34,7 @@ template static O* ConvertToC(std::vector&& in, int* count) { using T = std::vector; size_t size = in.size(); - O* out = static_cast(wpi::safe_malloc(size * sizeof(O) + sizeof(T))); + O* out = static_cast(wpi::util::safe_malloc(size * sizeof(O) + sizeof(T))); *count = size; for (size_t i = 0; i < size; ++i) { out[i] = ConvertToC(in[i]); @@ -51,106 +51,106 @@ static O* ConvertToC(std::vector&& in, int* count) { extern "C" { CS_PropertyKind CS_GetPropertyKind(CS_Property property, CS_Status* status) { - return cs::GetPropertyKind(property, status); + return wpi::cs::GetPropertyKind(property, status); } void CS_GetPropertyName(CS_Property property, WPI_String* name, CS_Status* status) { - wpi::SmallString<128> buf; - cs::ConvertToC(name, cs::GetPropertyName(property, buf, status)); + wpi::util::SmallString<128> buf; + wpi::cs::ConvertToC(name, wpi::cs::GetPropertyName(property, buf, status)); } int CS_GetProperty(CS_Property property, CS_Status* status) { - return cs::GetProperty(property, status); + return wpi::cs::GetProperty(property, status); } void CS_SetProperty(CS_Property property, int value, CS_Status* status) { - return cs::SetProperty(property, value, status); + return wpi::cs::SetProperty(property, value, status); } int CS_GetPropertyMin(CS_Property property, CS_Status* status) { - return cs::GetPropertyMin(property, status); + return wpi::cs::GetPropertyMin(property, status); } int CS_GetPropertyMax(CS_Property property, CS_Status* status) { - return cs::GetPropertyMax(property, status); + return wpi::cs::GetPropertyMax(property, status); } int CS_GetPropertyStep(CS_Property property, CS_Status* status) { - return cs::GetPropertyStep(property, status); + return wpi::cs::GetPropertyStep(property, status); } int CS_GetPropertyDefault(CS_Property property, CS_Status* status) { - return cs::GetPropertyDefault(property, status); + return wpi::cs::GetPropertyDefault(property, status); } void CS_GetStringProperty(CS_Property property, WPI_String* value, CS_Status* status) { - wpi::SmallString<128> buf; - cs::ConvertToC(value, cs::GetStringProperty(property, buf, status)); + wpi::util::SmallString<128> buf; + wpi::cs::ConvertToC(value, wpi::cs::GetStringProperty(property, buf, status)); } void CS_SetStringProperty(CS_Property property, const struct WPI_String* value, CS_Status* status) { - return cs::SetStringProperty(property, wpi::to_string_view(value), status); + return wpi::cs::SetStringProperty(property, wpi::util::to_string_view(value), status); } WPI_String* CS_GetEnumPropertyChoices(CS_Property property, int* count, CS_Status* status) { - auto choices = cs::GetEnumPropertyChoices(property, status); + auto choices = wpi::cs::GetEnumPropertyChoices(property, status); WPI_String* out = WPI_AllocateStringArray(choices.size()); *count = choices.size(); for (size_t i = 0; i < choices.size(); ++i) { - cs::ConvertToC(&out[i], choices[i]); + wpi::cs::ConvertToC(&out[i], choices[i]); } return out; } CS_SourceKind CS_GetSourceKind(CS_Source source, CS_Status* status) { - return cs::GetSourceKind(source, status); + return wpi::cs::GetSourceKind(source, status); } void CS_GetSourceName(CS_Source source, WPI_String* name, CS_Status* status) { - wpi::SmallString<128> buf; - cs::ConvertToC(name, cs::GetSourceName(source, buf, status)); + wpi::util::SmallString<128> buf; + wpi::cs::ConvertToC(name, wpi::cs::GetSourceName(source, buf, status)); } void CS_GetSourceDescription(CS_Source source, WPI_String* description, CS_Status* status) { - wpi::SmallString<128> buf; - cs::ConvertToC(description, cs::GetSourceDescription(source, buf, status)); + wpi::util::SmallString<128> buf; + wpi::cs::ConvertToC(description, wpi::cs::GetSourceDescription(source, buf, status)); } uint64_t CS_GetSourceLastFrameTime(CS_Source source, CS_Status* status) { - return cs::GetSourceLastFrameTime(source, status); + return wpi::cs::GetSourceLastFrameTime(source, status); } void CS_SetSourceConnectionStrategy(CS_Source source, CS_ConnectionStrategy strategy, CS_Status* status) { - cs::SetSourceConnectionStrategy(source, strategy, status); + wpi::cs::SetSourceConnectionStrategy(source, strategy, status); } CS_Bool CS_IsSourceConnected(CS_Source source, CS_Status* status) { - return cs::IsSourceConnected(source, status); + return wpi::cs::IsSourceConnected(source, status); } CS_Bool CS_IsSourceEnabled(CS_Source source, CS_Status* status) { - return cs::IsSourceEnabled(source, status); + return wpi::cs::IsSourceEnabled(source, status); } CS_Property CS_GetSourceProperty(CS_Source source, const struct WPI_String* name, CS_Status* status) { - return cs::GetSourceProperty(source, wpi::to_string_view(name), status); + return wpi::cs::GetSourceProperty(source, wpi::util::to_string_view(name), status); } CS_Property* CS_EnumerateSourceProperties(CS_Source source, int* count, CS_Status* status) { - wpi::SmallVector buf; - auto vec = cs::EnumerateSourceProperties(source, buf, status); + wpi::util::SmallVector buf; + auto vec = wpi::cs::EnumerateSourceProperties(source, buf, status); CS_Property* out = static_cast( - wpi::safe_malloc(vec.size() * sizeof(CS_Property))); + wpi::util::safe_malloc(vec.size() * sizeof(CS_Property))); *count = vec.size(); std::copy(vec.begin(), vec.end(), out); return out; @@ -158,22 +158,22 @@ CS_Property* CS_EnumerateSourceProperties(CS_Source source, int* count, void CS_GetSourceVideoMode(CS_Source source, CS_VideoMode* mode, CS_Status* status) { - *mode = cs::GetSourceVideoMode(source, status); + *mode = wpi::cs::GetSourceVideoMode(source, status); } CS_Bool CS_SetSourceVideoMode(CS_Source source, const CS_VideoMode* mode, CS_Status* status) { - return cs::SetSourceVideoMode( - source, static_cast(*mode), status); + return wpi::cs::SetSourceVideoMode( + source, static_cast(*mode), status); } CS_Bool CS_SetSourceVideoModeDiscrete(CS_Source source, enum WPI_PixelFormat pixelFormat, int width, int height, int fps, CS_Status* status) { - return cs::SetSourceVideoMode( + return wpi::cs::SetSourceVideoMode( source, - cs::VideoMode{static_cast( + wpi::cs::VideoMode{static_cast( static_cast(pixelFormat)), width, height, fps}, status); @@ -182,37 +182,37 @@ CS_Bool CS_SetSourceVideoModeDiscrete(CS_Source source, CS_Bool CS_SetSourcePixelFormat(CS_Source source, enum WPI_PixelFormat pixelFormat, CS_Status* status) { - return cs::SetSourcePixelFormat( + return wpi::cs::SetSourcePixelFormat( source, - static_cast(static_cast(pixelFormat)), + static_cast(static_cast(pixelFormat)), status); } CS_Bool CS_SetSourceResolution(CS_Source source, int width, int height, CS_Status* status) { - return cs::SetSourceResolution(source, width, height, status); + return wpi::cs::SetSourceResolution(source, width, height, status); } CS_Bool CS_SetSourceFPS(CS_Source source, int fps, CS_Status* status) { - return cs::SetSourceFPS(source, fps, status); + return wpi::cs::SetSourceFPS(source, fps, status); } CS_Bool CS_SetSourceConfigJson(CS_Source source, const struct WPI_String* config, CS_Status* status) { - return cs::SetSourceConfigJson(source, wpi::to_string_view(config), status); + return wpi::cs::SetSourceConfigJson(source, wpi::util::to_string_view(config), status); } void CS_GetSourceConfigJson(CS_Source source, WPI_String* config, CS_Status* status) { - cs::ConvertToC(config, cs::GetSourceConfigJson(source, status)); + wpi::cs::ConvertToC(config, wpi::cs::GetSourceConfigJson(source, status)); } CS_VideoMode* CS_EnumerateSourceVideoModes(CS_Source source, int* count, CS_Status* status) { - auto vec = cs::EnumerateSourceVideoModes(source, status); + auto vec = wpi::cs::EnumerateSourceVideoModes(source, status); CS_VideoMode* out = static_cast( - wpi::safe_malloc(vec.size() * sizeof(CS_VideoMode))); + wpi::util::safe_malloc(vec.size() * sizeof(CS_VideoMode))); *count = vec.size(); std::copy(vec.begin(), vec.end(), out); return out; @@ -220,84 +220,84 @@ CS_VideoMode* CS_EnumerateSourceVideoModes(CS_Source source, int* count, CS_Sink* CS_EnumerateSourceSinks(CS_Source source, int* count, CS_Status* status) { - wpi::SmallVector buf; - auto handles = cs::EnumerateSourceSinks(source, buf, status); + wpi::util::SmallVector buf; + auto handles = wpi::cs::EnumerateSourceSinks(source, buf, status); CS_Sink* sinks = - static_cast(wpi::safe_malloc(handles.size() * sizeof(CS_Sink))); + static_cast(wpi::util::safe_malloc(handles.size() * sizeof(CS_Sink))); *count = handles.size(); std::copy(handles.begin(), handles.end(), sinks); return sinks; } CS_Source CS_CopySource(CS_Source source, CS_Status* status) { - return cs::CopySource(source, status); + return wpi::cs::CopySource(source, status); } void CS_ReleaseSource(CS_Source source, CS_Status* status) { - return cs::ReleaseSource(source, status); + return wpi::cs::ReleaseSource(source, status); } void CS_SetCameraBrightness(CS_Source source, int brightness, CS_Status* status) { - return cs::SetCameraBrightness(source, brightness, status); + return wpi::cs::SetCameraBrightness(source, brightness, status); } int CS_GetCameraBrightness(CS_Source source, CS_Status* status) { - return cs::GetCameraBrightness(source, status); + return wpi::cs::GetCameraBrightness(source, status); } void CS_SetCameraWhiteBalanceAuto(CS_Source source, CS_Status* status) { - return cs::SetCameraWhiteBalanceAuto(source, status); + return wpi::cs::SetCameraWhiteBalanceAuto(source, status); } void CS_SetCameraWhiteBalanceHoldCurrent(CS_Source source, CS_Status* status) { - return cs::SetCameraWhiteBalanceHoldCurrent(source, status); + return wpi::cs::SetCameraWhiteBalanceHoldCurrent(source, status); } void CS_SetCameraWhiteBalanceManual(CS_Source source, int value, CS_Status* status) { - return cs::SetCameraWhiteBalanceManual(source, value, status); + return wpi::cs::SetCameraWhiteBalanceManual(source, value, status); } void CS_SetCameraExposureAuto(CS_Source source, CS_Status* status) { - return cs::SetCameraExposureAuto(source, status); + return wpi::cs::SetCameraExposureAuto(source, status); } void CS_SetCameraExposureHoldCurrent(CS_Source source, CS_Status* status) { - return cs::SetCameraExposureHoldCurrent(source, status); + return wpi::cs::SetCameraExposureHoldCurrent(source, status); } void CS_SetCameraExposureManual(CS_Source source, int value, CS_Status* status) { - return cs::SetCameraExposureManual(source, value, status); + return wpi::cs::SetCameraExposureManual(source, value, status); } CS_SinkKind CS_GetSinkKind(CS_Sink sink, CS_Status* status) { - return cs::GetSinkKind(sink, status); + return wpi::cs::GetSinkKind(sink, status); } void CS_GetSinkName(CS_Sink sink, WPI_String* name, CS_Status* status) { - wpi::SmallString<128> buf; - cs::ConvertToC(name, cs::GetSinkName(sink, buf, status)); + wpi::util::SmallString<128> buf; + wpi::cs::ConvertToC(name, wpi::cs::GetSinkName(sink, buf, status)); } void CS_GetSinkDescription(CS_Sink sink, WPI_String* description, CS_Status* status) { - wpi::SmallString<128> buf; - cs::ConvertToC(description, cs::GetSinkDescription(sink, buf, status)); + wpi::util::SmallString<128> buf; + wpi::cs::ConvertToC(description, wpi::cs::GetSinkDescription(sink, buf, status)); } CS_Property CS_GetSinkProperty(CS_Sink sink, const struct WPI_String* name, CS_Status* status) { - return cs::GetSinkProperty(sink, wpi::to_string_view(name), status); + return wpi::cs::GetSinkProperty(sink, wpi::util::to_string_view(name), status); } CS_Property* CS_EnumerateSinkProperties(CS_Sink sink, int* count, CS_Status* status) { - wpi::SmallVector buf; - auto vec = cs::EnumerateSinkProperties(sink, buf, status); + wpi::util::SmallVector buf; + auto vec = wpi::cs::EnumerateSinkProperties(sink, buf, status); CS_Property* out = static_cast( - wpi::safe_malloc(vec.size() * sizeof(CS_Property))); + wpi::util::safe_malloc(vec.size() * sizeof(CS_Property))); *count = vec.size(); std::copy(vec.begin(), vec.end(), out); return out; @@ -305,49 +305,49 @@ CS_Property* CS_EnumerateSinkProperties(CS_Sink sink, int* count, CS_Bool CS_SetSinkConfigJson(CS_Sink sink, const struct WPI_String* config, CS_Status* status) { - return cs::SetSinkConfigJson(sink, wpi::to_string_view(config), status); + return wpi::cs::SetSinkConfigJson(sink, wpi::util::to_string_view(config), status); } void CS_GetSinkConfigJson(CS_Sink sink, WPI_String* config, CS_Status* status) { - cs::ConvertToC(config, cs::GetSinkConfigJson(sink, status)); + wpi::cs::ConvertToC(config, wpi::cs::GetSinkConfigJson(sink, status)); } void CS_SetSinkSource(CS_Sink sink, CS_Source source, CS_Status* status) { - return cs::SetSinkSource(sink, source, status); + return wpi::cs::SetSinkSource(sink, source, status); } CS_Source CS_GetSinkSource(CS_Sink sink, CS_Status* status) { - return cs::GetSinkSource(sink, status); + return wpi::cs::GetSinkSource(sink, status); } CS_Property CS_GetSinkSourceProperty(CS_Sink sink, const struct WPI_String* name, CS_Status* status) { - return cs::GetSinkSourceProperty(sink, wpi::to_string_view(name), status); + return wpi::cs::GetSinkSourceProperty(sink, wpi::util::to_string_view(name), status); } CS_Sink CS_CopySink(CS_Sink sink, CS_Status* status) { - return cs::CopySink(sink, status); + return wpi::cs::CopySink(sink, status); } void CS_ReleaseSink(CS_Sink sink, CS_Status* status) { - return cs::ReleaseSink(sink, status); + return wpi::cs::ReleaseSink(sink, status); } void CS_SetListenerOnStart(void (*onStart)(void* data), void* data) { - cs::SetListenerOnStart([=] { onStart(data); }); + wpi::cs::SetListenerOnStart([=] { onStart(data); }); } void CS_SetListenerOnExit(void (*onExit)(void* data), void* data) { - cs::SetListenerOnExit([=] { onExit(data); }); + wpi::cs::SetListenerOnExit([=] { onExit(data); }); } CS_Listener CS_AddListener(void* data, void (*callback)(void* data, const CS_Event* event), int eventMask, CS_Bool immediateNotify, CS_Status* status) { - return cs::AddListener( - [=](const cs::RawEvent& rawEvent) { + return wpi::cs::AddListener( + [=](const wpi::cs::RawEvent& rawEvent) { CS_Event event = ConvertToC(rawEvent); callback(data, &event); }, @@ -355,41 +355,41 @@ CS_Listener CS_AddListener(void* data, } void CS_RemoveListener(CS_Listener handle, CS_Status* status) { - return cs::RemoveListener(handle, status); + return wpi::cs::RemoveListener(handle, status); } CS_ListenerPoller CS_CreateListenerPoller(void) { - return cs::CreateListenerPoller(); + return wpi::cs::CreateListenerPoller(); } void CS_DestroyListenerPoller(CS_ListenerPoller poller) { - cs::DestroyListenerPoller(poller); + wpi::cs::DestroyListenerPoller(poller); } CS_Listener CS_AddPolledListener(CS_ListenerPoller poller, int eventMask, CS_Bool immediateNotify, CS_Status* status) { - return cs::AddPolledListener(poller, eventMask, immediateNotify, status); + return wpi::cs::AddPolledListener(poller, eventMask, immediateNotify, status); } struct CS_Event* CS_PollListener(CS_ListenerPoller poller, int* count) { - return ConvertToC(cs::PollListener(poller), count); + return ConvertToC(wpi::cs::PollListener(poller), count); } struct CS_Event* CS_PollListenerTimeout(CS_ListenerPoller poller, int* count, double timeout, CS_Bool* timedOut) { bool cppTimedOut = false; - auto arrCpp = cs::PollListener(poller, timeout, &cppTimedOut); + auto arrCpp = wpi::cs::PollListener(poller, timeout, &cppTimedOut); *timedOut = cppTimedOut; return ConvertToC(std::move(arrCpp), count); } void CS_CancelPollListener(CS_ListenerPoller poller) { - cs::CancelPollListener(poller); + wpi::cs::CancelPollListener(poller); } void CS_FreeEvents(CS_Event* arr, int count) { // destroy vector saved at end of array - using T = std::vector; + using T = std::vector; alignas(T) unsigned char buf[sizeof(T)]; std::memcpy(buf, arr + count, sizeof(T)); reinterpret_cast(buf)->~T(); @@ -398,51 +398,51 @@ void CS_FreeEvents(CS_Event* arr, int count) { } int CS_NotifierDestroyed(void) { - return cs::NotifierDestroyed(); + return wpi::cs::NotifierDestroyed(); } void CS_SetTelemetryPeriod(double seconds) { - cs::SetTelemetryPeriod(seconds); + wpi::cs::SetTelemetryPeriod(seconds); } double CS_GetTelemetryElapsedTime(void) { - return cs::GetTelemetryElapsedTime(); + return wpi::cs::GetTelemetryElapsedTime(); } int64_t CS_GetTelemetryValue(CS_Handle handle, CS_TelemetryKind kind, CS_Status* status) { - return cs::GetTelemetryValue(handle, kind, status); + return wpi::cs::GetTelemetryValue(handle, kind, status); } double CS_GetTelemetryAverageValue(CS_Handle handle, CS_TelemetryKind kind, CS_Status* status) { - return cs::GetTelemetryAverageValue(handle, kind, status); + return wpi::cs::GetTelemetryAverageValue(handle, kind, status); } void CS_SetLogger(CS_LogFunc func, void* data, unsigned int min_level) { - cs::SetLogger( + wpi::cs::SetLogger( [=](unsigned int level, const char* file, unsigned int line, const char* msg) { - auto fileStr = wpi::make_string(file); - auto msgStr = wpi::make_string(msg); + auto fileStr = wpi::util::make_string(file); + auto msgStr = wpi::util::make_string(msg); func(data, level, &fileStr, line, &msgStr); }, min_level); } void CS_SetDefaultLogger(unsigned int min_level) { - cs::SetDefaultLogger(min_level); + wpi::cs::SetDefaultLogger(min_level); } void CS_Shutdown(void) { - cs::Shutdown(); + wpi::cs::Shutdown(); } CS_Source* CS_EnumerateSources(int* count, CS_Status* status) { - wpi::SmallVector buf; - auto handles = cs::EnumerateSourceHandles(buf, status); + wpi::util::SmallVector buf; + auto handles = wpi::cs::EnumerateSourceHandles(buf, status); CS_Source* sources = static_cast( - wpi::safe_malloc(handles.size() * sizeof(CS_Source))); + wpi::util::safe_malloc(handles.size() * sizeof(CS_Source))); *count = handles.size(); std::copy(handles.begin(), handles.end(), sources); return sources; @@ -455,17 +455,17 @@ void CS_ReleaseEnumeratedSources(CS_Source* sources, int count) { for (int i = 0; i < count; ++i) { CS_Status status = 0; if (sources[i] != 0) { - cs::ReleaseSource(sources[i], &status); + wpi::cs::ReleaseSource(sources[i], &status); } } std::free(sources); } CS_Sink* CS_EnumerateSinks(int* count, CS_Status* status) { - wpi::SmallVector buf; - auto handles = cs::EnumerateSinkHandles(buf, status); + wpi::util::SmallVector buf; + auto handles = wpi::cs::EnumerateSinkHandles(buf, status); CS_Sink* sinks = - static_cast(wpi::safe_malloc(handles.size() * sizeof(CS_Sink))); + static_cast(wpi::util::safe_malloc(handles.size() * sizeof(CS_Sink))); *count = handles.size(); std::copy(handles.begin(), handles.end(), sinks); return sinks; @@ -478,7 +478,7 @@ void CS_ReleaseEnumeratedSinks(CS_Sink* sinks, int count) { for (int i = 0; i < count; ++i) { CS_Status status = 0; if (sinks[i] != 0) { - cs::ReleaseSink(sinks[i], &status); + wpi::cs::ReleaseSink(sinks[i], &status); } } std::free(sinks); @@ -493,15 +493,15 @@ void CS_FreeEnumeratedVideoModes(CS_VideoMode* modes, int count) { } void CS_GetHostname(struct WPI_String* hostname) { - cs::ConvertToC(hostname, cs::GetHostname()); + wpi::cs::ConvertToC(hostname, wpi::cs::GetHostname()); } WPI_String* CS_GetNetworkInterfaces(int* count) { - auto interfaces = cs::GetNetworkInterfaces(); + auto interfaces = wpi::cs::GetNetworkInterfaces(); WPI_String* out = WPI_AllocateStringArray(interfaces.size()); *count = interfaces.size(); for (size_t i = 0; i < interfaces.size(); ++i) { - cs::ConvertToC(&out[i], interfaces[i]); + wpi::cs::ConvertToC(&out[i], interfaces[i]); } return out; } diff --git a/cscore/src/main/native/cpp/cscore_cpp.cpp b/cscore/src/main/native/cpp/cscore_cpp.cpp index 8aa92a3f3f..b7d17aba0e 100644 --- a/cscore/src/main/native/cpp/cscore_cpp.cpp +++ b/cscore/src/main/native/cpp/cscore_cpp.cpp @@ -21,7 +21,7 @@ #include "wpi/util/SmallString.hpp" #include "wpi/util/json.hpp" -using namespace cs; +using namespace wpi::cs; static std::shared_ptr GetPropertyContainer( CS_Property propertyHandle, int* propertyIndex, CS_Status* status) { @@ -51,7 +51,7 @@ static std::shared_ptr GetPropertyContainer( return container; } -namespace cs { +namespace wpi::cs { // // Property Functions @@ -67,7 +67,7 @@ CS_PropertyKind GetPropertyKind(CS_Property property, CS_Status* status) { } std::string GetPropertyName(CS_Property property, CS_Status* status) { - wpi::SmallString<128> buf; + wpi::util::SmallString<128> buf; int propertyIndex; auto container = GetPropertyContainer(property, &propertyIndex, status); if (!container) { @@ -77,7 +77,7 @@ std::string GetPropertyName(CS_Property property, CS_Status* status) { } std::string_view GetPropertyName(CS_Property property, - wpi::SmallVectorImpl& buf, + wpi::util::SmallVectorImpl& buf, CS_Status* status) { int propertyIndex; auto container = GetPropertyContainer(property, &propertyIndex, status); @@ -142,7 +142,7 @@ int GetPropertyDefault(CS_Property property, CS_Status* status) { } std::string GetStringProperty(CS_Property property, CS_Status* status) { - wpi::SmallString<128> buf; + wpi::util::SmallString<128> buf; int propertyIndex; auto container = GetPropertyContainer(property, &propertyIndex, status); if (!container) { @@ -152,7 +152,7 @@ std::string GetStringProperty(CS_Property property, CS_Status* status) { } std::string_view GetStringProperty(CS_Property property, - wpi::SmallVectorImpl& buf, + wpi::util::SmallVectorImpl& buf, CS_Status* status) { int propertyIndex; auto container = GetPropertyContainer(property, &propertyIndex, status); @@ -205,7 +205,7 @@ std::string GetSourceName(CS_Source source, CS_Status* status) { } std::string_view GetSourceName(CS_Source source, - wpi::SmallVectorImpl& buf, + wpi::util::SmallVectorImpl& buf, CS_Status* status) { auto data = Instance::GetInstance().GetSource(source); if (!data) { @@ -221,12 +221,12 @@ std::string GetSourceDescription(CS_Source source, CS_Status* status) { *status = CS_INVALID_HANDLE; return {}; } - wpi::SmallString<128> buf; + wpi::util::SmallString<128> buf; return std::string{data->source->GetDescription(buf)}; } std::string_view GetSourceDescription(CS_Source source, - wpi::SmallVectorImpl& buf, + wpi::util::SmallVectorImpl& buf, CS_Status* status) { auto data = Instance::GetInstance().GetSource(source); if (!data) { @@ -290,14 +290,14 @@ CS_Property GetSourceProperty(CS_Source source, std::string_view name, } std::span EnumerateSourceProperties( - CS_Source source, wpi::SmallVectorImpl& vec, + CS_Source source, wpi::util::SmallVectorImpl& vec, CS_Status* status) { auto data = Instance::GetInstance().GetSource(source); if (!data) { *status = CS_INVALID_HANDLE; return {}; } - wpi::SmallVector properties_buf; + wpi::util::SmallVector properties_buf; for (auto property : data->source->EnumerateProperties(properties_buf, status)) { vec.push_back(Handle{source, property, Handle::kProperty}); @@ -363,7 +363,7 @@ bool SetSourceConfigJson(CS_Source source, std::string_view config, return data->source->SetConfigJson(config, status); } -bool SetSourceConfigJson(CS_Source source, const wpi::json& config, +bool SetSourceConfigJson(CS_Source source, const wpi::util::json& config, CS_Status* status) { auto data = Instance::GetInstance().GetSource(source); if (!data) { @@ -382,11 +382,11 @@ std::string GetSourceConfigJson(CS_Source source, CS_Status* status) { return data->source->GetConfigJson(status); } -wpi::json GetSourceConfigJsonObject(CS_Source source, CS_Status* status) { +wpi::util::json GetSourceConfigJsonObject(CS_Source source, CS_Status* status) { auto data = Instance::GetInstance().GetSource(source); if (!data) { *status = CS_INVALID_HANDLE; - return wpi::json{}; + return wpi::util::json{}; } return data->source->GetConfigJsonObject(status); } @@ -402,7 +402,7 @@ std::vector EnumerateSourceVideoModes(CS_Source source, } std::span EnumerateSourceSinks(CS_Source source, - wpi::SmallVectorImpl& vec, + wpi::util::SmallVectorImpl& vec, CS_Status* status) { auto& inst = Instance::GetInstance(); auto data = inst.GetSource(source); @@ -540,7 +540,7 @@ std::string GetSinkName(CS_Sink sink, CS_Status* status) { return std::string{data->sink->GetName()}; } -std::string_view GetSinkName(CS_Sink sink, wpi::SmallVectorImpl& buf, +std::string_view GetSinkName(CS_Sink sink, wpi::util::SmallVectorImpl& buf, CS_Status* status) { auto data = Instance::GetInstance().GetSink(sink); if (!data) { @@ -556,12 +556,12 @@ std::string GetSinkDescription(CS_Sink sink, CS_Status* status) { *status = CS_INVALID_HANDLE; return {}; } - wpi::SmallString<128> buf; + wpi::util::SmallString<128> buf; return std::string{data->sink->GetDescription(buf)}; } std::string_view GetSinkDescription(CS_Sink sink, - wpi::SmallVectorImpl& buf, + wpi::util::SmallVectorImpl& buf, CS_Status* status) { auto data = Instance::GetInstance().GetSink(sink); if (!data) { @@ -587,13 +587,13 @@ CS_Property GetSinkProperty(CS_Sink sink, std::string_view name, } std::span EnumerateSinkProperties( - CS_Sink sink, wpi::SmallVectorImpl& vec, CS_Status* status) { + CS_Sink sink, wpi::util::SmallVectorImpl& vec, CS_Status* status) { auto data = Instance::GetInstance().GetSink(sink); if (!data) { *status = CS_INVALID_HANDLE; return {}; } - wpi::SmallVector properties_buf; + wpi::util::SmallVector properties_buf; for (auto property : data->sink->EnumerateProperties(properties_buf, status)) { vec.push_back(Handle{sink, property, Handle::kSinkProperty}); @@ -611,7 +611,7 @@ bool SetSinkConfigJson(CS_Sink sink, std::string_view config, return data->sink->SetConfigJson(config, status); } -bool SetSinkConfigJson(CS_Sink sink, const wpi::json& config, +bool SetSinkConfigJson(CS_Sink sink, const wpi::util::json& config, CS_Status* status) { auto data = Instance::GetInstance().GetSink(sink); if (!data) { @@ -630,11 +630,11 @@ std::string GetSinkConfigJson(CS_Sink sink, CS_Status* status) { return data->sink->GetConfigJson(status); } -wpi::json GetSinkConfigJsonObject(CS_Sink sink, CS_Status* status) { +wpi::util::json GetSinkConfigJsonObject(CS_Sink sink, CS_Status* status) { auto data = Instance::GetInstance().GetSink(sink); if (!data) { *status = CS_INVALID_HANDLE; - return wpi::json{}; + return wpi::util::json{}; } return data->sink->GetConfigJsonObject(status); } @@ -869,17 +869,17 @@ void Shutdown() { // std::span EnumerateSourceHandles( - wpi::SmallVectorImpl& vec, CS_Status* status) { + wpi::util::SmallVectorImpl& vec, CS_Status* status) { return Instance::GetInstance().EnumerateSourceHandles(vec); } -std::span EnumerateSinkHandles(wpi::SmallVectorImpl& vec, +std::span EnumerateSinkHandles(wpi::util::SmallVectorImpl& vec, CS_Status* status) { return Instance::GetInstance().EnumerateSinkHandles(vec); } std::string GetHostname() { - return wpi::GetHostname(); + return wpi::net::GetHostname(); } -} // namespace cs +} // namespace wpi::cs diff --git a/cscore/src/main/native/cpp/cscore_oo.cpp b/cscore/src/main/native/cpp/cscore_oo.cpp index 091997509b..19e21a254b 100644 --- a/cscore/src/main/native/cpp/cscore_oo.cpp +++ b/cscore/src/main/native/cpp/cscore_oo.cpp @@ -11,20 +11,20 @@ #include "wpi/util/json.hpp" -using namespace cs; +using namespace wpi::cs; -wpi::json VideoSource::GetConfigJsonObject() const { +wpi::util::json VideoSource::GetConfigJsonObject() const { m_status = 0; return GetSourceConfigJsonObject(m_handle, &m_status); } -wpi::json VideoSink::GetConfigJsonObject() const { +wpi::util::json VideoSink::GetConfigJsonObject() const { m_status = 0; return GetSinkConfigJsonObject(m_handle, &m_status); } std::vector VideoSource::EnumerateProperties() const { - wpi::SmallVector handles_buf; + wpi::util::SmallVector handles_buf; CS_Status status = 0; auto handles = EnumerateSourceProperties(m_handle, handles_buf, &status); @@ -37,7 +37,7 @@ std::vector VideoSource::EnumerateProperties() const { } std::vector VideoSource::EnumerateSinks() { - wpi::SmallVector handles_buf; + wpi::util::SmallVector handles_buf; CS_Status status = 0; auto handles = EnumerateSourceSinks(m_handle, handles_buf, &status); @@ -50,9 +50,9 @@ std::vector VideoSource::EnumerateSinks() { } std::vector VideoSource::EnumerateSources() { - wpi::SmallVector handles_buf; + wpi::util::SmallVector handles_buf; CS_Status status = 0; - auto handles = ::cs::EnumerateSourceHandles(handles_buf, &status); + auto handles = ::wpi::cs::EnumerateSourceHandles(handles_buf, &status); std::vector sources; sources.reserve(handles.size()); @@ -63,7 +63,7 @@ std::vector VideoSource::EnumerateSources() { } std::vector VideoSink::EnumerateProperties() const { - wpi::SmallVector handles_buf; + wpi::util::SmallVector handles_buf; CS_Status status = 0; auto handles = EnumerateSinkProperties(m_handle, handles_buf, &status); @@ -76,9 +76,9 @@ std::vector VideoSink::EnumerateProperties() const { } std::vector VideoSink::EnumerateSinks() { - wpi::SmallVector handles_buf; + wpi::util::SmallVector handles_buf; CS_Status status = 0; - auto handles = ::cs::EnumerateSinkHandles(handles_buf, &status); + auto handles = ::wpi::cs::EnumerateSinkHandles(handles_buf, &status); std::vector sinks; sinks.reserve(handles.size()); diff --git a/cscore/src/main/native/cpp/default_init_allocator.hpp b/cscore/src/main/native/cpp/default_init_allocator.hpp index d7706974bc..19de39a98c 100644 --- a/cscore/src/main/native/cpp/default_init_allocator.hpp +++ b/cscore/src/main/native/cpp/default_init_allocator.hpp @@ -8,7 +8,7 @@ #include #include -namespace cs { +namespace wpi::cs { // Allocator adaptor that interposes construct() calls to // convert value initialization into default initialization. @@ -36,6 +36,6 @@ class default_init_allocator : public A { } }; -} // namespace cs +} // namespace wpi::cs #endif // CSCORE_DEFAULT_INIT_ALLOCATOR_HPP_ diff --git a/cscore/src/main/native/cpp/jni/CameraServerJNI.cpp b/cscore/src/main/native/cpp/jni/CameraServerJNI.cpp index 39caab181e..20c92bb1f7 100644 --- a/cscore/src/main/native/cpp/jni/CameraServerJNI.cpp +++ b/cscore/src/main/native/cpp/jni/CameraServerJNI.cpp @@ -21,7 +21,7 @@ namespace cv { class Mat; } // namespace cv -using namespace wpi::java; +using namespace wpi::util::java; // // Globals and load/unload @@ -107,14 +107,14 @@ JNIEXPORT jint JNICALL JNI_OnLoad(JavaVM* vm, void* reserved) { } // Initial configuration of listener start/exit - cs::SetListenerOnStart(ListenerOnStart); - cs::SetListenerOnExit(ListenerOnExit); + wpi::cs::SetListenerOnStart(ListenerOnStart); + wpi::cs::SetListenerOnExit(ListenerOnExit); return JNI_VERSION_1_6; } JNIEXPORT void JNICALL JNI_OnUnload(JavaVM* vm, void* reserved) { - cs::Shutdown(); + wpi::cs::Shutdown(); JNIEnv* env; if (vm->GetEnv(reinterpret_cast(&env), JNI_VERSION_1_6) != JNI_OK) { @@ -141,7 +141,7 @@ class JCSGlobal { JCSGlobal(JNIEnv* env, T obj) : m_obj(static_cast(env->NewGlobalRef(obj))) {} ~JCSGlobal() { - if (!jvm || cs::NotifierDestroyed()) { + if (!jvm || wpi::cs::NotifierDestroyed()) { return; } JNIEnv* env; @@ -223,7 +223,7 @@ static inline bool CheckStatus(JNIEnv* env, CS_Status status) { return status == CS_OK; } -static jobject MakeJObject(JNIEnv* env, const cs::UsbCameraInfo& info) { +static jobject MakeJObject(JNIEnv* env, const wpi::cs::UsbCameraInfo& info) { static jmethodID constructor = env->GetMethodID( usbCameraInfoCls, "", "(ILjava/lang/String;Ljava/lang/String;[Ljava/lang/String;II)V"); @@ -236,7 +236,7 @@ static jobject MakeJObject(JNIEnv* env, const cs::UsbCameraInfo& info) { static_cast(info.productId)); } -static jobject MakeJObject(JNIEnv* env, const cs::VideoMode& videoMode) { +static jobject MakeJObject(JNIEnv* env, const wpi::cs::VideoMode& videoMode) { static jmethodID constructor = env->GetMethodID(videoModeCls, "", "(IIII)V"); return env->NewObject( @@ -245,7 +245,7 @@ static jobject MakeJObject(JNIEnv* env, const cs::VideoMode& videoMode) { static_cast(videoMode.fps)); } -static jobject MakeJObject(JNIEnv* env, const cs::RawEvent& event) { +static jobject MakeJObject(JNIEnv* env, const wpi::cs::RawEvent& event) { static jmethodID constructor = env->GetMethodID(videoEventCls, "", "(IIILjava/lang/String;IIIIIIILjava/lang/String;I)V"); @@ -272,7 +272,7 @@ static jobject MakeJObject(JNIEnv* env, const cs::RawEvent& event) { } static jobjectArray MakeJObject(JNIEnv* env, - std::span arr) { + std::span arr) { jobjectArray jarr = env->NewObjectArray(arr.size(), videoEventCls, nullptr); if (!jarr) { return nullptr; @@ -296,7 +296,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_getPropertyKind (JNIEnv* env, jclass, jint property) { CS_Status status = 0; - auto val = cs::GetPropertyKind(property, &status); + auto val = wpi::cs::GetPropertyKind(property, &status); CheckStatus(env, status); return val; } @@ -311,8 +311,8 @@ Java_org_wpilib_vision_camera_CameraServerJNI_getPropertyName (JNIEnv* env, jclass, jint property) { CS_Status status = 0; - wpi::SmallString<128> buf; - auto str = cs::GetPropertyName(property, buf, &status); + wpi::util::SmallString<128> buf; + auto str = wpi::cs::GetPropertyName(property, buf, &status); if (!CheckStatus(env, status)) { return nullptr; } @@ -329,7 +329,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_getProperty (JNIEnv* env, jclass, jint property) { CS_Status status = 0; - auto val = cs::GetProperty(property, &status); + auto val = wpi::cs::GetProperty(property, &status); CheckStatus(env, status); return val; } @@ -344,7 +344,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_setProperty (JNIEnv* env, jclass, jint property, jint value) { CS_Status status = 0; - cs::SetProperty(property, value, &status); + wpi::cs::SetProperty(property, value, &status); CheckStatus(env, status); } @@ -358,7 +358,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_getPropertyMin (JNIEnv* env, jclass, jint property) { CS_Status status = 0; - auto val = cs::GetPropertyMin(property, &status); + auto val = wpi::cs::GetPropertyMin(property, &status); CheckStatus(env, status); return val; } @@ -373,7 +373,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_getPropertyMax (JNIEnv* env, jclass, jint property) { CS_Status status = 0; - auto val = cs::GetPropertyMax(property, &status); + auto val = wpi::cs::GetPropertyMax(property, &status); CheckStatus(env, status); return val; } @@ -388,7 +388,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_getPropertyStep (JNIEnv* env, jclass, jint property) { CS_Status status = 0; - auto val = cs::GetPropertyStep(property, &status); + auto val = wpi::cs::GetPropertyStep(property, &status); CheckStatus(env, status); return val; } @@ -403,7 +403,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_getPropertyDefault (JNIEnv* env, jclass, jint property) { CS_Status status = 0; - auto val = cs::GetPropertyDefault(property, &status); + auto val = wpi::cs::GetPropertyDefault(property, &status); CheckStatus(env, status); return val; } @@ -418,8 +418,8 @@ Java_org_wpilib_vision_camera_CameraServerJNI_getStringProperty (JNIEnv* env, jclass, jint property) { CS_Status status = 0; - wpi::SmallString<128> buf; - auto str = cs::GetStringProperty(property, buf, &status); + wpi::util::SmallString<128> buf; + auto str = wpi::cs::GetStringProperty(property, buf, &status); if (!CheckStatus(env, status)) { return nullptr; } @@ -440,7 +440,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_setStringProperty return; } CS_Status status = 0; - cs::SetStringProperty(property, JStringRef{env, value}.str(), &status); + wpi::cs::SetStringProperty(property, JStringRef{env, value}.str(), &status); CheckStatus(env, status); } @@ -454,7 +454,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_getEnumPropertyChoices (JNIEnv* env, jclass, jint property) { CS_Status status = 0; - auto arr = cs::GetEnumPropertyChoices(property, &status); + auto arr = wpi::cs::GetEnumPropertyChoices(property, &status); if (!CheckStatus(env, status)) { return nullptr; } @@ -475,7 +475,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_createUsbCameraDev return 0; } CS_Status status = 0; - auto val = cs::CreateUsbCameraDev(JStringRef{env, name}.str(), dev, &status); + auto val = wpi::cs::CreateUsbCameraDev(JStringRef{env, name}.str(), dev, &status); CheckStatus(env, status); return val; } @@ -498,7 +498,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_createUsbCameraPath return 0; } CS_Status status = 0; - auto val = cs::CreateUsbCameraPath(JStringRef{env, name}.str(), + auto val = wpi::cs::CreateUsbCameraPath(JStringRef{env, name}.str(), JStringRef{env, path}.str(), &status); CheckStatus(env, status); return val; @@ -522,7 +522,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_createHttpCamera return 0; } CS_Status status = 0; - auto val = cs::CreateHttpCamera( + auto val = wpi::cs::CreateHttpCamera( JStringRef{env, name}.str(), JStringRef{env, url}.str(), static_cast(kind), &status); CheckStatus(env, status); @@ -547,7 +547,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_createHttpCameraMulti return 0; } size_t len = env->GetArrayLength(urls); - wpi::SmallVector vec; + wpi::util::SmallVector vec; vec.reserve(len); for (size_t i = 0; i < len; ++i) { JLocal elem{ @@ -560,7 +560,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_createHttpCameraMulti } CS_Status status = 0; auto val = - cs::CreateHttpCamera(JStringRef{env, name}.str(), vec, + wpi::cs::CreateHttpCamera(JStringRef{env, name}.str(), vec, static_cast(kind), &status); CheckStatus(env, status); return val; @@ -581,9 +581,9 @@ Java_org_wpilib_vision_camera_CameraServerJNI_createRawSource return 0; } CS_Status status = 0; - auto val = cs::CreateRawSource( + auto val = wpi::cs::CreateRawSource( JStringRef{env, name}.str(), isCv, - cs::VideoMode{static_cast(pixelFormat), + wpi::cs::VideoMode{static_cast(pixelFormat), static_cast(width), static_cast(height), static_cast(fps)}, &status); @@ -601,7 +601,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_getSourceKind (JNIEnv* env, jclass, jint source) { CS_Status status = 0; - auto val = cs::GetSourceKind(source, &status); + auto val = wpi::cs::GetSourceKind(source, &status); CheckStatus(env, status); return val; } @@ -616,8 +616,8 @@ Java_org_wpilib_vision_camera_CameraServerJNI_getSourceName (JNIEnv* env, jclass, jint source) { CS_Status status = 0; - wpi::SmallString<128> buf; - auto str = cs::GetSourceName(source, buf, &status); + wpi::util::SmallString<128> buf; + auto str = wpi::cs::GetSourceName(source, buf, &status); if (!CheckStatus(env, status)) { return nullptr; } @@ -634,8 +634,8 @@ Java_org_wpilib_vision_camera_CameraServerJNI_getSourceDescription (JNIEnv* env, jclass, jint source) { CS_Status status = 0; - wpi::SmallString<128> buf; - auto str = cs::GetSourceDescription(source, buf, &status); + wpi::util::SmallString<128> buf; + auto str = wpi::cs::GetSourceDescription(source, buf, &status); if (!CheckStatus(env, status)) { return nullptr; } @@ -652,7 +652,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_getSourceLastFrameTime (JNIEnv* env, jclass, jint source) { CS_Status status = 0; - auto val = cs::GetSourceLastFrameTime(source, &status); + auto val = wpi::cs::GetSourceLastFrameTime(source, &status); CheckStatus(env, status); return val; } @@ -667,7 +667,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_setSourceConnectionStrategy (JNIEnv* env, jclass, jint source, jint strategy) { CS_Status status = 0; - cs::SetSourceConnectionStrategy( + wpi::cs::SetSourceConnectionStrategy( source, static_cast(strategy), &status); CheckStatus(env, status); } @@ -682,7 +682,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_isSourceConnected (JNIEnv* env, jclass, jint source) { CS_Status status = 0; - auto val = cs::IsSourceConnected(source, &status); + auto val = wpi::cs::IsSourceConnected(source, &status); CheckStatus(env, status); return val; } @@ -697,7 +697,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_isSourceEnabled (JNIEnv* env, jclass, jint source) { CS_Status status = 0; - auto val = cs::IsSourceEnabled(source, &status); + auto val = wpi::cs::IsSourceEnabled(source, &status); CheckStatus(env, status); return val; } @@ -717,7 +717,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_getSourceProperty } CS_Status status = 0; auto val = - cs::GetSourceProperty(source, JStringRef{env, name}.str(), &status); + wpi::cs::GetSourceProperty(source, JStringRef{env, name}.str(), &status); CheckStatus(env, status); return val; } @@ -732,8 +732,8 @@ Java_org_wpilib_vision_camera_CameraServerJNI_enumerateSourceProperties (JNIEnv* env, jclass, jint source) { CS_Status status = 0; - wpi::SmallVector buf; - auto arr = cs::EnumerateSourceProperties(source, buf, &status); + wpi::util::SmallVector buf; + auto arr = wpi::cs::EnumerateSourceProperties(source, buf, &status); if (!CheckStatus(env, status)) { return nullptr; } @@ -750,7 +750,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_getSourceVideoMode (JNIEnv* env, jclass, jint source) { CS_Status status = 0; - auto val = cs::GetSourceVideoMode(source, &status); + auto val = wpi::cs::GetSourceVideoMode(source, &status); if (!CheckStatus(env, status)) { return nullptr; } @@ -768,9 +768,9 @@ Java_org_wpilib_vision_camera_CameraServerJNI_setSourceVideoMode jint fps) { CS_Status status = 0; - auto val = cs::SetSourceVideoMode( + auto val = wpi::cs::SetSourceVideoMode( source, - cs::VideoMode(static_cast(pixelFormat), width, + wpi::cs::VideoMode(static_cast(pixelFormat), width, height, fps), &status); CheckStatus(env, status); @@ -787,8 +787,8 @@ Java_org_wpilib_vision_camera_CameraServerJNI_setSourcePixelFormat (JNIEnv* env, jclass, jint source, jint pixelFormat) { CS_Status status = 0; - auto val = cs::SetSourcePixelFormat( - source, static_cast(pixelFormat), &status); + auto val = wpi::cs::SetSourcePixelFormat( + source, static_cast(pixelFormat), &status); CheckStatus(env, status); return val; } @@ -803,7 +803,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_setSourceResolution (JNIEnv* env, jclass, jint source, jint width, jint height) { CS_Status status = 0; - auto val = cs::SetSourceResolution(source, width, height, &status); + auto val = wpi::cs::SetSourceResolution(source, width, height, &status); CheckStatus(env, status); return val; } @@ -818,7 +818,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_setSourceFPS (JNIEnv* env, jclass, jint source, jint fps) { CS_Status status = 0; - auto val = cs::SetSourceFPS(source, fps, &status); + auto val = wpi::cs::SetSourceFPS(source, fps, &status); CheckStatus(env, status); return val; } @@ -833,7 +833,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_setSourceConfigJson (JNIEnv* env, jclass, jint source, jstring config) { CS_Status status = 0; - auto val = cs::SetSourceConfigJson(source, JStringRef{env, config}, &status); + auto val = wpi::cs::SetSourceConfigJson(source, JStringRef{env, config}, &status); CheckStatus(env, status); return val; } @@ -848,7 +848,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_getSourceConfigJson (JNIEnv* env, jclass, jint source) { CS_Status status = 0; - auto val = cs::GetSourceConfigJson(source, &status); + auto val = wpi::cs::GetSourceConfigJson(source, &status); CheckStatus(env, status); return MakeJString(env, val); } @@ -863,7 +863,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_enumerateSourceVideoModes (JNIEnv* env, jclass, jint source) { CS_Status status = 0; - auto arr = cs::EnumerateSourceVideoModes(source, &status); + auto arr = wpi::cs::EnumerateSourceVideoModes(source, &status); if (!CheckStatus(env, status)) { return nullptr; } @@ -888,8 +888,8 @@ Java_org_wpilib_vision_camera_CameraServerJNI_enumerateSourceSinks (JNIEnv* env, jclass, jint source) { CS_Status status = 0; - wpi::SmallVector buf; - auto arr = cs::EnumerateSourceSinks(source, buf, &status); + wpi::util::SmallVector buf; + auto arr = wpi::cs::EnumerateSourceSinks(source, buf, &status); if (!CheckStatus(env, status)) { return nullptr; } @@ -906,7 +906,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_copySource (JNIEnv* env, jclass, jint source) { CS_Status status = 0; - auto val = cs::CopySource(source, &status); + auto val = wpi::cs::CopySource(source, &status); CheckStatus(env, status); return val; } @@ -921,7 +921,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_releaseSource (JNIEnv* env, jclass, jint source) { CS_Status status = 0; - cs::ReleaseSource(source, &status); + wpi::cs::ReleaseSource(source, &status); CheckStatus(env, status); } @@ -935,7 +935,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_setCameraBrightness (JNIEnv* env, jclass, jint source, jint brightness) { CS_Status status = 0; - cs::SetCameraBrightness(source, brightness, &status); + wpi::cs::SetCameraBrightness(source, brightness, &status); CheckStatus(env, status); } @@ -949,7 +949,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_getCameraBrightness (JNIEnv* env, jclass, jint source) { CS_Status status = 0; - auto val = cs::GetCameraBrightness(source, &status); + auto val = wpi::cs::GetCameraBrightness(source, &status); CheckStatus(env, status); return val; } @@ -964,7 +964,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_setCameraWhiteBalanceAuto (JNIEnv* env, jclass, jint source) { CS_Status status = 0; - cs::SetCameraWhiteBalanceAuto(source, &status); + wpi::cs::SetCameraWhiteBalanceAuto(source, &status); CheckStatus(env, status); } @@ -978,7 +978,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_setCameraWhiteBalanceHoldCurrent (JNIEnv* env, jclass, jint source) { CS_Status status = 0; - cs::SetCameraWhiteBalanceHoldCurrent(source, &status); + wpi::cs::SetCameraWhiteBalanceHoldCurrent(source, &status); CheckStatus(env, status); } @@ -992,7 +992,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_setCameraWhiteBalanceManual (JNIEnv* env, jclass, jint source, jint value) { CS_Status status = 0; - cs::SetCameraWhiteBalanceManual(source, value, &status); + wpi::cs::SetCameraWhiteBalanceManual(source, value, &status); CheckStatus(env, status); } @@ -1006,7 +1006,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_setCameraExposureAuto (JNIEnv* env, jclass, jint source) { CS_Status status = 0; - cs::SetCameraExposureAuto(source, &status); + wpi::cs::SetCameraExposureAuto(source, &status); CheckStatus(env, status); } @@ -1020,7 +1020,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_setCameraExposureHoldCurrent (JNIEnv* env, jclass, jint source) { CS_Status status = 0; - cs::SetCameraExposureHoldCurrent(source, &status); + wpi::cs::SetCameraExposureHoldCurrent(source, &status); CheckStatus(env, status); } @@ -1034,7 +1034,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_setCameraExposureManual (JNIEnv* env, jclass, jint source, jint value) { CS_Status status = 0; - cs::SetCameraExposureManual(source, value, &status); + wpi::cs::SetCameraExposureManual(source, value, &status); CheckStatus(env, status); } @@ -1048,7 +1048,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_setUsbCameraPath (JNIEnv* env, jclass, jint source, jstring path) { CS_Status status = 0; - cs::SetUsbCameraPath(source, JStringRef{env, path}.str(), &status); + wpi::cs::SetUsbCameraPath(source, JStringRef{env, path}.str(), &status); CheckStatus(env, status); } @@ -1062,7 +1062,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_getUsbCameraPath (JNIEnv* env, jclass, jint source) { CS_Status status = 0; - auto str = cs::GetUsbCameraPath(source, &status); + auto str = wpi::cs::GetUsbCameraPath(source, &status); if (!CheckStatus(env, status)) { return nullptr; } @@ -1079,7 +1079,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_getUsbCameraInfo (JNIEnv* env, jclass, jint source) { CS_Status status = 0; - auto info = cs::GetUsbCameraInfo(source, &status); + auto info = wpi::cs::GetUsbCameraInfo(source, &status); if (!CheckStatus(env, status)) { return nullptr; } @@ -1096,7 +1096,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_getHttpCameraKind (JNIEnv* env, jclass, jint source) { CS_Status status = 0; - auto kind = cs::GetHttpCameraKind(source, &status); + auto kind = wpi::cs::GetHttpCameraKind(source, &status); if (!CheckStatus(env, status)) { return 0; } @@ -1117,7 +1117,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_setHttpCameraUrls return; } size_t len = env->GetArrayLength(urls); - wpi::SmallVector vec; + wpi::util::SmallVector vec; vec.reserve(len); for (size_t i = 0; i < len; ++i) { JLocal elem{ @@ -1129,7 +1129,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_setHttpCameraUrls vec.emplace_back(JStringRef{env, elem}.str()); } CS_Status status = 0; - cs::SetHttpCameraUrls(source, vec, &status); + wpi::cs::SetHttpCameraUrls(source, vec, &status); CheckStatus(env, status); } @@ -1143,7 +1143,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_getHttpCameraUrls (JNIEnv* env, jclass, jint source) { CS_Status status = 0; - auto arr = cs::GetHttpCameraUrls(source, &status); + auto arr = wpi::cs::GetHttpCameraUrls(source, &status); if (!CheckStatus(env, status)) { return nullptr; } @@ -1159,13 +1159,13 @@ JNIEXPORT void JNICALL Java_org_wpilib_vision_camera_CameraServerJNI_putRawSourceFrame (JNIEnv* env, jclass, jint source, jlong framePtr) { - auto* frame = reinterpret_cast(framePtr); + auto* frame = reinterpret_cast(framePtr); if (!frame) { nullPointerEx.Throw(env, "frame is null"); return; } CS_Status status = 0; - cs::PutSourceFrame(source, *frame, &status); + wpi::cs::PutSourceFrame(source, *frame, &status); CheckStatus(env, status); } @@ -1193,7 +1193,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_putRawSourceFrameBB frame.stride = stride; frame.pixelFormat = pixelFormat; CS_Status status = 0; - cs::PutSourceFrame(source, frame, &status); + wpi::cs::PutSourceFrame(source, frame, &status); CheckStatus(env, status); } @@ -1221,7 +1221,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_putRawSourceFrameData frame.stride = stride; frame.pixelFormat = pixelFormat; CS_Status status = 0; - cs::PutSourceFrame(source, frame, &status); + wpi::cs::PutSourceFrame(source, frame, &status); CheckStatus(env, status); } @@ -1239,7 +1239,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_notifySourceError return; } CS_Status status = 0; - cs::NotifySourceError(source, JStringRef{env, msg}.str(), &status); + wpi::cs::NotifySourceError(source, JStringRef{env, msg}.str(), &status); CheckStatus(env, status); } @@ -1253,7 +1253,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_setSourceConnected (JNIEnv* env, jclass, jint source, jboolean connected) { CS_Status status = 0; - cs::SetSourceConnected(source, connected, &status); + wpi::cs::SetSourceConnected(source, connected, &status); CheckStatus(env, status); } @@ -1271,7 +1271,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_setSourceDescription return; } CS_Status status = 0; - cs::SetSourceDescription(source, JStringRef{env, description}.str(), &status); + wpi::cs::SetSourceDescription(source, JStringRef{env, description}.str(), &status); CheckStatus(env, status); } @@ -1286,7 +1286,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_createSourceProperty jint maximum, jint step, jint defaultValue, jint value) { CS_Status status = 0; - auto val = cs::CreateSourceProperty( + auto val = wpi::cs::CreateSourceProperty( source, JStringRef{env, name}.str(), static_cast(kind), minimum, maximum, step, defaultValue, value, &status); CheckStatus(env, status); @@ -1307,7 +1307,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_setSourceEnumPropertyChoices return; } size_t len = env->GetArrayLength(choices); - wpi::SmallVector vec; + wpi::util::SmallVector vec; vec.reserve(len); for (size_t i = 0; i < len; ++i) { JLocal elem{ @@ -1319,7 +1319,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_setSourceEnumPropertyChoices vec.emplace_back(JStringRef{env, elem}.str()); } CS_Status status = 0; - cs::SetSourceEnumPropertyChoices(source, property, vec, &status); + wpi::cs::SetSourceEnumPropertyChoices(source, property, vec, &status); CheckStatus(env, status); } @@ -1341,7 +1341,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_createMjpegServer return 0; } CS_Status status = 0; - auto val = cs::CreateMjpegServer(JStringRef{env, name}.str(), + auto val = wpi::cs::CreateMjpegServer(JStringRef{env, name}.str(), JStringRef{env, listenAddress}.str(), port, &status); CheckStatus(env, status); @@ -1362,7 +1362,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_createRawSink return 0; } CS_Status status = 0; - auto val = cs::CreateRawSink(JStringRef{env, name}.str(), isCv, &status); + auto val = wpi::cs::CreateRawSink(JStringRef{env, name}.str(), isCv, &status); CheckStatus(env, status); return val; } @@ -1377,7 +1377,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_getSinkKind (JNIEnv* env, jclass, jint sink) { CS_Status status = 0; - auto val = cs::GetSinkKind(sink, &status); + auto val = wpi::cs::GetSinkKind(sink, &status); CheckStatus(env, status); return val; } @@ -1392,8 +1392,8 @@ Java_org_wpilib_vision_camera_CameraServerJNI_getSinkName (JNIEnv* env, jclass, jint sink) { CS_Status status = 0; - wpi::SmallString<128> buf; - auto str = cs::GetSinkName(sink, buf, &status); + wpi::util::SmallString<128> buf; + auto str = wpi::cs::GetSinkName(sink, buf, &status); if (!CheckStatus(env, status)) { return nullptr; } @@ -1410,8 +1410,8 @@ Java_org_wpilib_vision_camera_CameraServerJNI_getSinkDescription (JNIEnv* env, jclass, jint sink) { CS_Status status = 0; - wpi::SmallString<128> buf; - auto str = cs::GetSinkDescription(sink, buf, &status); + wpi::util::SmallString<128> buf; + auto str = wpi::cs::GetSinkDescription(sink, buf, &status); if (!CheckStatus(env, status)) { return nullptr; } @@ -1432,7 +1432,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_getSinkProperty return 0; } CS_Status status = 0; - auto val = cs::GetSinkProperty(sink, JStringRef{env, name}.str(), &status); + auto val = wpi::cs::GetSinkProperty(sink, JStringRef{env, name}.str(), &status); CheckStatus(env, status); return val; } @@ -1447,8 +1447,8 @@ Java_org_wpilib_vision_camera_CameraServerJNI_enumerateSinkProperties (JNIEnv* env, jclass, jint source) { CS_Status status = 0; - wpi::SmallVector buf; - auto arr = cs::EnumerateSinkProperties(source, buf, &status); + wpi::util::SmallVector buf; + auto arr = wpi::cs::EnumerateSinkProperties(source, buf, &status); if (!CheckStatus(env, status)) { return nullptr; } @@ -1465,7 +1465,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_setSinkConfigJson (JNIEnv* env, jclass, jint source, jstring config) { CS_Status status = 0; - auto val = cs::SetSinkConfigJson(source, JStringRef{env, config}, &status); + auto val = wpi::cs::SetSinkConfigJson(source, JStringRef{env, config}, &status); CheckStatus(env, status); return val; } @@ -1480,7 +1480,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_getSinkConfigJson (JNIEnv* env, jclass, jint source) { CS_Status status = 0; - auto val = cs::GetSinkConfigJson(source, &status); + auto val = wpi::cs::GetSinkConfigJson(source, &status); CheckStatus(env, status); return MakeJString(env, val); } @@ -1495,7 +1495,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_setSinkSource (JNIEnv* env, jclass, jint sink, jint source) { CS_Status status = 0; - cs::SetSinkSource(sink, source, &status); + wpi::cs::SetSinkSource(sink, source, &status); CheckStatus(env, status); } @@ -1514,7 +1514,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_getSinkSourceProperty } CS_Status status = 0; auto val = - cs::GetSinkSourceProperty(sink, JStringRef{env, name}.str(), &status); + wpi::cs::GetSinkSourceProperty(sink, JStringRef{env, name}.str(), &status); CheckStatus(env, status); return val; } @@ -1529,7 +1529,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_getSinkSource (JNIEnv* env, jclass, jint sink) { CS_Status status = 0; - auto val = cs::GetSinkSource(sink, &status); + auto val = wpi::cs::GetSinkSource(sink, &status); CheckStatus(env, status); return val; } @@ -1544,7 +1544,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_copySink (JNIEnv* env, jclass, jint sink) { CS_Status status = 0; - auto val = cs::CopySink(sink, &status); + auto val = wpi::cs::CopySink(sink, &status); CheckStatus(env, status); return val; } @@ -1559,7 +1559,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_releaseSink (JNIEnv* env, jclass, jint sink) { CS_Status status = 0; - cs::ReleaseSink(sink, &status); + wpi::cs::ReleaseSink(sink, &status); CheckStatus(env, status); } @@ -1573,7 +1573,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_getMjpegServerListenAddress (JNIEnv* env, jclass, jint sink) { CS_Status status = 0; - auto str = cs::GetMjpegServerListenAddress(sink, &status); + auto str = wpi::cs::GetMjpegServerListenAddress(sink, &status); if (!CheckStatus(env, status)) { return nullptr; } @@ -1590,7 +1590,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_getMjpegServerPort (JNIEnv* env, jclass, jint sink) { CS_Status status = 0; - auto val = cs::GetMjpegServerPort(sink, &status); + auto val = wpi::cs::GetMjpegServerPort(sink, &status); CheckStatus(env, status); return val; } @@ -1609,7 +1609,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_setSinkDescription return; } CS_Status status = 0; - cs::SetSinkDescription(sink, JStringRef{env, description}.str(), &status); + wpi::cs::SetSinkDescription(sink, JStringRef{env, description}.str(), &status); CheckStatus(env, status); } @@ -1622,14 +1622,14 @@ JNIEXPORT jlong JNICALL Java_org_wpilib_vision_camera_CameraServerJNI_grabRawSinkFrame (JNIEnv* env, jclass, jint sink, jobject frameObj, jlong framePtr) { - auto* frame = reinterpret_cast(framePtr); + auto* frame = reinterpret_cast(framePtr); auto origData = frame->data; CS_Status status = 0; - auto rv = cs::GrabSinkFrame(static_cast(sink), *frame, &status); + auto rv = wpi::cs::GrabSinkFrame(static_cast(sink), *frame, &status); if (!CheckStatus(env, status)) { return 0; } - wpi::SetFrameData(env, rawFrameCls, frameObj, *frame, + wpi::util::SetFrameData(env, rawFrameCls, frameObj, *frame, origData != frame->data); return rv; } @@ -1644,15 +1644,15 @@ Java_org_wpilib_vision_camera_CameraServerJNI_grabRawSinkFrameTimeout (JNIEnv* env, jclass, jint sink, jobject frameObj, jlong framePtr, jdouble timeout) { - auto* frame = reinterpret_cast(framePtr); + auto* frame = reinterpret_cast(framePtr); auto origData = frame->data; CS_Status status = 0; - auto rv = cs::GrabSinkFrameTimeout(static_cast(sink), *frame, + auto rv = wpi::cs::GrabSinkFrameTimeout(static_cast(sink), *frame, timeout, &status); if (!CheckStatus(env, status)) { return 0; } - wpi::SetFrameData(env, rawFrameCls, frameObj, *frame, + wpi::util::SetFrameData(env, rawFrameCls, frameObj, *frame, origData != frame->data); return rv; } @@ -1667,8 +1667,8 @@ Java_org_wpilib_vision_camera_CameraServerJNI_getSinkError (JNIEnv* env, jclass, jint sink) { CS_Status status = 0; - wpi::SmallString<128> buf; - auto str = cs::GetSinkError(sink, buf, &status); + wpi::util::SmallString<128> buf; + auto str = wpi::cs::GetSinkError(sink, buf, &status); if (!CheckStatus(env, status)) { return nullptr; } @@ -1685,7 +1685,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_setSinkEnabled (JNIEnv* env, jclass, jint sink, jboolean enabled) { CS_Status status = 0; - cs::SetSinkEnabled(sink, enabled, &status); + wpi::cs::SetSinkEnabled(sink, enabled, &status); CheckStatus(env, status); } @@ -1721,8 +1721,8 @@ Java_org_wpilib_vision_camera_CameraServerJNI_addListener } CS_Status status = 0; - CS_Listener handle = cs::AddListener( - [=](const cs::RawEvent& event) { + CS_Listener handle = wpi::cs::AddListener( + [=](const wpi::cs::RawEvent& event) { JNIEnv* env = listenerEnv; if (!env || !env->functions) { return; @@ -1763,7 +1763,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_removeListener (JNIEnv* env, jclass, jint handle) { CS_Status status = 0; - cs::RemoveListener(handle, &status); + wpi::cs::RemoveListener(handle, &status); CheckStatus(env, status); } @@ -1776,7 +1776,7 @@ JNIEXPORT jint JNICALL Java_org_wpilib_vision_camera_CameraServerJNI_createListenerPoller (JNIEnv*, jclass) { - return cs::CreateListenerPoller(); + return wpi::cs::CreateListenerPoller(); } /* @@ -1788,7 +1788,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_vision_camera_CameraServerJNI_destroyListenerPoller (JNIEnv*, jclass, jint poller) { - cs::DestroyListenerPoller(poller); + wpi::cs::DestroyListenerPoller(poller); } /* @@ -1801,7 +1801,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_addPolledListener (JNIEnv* env, jclass, jint poller, jint eventMask, jboolean immediateNotify) { CS_Status status = 0; - auto rv = cs::AddPolledListener(poller, eventMask, immediateNotify, &status); + auto rv = wpi::cs::AddPolledListener(poller, eventMask, immediateNotify, &status); CheckStatus(env, status); return rv; } @@ -1815,7 +1815,7 @@ JNIEXPORT jobjectArray JNICALL Java_org_wpilib_vision_camera_CameraServerJNI_pollListener (JNIEnv* env, jclass, jint poller) { - auto events = cs::PollListener(poller); + auto events = wpi::cs::PollListener(poller); if (events.empty()) { interruptedEx.Throw(env, "PollListener interrupted"); return nullptr; @@ -1833,7 +1833,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_pollListenerTimeout (JNIEnv* env, jclass, jint poller, jdouble timeout) { bool timed_out = false; - auto events = cs::PollListener(poller, timeout, &timed_out); + auto events = wpi::cs::PollListener(poller, timeout, &timed_out); if (events.empty() && !timed_out) { interruptedEx.Throw(env, "PollListener interrupted"); return nullptr; @@ -1850,7 +1850,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_vision_camera_CameraServerJNI_cancelPollListener (JNIEnv*, jclass, jint poller) { - cs::CancelPollListener(poller); + wpi::cs::CancelPollListener(poller); } /* @@ -1862,7 +1862,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_vision_camera_CameraServerJNI_setTelemetryPeriod (JNIEnv* env, jclass, jdouble seconds) { - cs::SetTelemetryPeriod(seconds); + wpi::cs::SetTelemetryPeriod(seconds); } /* @@ -1874,7 +1874,7 @@ JNIEXPORT jdouble JNICALL Java_org_wpilib_vision_camera_CameraServerJNI_getTelemetryElapsedTime (JNIEnv* env, jclass) { - return cs::GetTelemetryElapsedTime(); + return wpi::cs::GetTelemetryElapsedTime(); } /* @@ -1887,7 +1887,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_getTelemetryValue (JNIEnv* env, jclass, jint handle, jint kind) { CS_Status status = 0; - auto val = cs::GetTelemetryValue(handle, static_cast(kind), + auto val = wpi::cs::GetTelemetryValue(handle, static_cast(kind), &status); CheckStatus(env, status); return val; @@ -1903,7 +1903,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_getTelemetryAverageValue (JNIEnv* env, jclass, jint handle, jint kind) { CS_Status status = 0; - auto val = cs::GetTelemetryAverageValue( + auto val = wpi::cs::GetTelemetryAverageValue( handle, static_cast(kind), &status); CheckStatus(env, status); return val; @@ -1919,7 +1919,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_enumerateUsbCameras (JNIEnv* env, jclass) { CS_Status status = 0; - auto arr = cs::EnumerateUsbCameras(&status); + auto arr = wpi::cs::EnumerateUsbCameras(&status); if (!CheckStatus(env, status)) { return nullptr; } @@ -1945,8 +1945,8 @@ Java_org_wpilib_vision_camera_CameraServerJNI_enumerateSources (JNIEnv* env, jclass) { CS_Status status = 0; - wpi::SmallVector buf; - auto arr = cs::EnumerateSourceHandles(buf, &status); + wpi::util::SmallVector buf; + auto arr = wpi::cs::EnumerateSourceHandles(buf, &status); if (!CheckStatus(env, status)) { return nullptr; } @@ -1963,8 +1963,8 @@ Java_org_wpilib_vision_camera_CameraServerJNI_enumerateSinks (JNIEnv* env, jclass) { CS_Status status = 0; - wpi::SmallVector buf; - auto arr = cs::EnumerateSinkHandles(buf, &status); + wpi::util::SmallVector buf; + auto arr = wpi::cs::EnumerateSinkHandles(buf, &status); if (!CheckStatus(env, status)) { return nullptr; } @@ -1980,7 +1980,7 @@ JNIEXPORT jstring JNICALL Java_org_wpilib_vision_camera_CameraServerJNI_getHostname (JNIEnv* env, jclass) { - return MakeJString(env, cs::GetHostname()); + return MakeJString(env, wpi::cs::GetHostname()); } /* @@ -1992,7 +1992,7 @@ JNIEXPORT jobjectArray JNICALL Java_org_wpilib_vision_camera_CameraServerJNI_getNetworkInterfaces (JNIEnv* env, jclass) { - return MakeJStringArray(env, cs::GetNetworkInterfaces()); + return MakeJStringArray(env, wpi::cs::GetNetworkInterfaces()); } } // extern "C" @@ -2058,7 +2058,7 @@ Java_org_wpilib_vision_camera_CameraServerJNI_setLogger logger.Start(); logger.SetFunc(env, func, mid); - cs::SetLogger( + wpi::cs::SetLogger( [](unsigned int level, const char* file, unsigned int line, const char* msg) { LoggerJNI::GetInstance().Send(level, file, line, msg); @@ -2075,7 +2075,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_vision_camera_CameraServerJNI_runMainRunLoop (JNIEnv*, jclass) { - cs::RunMainRunLoop(); + wpi::cs::RunMainRunLoop(); } /* @@ -2087,7 +2087,7 @@ JNIEXPORT jint JNICALL Java_org_wpilib_vision_camera_CameraServerJNI_runMainRunLoopTimeout (JNIEnv*, jclass, jdouble timeout) { - return cs::RunMainRunLoopTimeout(timeout); + return wpi::cs::RunMainRunLoopTimeout(timeout); } /* @@ -2099,7 +2099,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_vision_camera_CameraServerJNI_stopMainRunLoop (JNIEnv*, jclass) { - return cs::StopMainRunLoop(); + return wpi::cs::StopMainRunLoop(); } } // extern "C" diff --git a/cscore/src/main/native/include/wpi/cs/cscore_cpp.hpp b/cscore/src/main/native/include/wpi/cs/cscore_cpp.hpp index 63bfe23d18..66ccfe5654 100644 --- a/cscore/src/main/native/include/wpi/cs/cscore_cpp.hpp +++ b/cscore/src/main/native/include/wpi/cs/cscore_cpp.hpp @@ -25,7 +25,7 @@ #endif /** CameraServer (cscore) namespace */ -namespace cs { +namespace wpi::cs { /** * @defgroup cscore_cpp_api cscore C++ function API @@ -178,7 +178,7 @@ struct RawEvent { CS_PropertyKind GetPropertyKind(CS_Property property, CS_Status* status); std::string GetPropertyName(CS_Property property, CS_Status* status); std::string_view GetPropertyName(CS_Property property, - wpi::SmallVectorImpl& buf, + wpi::util::SmallVectorImpl& buf, CS_Status* status); int GetProperty(CS_Property property, CS_Status* status); void SetProperty(CS_Property property, int value, CS_Status* status); @@ -188,7 +188,7 @@ int GetPropertyStep(CS_Property property, CS_Status* status); int GetPropertyDefault(CS_Property property, CS_Status* status); std::string GetStringProperty(CS_Property property, CS_Status* status); std::string_view GetStringProperty(CS_Property property, - wpi::SmallVectorImpl& buf, + wpi::util::SmallVectorImpl& buf, CS_Status* status); void SetStringProperty(CS_Property property, std::string_view value, CS_Status* status); @@ -219,11 +219,11 @@ CS_Source CreateCvSource(std::string_view name, const VideoMode& mode, CS_SourceKind GetSourceKind(CS_Source source, CS_Status* status); std::string GetSourceName(CS_Source source, CS_Status* status); std::string_view GetSourceName(CS_Source source, - wpi::SmallVectorImpl& buf, + wpi::util::SmallVectorImpl& buf, CS_Status* status); std::string GetSourceDescription(CS_Source source, CS_Status* status); std::string_view GetSourceDescription(CS_Source source, - wpi::SmallVectorImpl& buf, + wpi::util::SmallVectorImpl& buf, CS_Status* status); uint64_t GetSourceLastFrameTime(CS_Source source, CS_Status* status); void SetSourceConnectionStrategy(CS_Source source, @@ -234,7 +234,7 @@ bool IsSourceEnabled(CS_Source source, CS_Status* status); CS_Property GetSourceProperty(CS_Source source, std::string_view name, CS_Status* status); std::span EnumerateSourceProperties( - CS_Source source, wpi::SmallVectorImpl& vec, + CS_Source source, wpi::util::SmallVectorImpl& vec, CS_Status* status); VideoMode GetSourceVideoMode(CS_Source source, CS_Status* status); bool SetSourceVideoMode(CS_Source source, const VideoMode& mode, @@ -246,14 +246,14 @@ bool SetSourceResolution(CS_Source source, int width, int height, bool SetSourceFPS(CS_Source source, int fps, CS_Status* status); bool SetSourceConfigJson(CS_Source source, std::string_view config, CS_Status* status); -bool SetSourceConfigJson(CS_Source source, const wpi::json& config, +bool SetSourceConfigJson(CS_Source source, const wpi::util::json& config, CS_Status* status); std::string GetSourceConfigJson(CS_Source source, CS_Status* status); -wpi::json GetSourceConfigJsonObject(CS_Source source, CS_Status* status); +wpi::util::json GetSourceConfigJsonObject(CS_Source source, CS_Status* status); std::vector EnumerateSourceVideoModes(CS_Source source, CS_Status* status); std::span EnumerateSourceSinks(CS_Source source, - wpi::SmallVectorImpl& vec, + wpi::util::SmallVectorImpl& vec, CS_Status* status); CS_Source CopySource(CS_Source source, CS_Status* status); void ReleaseSource(CS_Source source, CS_Status* status); @@ -332,25 +332,25 @@ CS_Sink CreateCvSinkCallback(std::string_view name, */ CS_SinkKind GetSinkKind(CS_Sink sink, CS_Status* status); std::string GetSinkName(CS_Sink sink, CS_Status* status); -std::string_view GetSinkName(CS_Sink sink, wpi::SmallVectorImpl& buf, +std::string_view GetSinkName(CS_Sink sink, wpi::util::SmallVectorImpl& buf, CS_Status* status); std::string GetSinkDescription(CS_Sink sink, CS_Status* status); std::string_view GetSinkDescription(CS_Sink sink, - wpi::SmallVectorImpl& buf, + wpi::util::SmallVectorImpl& buf, CS_Status* status); CS_Property GetSinkProperty(CS_Sink sink, std::string_view name, CS_Status* status); std::span EnumerateSinkProperties( - CS_Sink sink, wpi::SmallVectorImpl& vec, CS_Status* status); + CS_Sink sink, wpi::util::SmallVectorImpl& vec, CS_Status* status); void SetSinkSource(CS_Sink sink, CS_Source source, CS_Status* status); CS_Property GetSinkSourceProperty(CS_Sink sink, std::string_view name, CS_Status* status); bool SetSinkConfigJson(CS_Sink sink, std::string_view config, CS_Status* status); -bool SetSinkConfigJson(CS_Sink sink, const wpi::json& config, +bool SetSinkConfigJson(CS_Sink sink, const wpi::util::json& config, CS_Status* status); std::string GetSinkConfigJson(CS_Sink sink, CS_Status* status); -wpi::json GetSinkConfigJsonObject(CS_Sink sink, CS_Status* status); +wpi::util::json GetSinkConfigJsonObject(CS_Sink sink, CS_Status* status); CS_Source GetSinkSource(CS_Sink sink, CS_Status* status); CS_Sink CopySink(CS_Sink sink, CS_Status* status); void ReleaseSink(CS_Sink sink, CS_Status* status); @@ -371,7 +371,7 @@ int GetMjpegServerPort(CS_Sink sink, CS_Status* status); void SetSinkDescription(CS_Sink sink, std::string_view description, CS_Status* status); std::string GetSinkError(CS_Sink sink, CS_Status* status); -std::string_view GetSinkError(CS_Sink sink, wpi::SmallVectorImpl& buf, +std::string_view GetSinkError(CS_Sink sink, wpi::util::SmallVectorImpl& buf, CS_Status* status); void SetSinkEnabled(CS_Sink sink, bool enabled, CS_Status* status); /** @} */ @@ -436,8 +436,8 @@ void Shutdown(); std::vector EnumerateUsbCameras(CS_Status* status); std::span EnumerateSourceHandles( - wpi::SmallVectorImpl& vec, CS_Status* status); -std::span EnumerateSinkHandles(wpi::SmallVectorImpl& vec, + wpi::util::SmallVectorImpl& vec, CS_Status* status); +std::span EnumerateSinkHandles(wpi::util::SmallVectorImpl& vec, CS_Status* status); std::string GetHostname(); @@ -447,7 +447,7 @@ std::vector GetNetworkInterfaces(); /** @} */ -} // namespace cs +} // namespace wpi::cs #ifdef _WIN32 // Disable uninitialized variable warnings diff --git a/cscore/src/main/native/include/wpi/cs/cscore_cv.hpp b/cscore/src/main/native/include/wpi/cs/cscore_cv.hpp index 1894c2537d..c3e79f2b93 100644 --- a/cscore/src/main/native/include/wpi/cs/cscore_cv.hpp +++ b/cscore/src/main/native/include/wpi/cs/cscore_cv.hpp @@ -13,7 +13,7 @@ #include "wpi/cs/cscore_raw.h" #include "wpi/util/RawFrame.h" -namespace cs { +namespace wpi::cs { /** * A source for user code to provide OpenCV images as video frames. * @@ -107,7 +107,7 @@ class CvSink : public ImageSink { * with. * * @return Frame time, or 0 on error (call GetError() to obtain the error - * message); the frame time is in the same time base as wpi::Now(), + * message); the frame time is in the same time base as wpi::util::Now(), * and is in 1 us increments. */ [[nodiscard]] @@ -119,7 +119,7 @@ class CvSink : public ImageSink { * with. * * @return Frame time, or 0 on error (call GetError() to obtain the error - * message); the frame time is in the same time base as wpi::Now(), + * message); the frame time is in the same time base as wpi::util::Now(), * and is in 1 us increments. */ [[nodiscard]] @@ -133,7 +133,7 @@ class CvSink : public ImageSink { * any grabFrame*() call on the sink. * * @return Frame time, or 0 on error (call GetError() to obtain the error - * message); the frame time is in the same time base as wpi::Now(), + * message); the frame time is in the same time base as wpi::util::Now(), * and is in 1 us increments. */ [[nodiscard]] @@ -146,7 +146,7 @@ class CvSink : public ImageSink { * any grabFrame*() call on the sink. * * @return Frame time, or 0 on error (call GetError() to obtain the error - * message); the frame time is in the same time base as wpi::Now(), + * message); the frame time is in the same time base as wpi::util::Now(), * and is in 1 us increments. */ [[nodiscard]] @@ -166,7 +166,7 @@ class CvSink : public ImageSink { * a new frame. * * @return Frame time, or 0 on error (call GetError() to obtain the error - * message); the frame time is in the same time base as wpi::Now(), + * message); the frame time is in the same time base as wpi::util::Now(), * and is in 1 us increments. */ [[nodiscard]] @@ -175,7 +175,7 @@ class CvSink : public ImageSink { /** * Get the last time a frame was grabbed. This uses the same time base as - * wpi::Now(). + * wpi::util::Now(). * * @return Time in 1 us increments. */ @@ -193,7 +193,7 @@ class CvSink : public ImageSink { private: constexpr int GetCvFormat(WPI_PixelFormat pixelFormat); - wpi::RawFrame rawFrame; + wpi::util::RawFrame rawFrame; VideoMode::PixelFormat pixelFormat; }; @@ -431,6 +431,6 @@ inline WPI_TimestampSource CvSink::LastFrameTimeSource() { return static_cast(rawFrame.timestampSrc); } -} // namespace cs +} // namespace wpi::cs #endif // CSCORE_WPI_CS_CSCORE_CV_HPP_ diff --git a/cscore/src/main/native/include/wpi/cs/cscore_oo.hpp b/cscore/src/main/native/include/wpi/cs/cscore_oo.hpp index c3c66ee3d5..80e038d0ca 100644 --- a/cscore/src/main/native/include/wpi/cs/cscore_oo.hpp +++ b/cscore/src/main/native/include/wpi/cs/cscore_oo.hpp @@ -16,7 +16,7 @@ #include "wpi/cs/cscore_cpp.hpp" #include "wpi/util/deprecated.hpp" -namespace cs { +namespace wpi::cs { /** * @defgroup cscore_oo cscore C++ object-oriented API @@ -191,7 +191,7 @@ class VideoProperty { * @param buf The backing storage to which to write the property value. * @return The string property value as a reference to the given buffer. */ - std::string_view GetString(wpi::SmallVectorImpl& buf) const { + std::string_view GetString(wpi::util::SmallVectorImpl& buf) const { m_status = 0; return GetStringProperty(m_handle, buf, &m_status); } @@ -349,7 +349,7 @@ class VideoSource { /** * Get the last time a frame was captured. - * This uses the same time base as wpi::Now(). + * This uses the same time base as wpi::util::Now(). * * @return Time in 1 us increments. */ @@ -515,7 +515,7 @@ class VideoSource { * @param config configuration * @return True if set successfully */ - bool SetConfigJson(const wpi::json& config) { + bool SetConfigJson(const wpi::util::json& config) { m_status = 0; return SetSourceConfigJson(m_handle, config, &m_status); } @@ -535,7 +535,7 @@ class VideoSource { * * @return JSON configuration object */ - wpi::json GetConfigJsonObject() const; + wpi::util::json GetConfigJsonObject() const; /** * Get the actual FPS. @@ -546,7 +546,7 @@ class VideoSource { */ double GetActualFPS() const { m_status = 0; - return cs::GetTelemetryAverageValue(m_handle, CS_SOURCE_FRAMES_RECEIVED, + return wpi::cs::GetTelemetryAverageValue(m_handle, CS_SOURCE_FRAMES_RECEIVED, &m_status); } @@ -559,7 +559,7 @@ class VideoSource { */ double GetActualDataRate() const { m_status = 0; - return cs::GetTelemetryAverageValue(m_handle, CS_SOURCE_BYTES_RECEIVED, + return wpi::cs::GetTelemetryAverageValue(m_handle, CS_SOURCE_BYTES_RECEIVED, &m_status); } @@ -727,7 +727,7 @@ class UsbCamera : public VideoCamera { */ static std::vector EnumerateUsbCameras() { CS_Status status = 0; - return ::cs::EnumerateUsbCameras(&status); + return ::wpi::cs::EnumerateUsbCameras(&status); } /** @@ -735,7 +735,7 @@ class UsbCamera : public VideoCamera { */ void SetPath(std::string_view path) { m_status = 0; - return ::cs::SetUsbCameraPath(m_handle, path, &m_status); + return ::wpi::cs::SetUsbCameraPath(m_handle, path, &m_status); } /** @@ -743,7 +743,7 @@ class UsbCamera : public VideoCamera { */ std::string GetPath() const { m_status = 0; - return ::cs::GetUsbCameraPath(m_handle, &m_status); + return ::wpi::cs::GetUsbCameraPath(m_handle, &m_status); } /** @@ -751,7 +751,7 @@ class UsbCamera : public VideoCamera { */ UsbCameraInfo GetInfo() const { m_status = 0; - return ::cs::GetUsbCameraInfo(m_handle, &m_status); + return ::wpi::cs::GetUsbCameraInfo(m_handle, &m_status); } /** @@ -867,7 +867,7 @@ class HttpCamera : public VideoCamera { HttpCameraKind GetHttpCameraKind() const { m_status = 0; return static_cast( - static_cast(::cs::GetHttpCameraKind(m_handle, &m_status))); + static_cast(::wpi::cs::GetHttpCameraKind(m_handle, &m_status))); } /** @@ -875,7 +875,7 @@ class HttpCamera : public VideoCamera { */ void SetUrls(std::span urls) { m_status = 0; - ::cs::SetHttpCameraUrls(m_handle, urls, &m_status); + ::wpi::cs::SetHttpCameraUrls(m_handle, urls, &m_status); } /** @@ -889,7 +889,7 @@ class HttpCamera : public VideoCamera { vec.emplace_back(url); } m_status = 0; - ::cs::SetHttpCameraUrls(m_handle, vec, &m_status); + ::wpi::cs::SetHttpCameraUrls(m_handle, vec, &m_status); } /** @@ -897,7 +897,7 @@ class HttpCamera : public VideoCamera { */ std::vector GetUrls() const { m_status = 0; - return ::cs::GetHttpCameraUrls(m_handle, &m_status); + return ::wpi::cs::GetHttpCameraUrls(m_handle, &m_status); } }; @@ -1256,7 +1256,7 @@ class VideoSink { * @param config configuration * @return True if set successfully */ - bool SetConfigJson(const wpi::json& config) { + bool SetConfigJson(const wpi::util::json& config) { m_status = 0; return SetSinkConfigJson(m_handle, config, &m_status); } @@ -1276,7 +1276,7 @@ class VideoSink { * * @return JSON configuration object */ - wpi::json GetConfigJsonObject() const; + wpi::util::json GetConfigJsonObject() const; /** * Configure which source should provide frames to this sink. Each sink @@ -1370,7 +1370,7 @@ class MjpegServer : public VideoSink { */ std::string GetListenAddress() const { m_status = 0; - return cs::GetMjpegServerListenAddress(m_handle, &m_status); + return wpi::cs::GetMjpegServerListenAddress(m_handle, &m_status); } /** @@ -1378,7 +1378,7 @@ class MjpegServer : public VideoSink { */ int GetPort() const { m_status = 0; - return cs::GetMjpegServerPort(m_handle, &m_status); + return wpi::cs::GetMjpegServerPort(m_handle, &m_status); } /** @@ -1577,6 +1577,6 @@ class VideoListener { /** @} */ -} // namespace cs +} // namespace wpi::cs #endif // CSCORE_WPI_CS_CSCORE_OO_HPP_ diff --git a/cscore/src/main/native/include/wpi/cs/cscore_raw.h b/cscore/src/main/native/include/wpi/cs/cscore_raw.h index 11f80c2508..7b3ff550a2 100644 --- a/cscore/src/main/native/include/wpi/cs/cscore_raw.h +++ b/cscore/src/main/native/include/wpi/cs/cscore_raw.h @@ -52,7 +52,7 @@ CS_Source CS_CreateRawSource(const struct WPI_String* name, CS_Bool isCv, #endif #ifdef __cplusplus -namespace cs { +namespace wpi::cs { /** * @defgroup cscore_raw_func Raw Image Functions @@ -111,7 +111,7 @@ class RawSource : public ImageSource { * * @param image raw frame image */ - void PutFrame(wpi::RawFrame& image); + void PutFrame(wpi::util::RawFrame& image); }; /** @@ -155,22 +155,22 @@ class RawSink : public ImageSink { * The provided image will have three 8-bit channels stored in BGR order. * * @return Frame time, or 0 on error (call GetError() to obtain the error - * message); the frame time is in the same time base as wpi::Now(), + * message); the frame time is in the same time base as wpi::util::Now(), * and is in 1 us increments. */ [[nodiscard]] - uint64_t GrabFrame(wpi::RawFrame& image, double timeout = 0.225) const; + uint64_t GrabFrame(wpi::util::RawFrame& image, double timeout = 0.225) const; /** * Wait for the next frame and get the image. May block forever. * The provided image will have three 8-bit channels stored in BGR order. * * @return Frame time, or 0 on error (call GetError() to obtain the error - * message); the frame time is in the same time base as wpi::Now(), + * message); the frame time is in the same time base as wpi::util::Now(), * and is in 1 us increments. */ [[nodiscard]] - uint64_t GrabFrameNoTimeout(wpi::RawFrame& image) const; + uint64_t GrabFrameNoTimeout(wpi::util::RawFrame& image) const; /** * Wait for the next frame and get the image. May block forever. @@ -183,11 +183,11 @@ class RawSink : public ImageSink { * a new frame. * * @return Frame time, or 0 on error (call GetError() to obtain the error - * message); the frame time is in the same time base as wpi::Now(), + * message); the frame time is in the same time base as wpi::util::Now(), * and is in 1 us increments. */ [[nodiscard]] - uint64_t GrabFrameLastTime(wpi::RawFrame& image, uint64_t lastFrameTime, + uint64_t GrabFrameLastTime(wpi::util::RawFrame& image, uint64_t lastFrameTime, double timeout = 0.225) const; }; @@ -202,7 +202,7 @@ inline RawSource::RawSource(std::string_view name, &m_status); } -inline void RawSource::PutFrame(wpi::RawFrame& image) { +inline void RawSource::PutFrame(wpi::util::RawFrame& image) { m_status = 0; PutSourceFrame(m_handle, image, &m_status); } @@ -216,17 +216,17 @@ inline RawSink::RawSink(std::string_view name, m_handle = CreateRawSinkCallback(name, false, processFrame, &m_status); } -inline uint64_t RawSink::GrabFrame(wpi::RawFrame& image, double timeout) const { +inline uint64_t RawSink::GrabFrame(wpi::util::RawFrame& image, double timeout) const { m_status = 0; return GrabSinkFrameTimeout(m_handle, image, timeout, &m_status); } -inline uint64_t RawSink::GrabFrameNoTimeout(wpi::RawFrame& image) const { +inline uint64_t RawSink::GrabFrameNoTimeout(wpi::util::RawFrame& image) const { m_status = 0; return GrabSinkFrame(m_handle, image, &m_status); } -inline uint64_t RawSink::GrabFrameLastTime(wpi::RawFrame& image, +inline uint64_t RawSink::GrabFrameLastTime(wpi::util::RawFrame& image, uint64_t lastFrameTime, double timeout) const { m_status = 0; @@ -235,7 +235,7 @@ inline uint64_t RawSink::GrabFrameLastTime(wpi::RawFrame& image, } /** @} */ -} // namespace cs +} // namespace wpi::cs #endif diff --git a/cscore/src/main/native/include/wpi/cs/cscore_runloop.hpp b/cscore/src/main/native/include/wpi/cs/cscore_runloop.hpp index 255feb45db..4152ec0ab6 100644 --- a/cscore/src/main/native/include/wpi/cs/cscore_runloop.hpp +++ b/cscore/src/main/native/include/wpi/cs/cscore_runloop.hpp @@ -4,7 +4,7 @@ #pragma once -namespace cs { +namespace wpi::cs { void RunMainRunLoop(); @@ -17,4 +17,4 @@ int RunMainRunLoopTimeout(double timeout); void StopMainRunLoop(); -} // namespace cs +} // namespace wpi::cs diff --git a/cscore/src/main/native/linux/NetworkListener.cpp b/cscore/src/main/native/linux/NetworkListener.cpp index 382d97ca1d..c48c9da6cc 100644 --- a/cscore/src/main/native/linux/NetworkListener.cpp +++ b/cscore/src/main/native/linux/NetworkListener.cpp @@ -20,31 +20,31 @@ #include "Notifier.hpp" #include "wpi/util/SafeThread.hpp" -using namespace cs; +using namespace wpi::cs; class NetworkListener::Impl { public: - Impl(wpi::Logger& logger, Notifier& notifier) + Impl(wpi::util::Logger& logger, Notifier& notifier) : m_logger(logger), m_notifier(notifier) {} - wpi::Logger& m_logger; + wpi::util::Logger& m_logger; Notifier& m_notifier; - class Thread : public wpi::SafeThread { + class Thread : public wpi::util::SafeThread { public: - Thread(wpi::Logger& logger, Notifier& notifier) + Thread(wpi::util::Logger& logger, Notifier& notifier) : m_logger(logger), m_notifier(notifier) {} void Main() override; - wpi::Logger& m_logger; + wpi::util::Logger& m_logger; Notifier& m_notifier; int m_command_fd = -1; }; - wpi::SafeThreadOwner m_owner; + wpi::util::SafeThreadOwner m_owner; }; -NetworkListener::NetworkListener(wpi::Logger& logger, Notifier& notifier) +NetworkListener::NetworkListener(wpi::util::Logger& logger, Notifier& notifier) : m_impl(std::make_unique(logger, notifier)) {} NetworkListener::~NetworkListener() { diff --git a/cscore/src/main/native/linux/NetworkUtil.cpp b/cscore/src/main/native/linux/NetworkUtil.cpp index d15398f441..160ab4458c 100644 --- a/cscore/src/main/native/linux/NetworkUtil.cpp +++ b/cscore/src/main/native/linux/NetworkUtil.cpp @@ -12,7 +12,7 @@ #include #include -namespace cs { +namespace wpi::cs { std::vector GetNetworkInterfaces() { struct ifaddrs* ifa; @@ -42,4 +42,4 @@ std::vector GetNetworkInterfaces() { return rv; } -} // namespace cs +} // namespace wpi::cs diff --git a/cscore/src/main/native/linux/RunLoopHelpers.cpp b/cscore/src/main/native/linux/RunLoopHelpers.cpp index 4c0c9d6b2e..936312240a 100644 --- a/cscore/src/main/native/linux/RunLoopHelpers.cpp +++ b/cscore/src/main/native/linux/RunLoopHelpers.cpp @@ -5,22 +5,22 @@ #include "wpi/cs/cscore_runloop.hpp" #include "wpi/util/Synchronization.h" -static wpi::Event& GetInstance() { - static wpi::Event event; +static wpi::util::Event& GetInstance() { + static wpi::util::Event event; return event; } -namespace cs { +namespace wpi::cs { void RunMainRunLoop() { - wpi::Event& event = GetInstance(); - wpi::WaitForObject(event.GetHandle()); + wpi::util::Event& event = GetInstance(); + wpi::util::WaitForObject(event.GetHandle()); } int RunMainRunLoopTimeout(double timeout) { - wpi::Event& event = GetInstance(); + wpi::util::Event& event = GetInstance(); bool timedOut = false; - bool signaled = wpi::WaitForObject(event.GetHandle(), timeout, &timedOut); + bool signaled = wpi::util::WaitForObject(event.GetHandle(), timeout, &timedOut); if (timedOut) { return 3; } @@ -31,8 +31,8 @@ int RunMainRunLoopTimeout(double timeout) { } void StopMainRunLoop() { - wpi::Event& event = GetInstance(); + wpi::util::Event& event = GetInstance(); event.Set(); } -} // namespace cs +} // namespace wpi::cs diff --git a/cscore/src/main/native/linux/UsbCameraBuffer.hpp b/cscore/src/main/native/linux/UsbCameraBuffer.hpp index 4fd13d1d90..c2aa829325 100644 --- a/cscore/src/main/native/linux/UsbCameraBuffer.hpp +++ b/cscore/src/main/native/linux/UsbCameraBuffer.hpp @@ -9,7 +9,7 @@ #include -namespace cs { +namespace wpi::cs { class UsbCameraBuffer { public: @@ -50,6 +50,6 @@ class UsbCameraBuffer { size_t m_length{0}; }; -} // namespace cs +} // namespace wpi::cs #endif // CSCORE_USBCAMERABUFFER_HPP_ diff --git a/cscore/src/main/native/linux/UsbCameraImpl.cpp b/cscore/src/main/native/linux/UsbCameraImpl.cpp index 4378842819..4e9aa73fa9 100644 --- a/cscore/src/main/native/linux/UsbCameraImpl.cpp +++ b/cscore/src/main/native/linux/UsbCameraImpl.cpp @@ -41,7 +41,7 @@ #include "wpi/util/raw_ostream.hpp" #include "wpi/util/timestamp.h" -using namespace cs; +using namespace wpi::cs; namespace { // Find the length of an array. @@ -120,8 +120,8 @@ static __u32 FromPixelFormat(VideoMode::PixelFormat pixelFormat) { } static bool IsPercentageProperty(std::string_view name) { - if (wpi::starts_with(name, "raw_")) { - name = wpi::substr(name, 4); + if (wpi::util::starts_with(name, "raw_")) { + name = wpi::util::substr(name, 4); } return name == "brightness" || name == "contrast" || name == "saturation" || name == "hue" || name == "sharpness" || name == "gain" || @@ -206,14 +206,14 @@ static bool GetVendorProduct(int dev, int* vendor, int* product) { return false; } std::string_view readStr{readBuf}; - if (auto v = wpi::parse_integer( - wpi::substr(wpi::substr(readStr, readStr.find('v')), 1, 4), 16)) { + if (auto v = wpi::util::parse_integer( + wpi::util::substr(wpi::util::substr(readStr, readStr.find('v')), 1, 4), 16)) { *vendor = v.value(); } else { return false; } - if (auto v = wpi::parse_integer( - wpi::substr(wpi::substr(readStr, readStr.find('p')), 1, 4), 16)) { + if (auto v = wpi::util::parse_integer( + wpi::util::substr(wpi::util::substr(readStr, readStr.find('p')), 1, 4), 16)) { *product = v.value(); } else { return false; @@ -239,7 +239,7 @@ static bool GetDescriptionSysV4L(int dev, std::string* desc) { return false; } - *desc = wpi::rtrim(std::string_view(readBuf, n)); + *desc = wpi::util::rtrim(std::string_view(readBuf, n)); return true; } @@ -261,9 +261,9 @@ static bool GetDescriptionIoctl(const char* cpath, std::string* desc) { // try to convert "UVC Camera (0000:0000)" into a better name std::optional vendor; std::optional product; - if (wpi::starts_with(card, "UVC Camera (") && - (vendor = wpi::parse_integer(wpi::substr(card, 12, 4), 16)) && - (product = wpi::parse_integer(wpi::substr(card, 17, 4), 16))) { + if (wpi::util::starts_with(card, "UVC Camera (") && + (vendor = wpi::util::parse_integer(wpi::util::substr(card, 12, 4), 16)) && + (product = wpi::util::parse_integer(wpi::util::substr(card, 17, 4), 16))) { std::string card2 = GetUsbNameFromId(vendor.value(), product.value()); if (!card2.empty()) { *desc = std::move(card2); @@ -306,10 +306,10 @@ static int GetDeviceNum(const char* cpath) { } std::string fn = path.filename(); - if (!wpi::starts_with(fn, "video")) { + if (!wpi::util::starts_with(fn, "video")) { return -1; } - if (auto dev = wpi::parse_integer(wpi::substr(fn, 5), 10)) { + if (auto dev = wpi::util::parse_integer(wpi::util::substr(fn, 5), 10)) { return dev.value(); } return -1; @@ -334,7 +334,7 @@ static std::string GetDescriptionImpl(const char* cpath) { return std::string{}; } -UsbCameraImpl::UsbCameraImpl(std::string_view name, wpi::Logger& logger, +UsbCameraImpl::UsbCameraImpl(std::string_view name, wpi::util::Logger& logger, Notifier& notifier, Telemetry& telemetry, std::string_view path) : SourceImpl{name, logger, notifier, telemetry}, @@ -391,27 +391,27 @@ void UsbCameraImpl::Start() { void UsbCameraImpl::CameraThreadMain() { // We want to be notified on file creation and deletion events in the device // path. This is used to detect disconnects and reconnects. - std::unique_ptr notify_is; + std::unique_ptr notify_is; int notify_fd = inotify_init(); if (notify_fd >= 0) { // need to make a copy as dirname can modify it - wpi::SmallString<64> pathCopy{m_path}; + wpi::util::SmallString<64> pathCopy{m_path}; pathCopy.push_back('\0'); if (inotify_add_watch(notify_fd, dirname(pathCopy.data()), IN_CREATE | IN_DELETE) < 0) { close(notify_fd); notify_fd = -1; } else { - notify_is = std::make_unique( + notify_is = std::make_unique( notify_fd, true, sizeof(struct inotify_event) + NAME_MAX + 1); } } bool notified = (notify_fd < 0); // treat as always notified if cannot notify // Get the basename for later notify use - wpi::SmallString<64> pathCopy{m_path}; + wpi::util::SmallString<64> pathCopy{m_path}; pathCopy.push_back('\0'); - wpi::SmallString<64> base{basename(pathCopy.data())}; + wpi::util::SmallString<64> base{basename(pathCopy.data())}; // Used to restart streaming on reconnect bool wasStreaming = false; @@ -486,7 +486,7 @@ void UsbCameraImpl::CameraThreadMain() { // Read the event structure notify_is->read(&event, sizeof(event)); // Read the event name - wpi::SmallString<64> raw_name; + wpi::util::SmallString<64> raw_name; raw_name.resize(event.len); notify_is->read(raw_name.data(), event.len); // If the name is what we expect... @@ -555,18 +555,18 @@ void UsbCameraImpl::CameraThreadMain() { good = false; } if (good) { - Frame::Time frameTime{wpi::Now()}; + Frame::Time frameTime{wpi::util::Now()}; WPI_TimestampSource timeSource{WPI_TIMESRC_FRAME_DEQUEUE}; // check the timestamp time auto tsFlags = buf.flags & V4L2_BUF_FLAG_TIMESTAMP_MASK; SDEBUG4("Flags {}", tsFlags); if (tsFlags == V4L2_BUF_FLAG_TIMESTAMP_UNKNOWN) { - SDEBUG4("Got unknown time for frame - default to wpi::Now"); + SDEBUG4("Got unknown time for frame - default to wpi::util::Now"); } else if (tsFlags == V4L2_BUF_FLAG_TIMESTAMP_MONOTONIC) { SDEBUG4("Got valid monotonic time for frame"); // we can't go directly to frametime, since the rest of cscore - // expects us to use wpi::Now, which is in an arbitrary timebase + // expects us to use wpi::util::Now, which is in an arbitrary timebase // (see timestamp.cpp). Best I can do is (approximately) translate // between timebases @@ -595,7 +595,7 @@ void UsbCameraImpl::CameraThreadMain() { // Can't do anything if we can't access the clock, leave default } } else if (tsFlags == V4L2_BUF_FLAG_TIMESTAMP_COPY) { - SDEBUG4("Got valid copy time for frame - default to wpi::Now"); + SDEBUG4("Got valid copy time for frame - default to wpi::util::Now"); } PutFrame(static_cast(m_mode.pixelFormat), @@ -813,7 +813,7 @@ bool UsbCameraImpl::DeviceStreamOff() { } CS_StatusValue UsbCameraImpl::DeviceCmdSetMode( - std::unique_lock& lock, const Message& msg) { + std::unique_lock& lock, const Message& msg) { VideoMode newMode; if (msg.kind == Message::kCmdSetMode) { newMode.pixelFormat = msg.data[0]; @@ -877,7 +877,7 @@ CS_StatusValue UsbCameraImpl::DeviceCmdSetMode( } CS_StatusValue UsbCameraImpl::DeviceCmdSetProperty( - std::unique_lock& lock, const Message& msg) { + std::unique_lock& lock, const Message& msg) { bool setString = (msg.kind == Message::kCmdSetPropertyStr); int property = msg.data[0]; int value = msg.data[1]; @@ -940,7 +940,7 @@ CS_StatusValue UsbCameraImpl::DeviceCmdSetProperty( } CS_StatusValue UsbCameraImpl::DeviceCmdSetPath( - std::unique_lock& lock, const Message& msg) { + std::unique_lock& lock, const Message& msg) { m_path = msg.dataStr; lock.unlock(); // disconnect and reconnect @@ -960,7 +960,7 @@ CS_StatusValue UsbCameraImpl::DeviceCmdSetPath( } CS_StatusValue UsbCameraImpl::DeviceProcessCommand( - std::unique_lock& lock, const Message& msg) { + std::unique_lock& lock, const Message& msg) { if (msg.kind == Message::kCmdSetMode || msg.kind == Message::kCmdSetPixelFormat || msg.kind == Message::kCmdSetResolution || @@ -1453,12 +1453,12 @@ bool UsbCameraImpl::CacheProperties(CS_Status* status) const { } void UsbCameraImpl::SetQuirks() { - wpi::SmallString<128> descbuf; + wpi::util::SmallString<128> descbuf; std::string_view desc = GetDescription(descbuf); - m_lifecam_exposure = wpi::ends_with(desc, "LifeCam HD-3000") || - wpi::ends_with(desc, "LifeCam Cinema (TM)"); - m_ov9281_exposure = wpi::contains(desc, "OV9281"); - m_picamera = wpi::ends_with(desc, "mmal service"); + m_lifecam_exposure = wpi::util::ends_with(desc, "LifeCam HD-3000") || + wpi::util::ends_with(desc, "LifeCam Cinema (TM)"); + m_ov9281_exposure = wpi::util::contains(desc, "OV9281"); + m_picamera = wpi::util::ends_with(desc, "mmal service"); int deviceNum = GetDeviceNum(m_path.c_str()); if (deviceNum >= 0) { @@ -1611,7 +1611,7 @@ std::string UsbCameraImpl::GetPath() const { return m_path; } -namespace cs { +namespace wpi::cs { CS_Source CreateUsbCameraDev(std::string_view name, int dev, CS_Status* status) { @@ -1668,7 +1668,7 @@ UsbCameraInfo GetUsbCameraInfo(CS_Source source, CS_Status* status) { // look through /dev/v4l/by-id and /dev/v4l/by-path for symlinks to the // keypath - wpi::SmallString<128> path; + wpi::util::SmallString<128> path; for (auto symlinkDir : symlinkDirs) { if (DIR* dp = ::opendir(symlinkDir)) { while (struct dirent* ep = ::readdir(dp)) { @@ -1703,13 +1703,13 @@ std::vector EnumerateUsbCameras(CS_Status* status) { if (DIR* dp = ::opendir("/dev")) { while (struct dirent* ep = ::readdir(dp)) { std::string_view fname{ep->d_name}; - if (!wpi::starts_with(fname, "video")) { + if (!wpi::util::starts_with(fname, "video")) { continue; } unsigned int dev = 0; if (auto v = - wpi::parse_integer(wpi::substr(fname, 5), 10)) { + wpi::util::parse_integer(wpi::util::substr(fname, 5), 10)) { dev = v.value(); } else { continue; @@ -1718,7 +1718,7 @@ std::vector EnumerateUsbCameras(CS_Status* status) { UsbCameraInfo info; info.dev = dev; - wpi::SmallString<32> path{"/dev/"}; + wpi::util::SmallString<32> path{"/dev/"}; path += fname; info.path = path.str(); @@ -1747,7 +1747,7 @@ std::vector EnumerateUsbCameras(CS_Status* status) { // look through /dev/v4l/by-id and /dev/v4l/by-path for symlinks to // /dev/videoN - wpi::SmallString<128> path; + wpi::util::SmallString<128> path; for (auto symlinkDir : symlinkDirs) { if (DIR* dp = ::opendir(symlinkDir)) { while (struct dirent* ep = ::readdir(dp)) { @@ -1759,8 +1759,8 @@ std::vector EnumerateUsbCameras(CS_Status* status) { if (target) { std::string fname = fs::path{target}.filename(); std::optional dev; - if (wpi::starts_with(fname, "video") && - (dev = wpi::parse_integer(wpi::substr(fname, 5), + if (wpi::util::starts_with(fname, "video") && + (dev = wpi::util::parse_integer(wpi::util::substr(fname, 5), 10)) && dev.value() < retval.size()) { retval[dev.value()].otherPaths.emplace_back(path.str()); @@ -1782,4 +1782,4 @@ std::vector EnumerateUsbCameras(CS_Status* status) { return retval; } -} // namespace cs +} // namespace wpi::cs diff --git a/cscore/src/main/native/linux/UsbCameraImpl.hpp b/cscore/src/main/native/linux/UsbCameraImpl.hpp index 27da2b8280..4680732416 100644 --- a/cscore/src/main/native/linux/UsbCameraImpl.hpp +++ b/cscore/src/main/native/linux/UsbCameraImpl.hpp @@ -24,14 +24,14 @@ #include "wpi/util/raw_istream.hpp" #include "wpi/util/raw_ostream.hpp" -namespace cs { +namespace wpi::cs { class Notifier; class Telemetry; class UsbCameraImpl : public SourceImpl { public: - UsbCameraImpl(std::string_view name, wpi::Logger& logger, Notifier& notifier, + UsbCameraImpl(std::string_view name, wpi::util::Logger& logger, Notifier& notifier, Telemetry& telemetry, std::string_view path); ~UsbCameraImpl() override; @@ -123,13 +123,13 @@ class UsbCameraImpl : public SourceImpl { void DeviceCacheVideoModes(); // Command helper functions - CS_StatusValue DeviceProcessCommand(std::unique_lock& lock, + CS_StatusValue DeviceProcessCommand(std::unique_lock& lock, const Message& msg); - CS_StatusValue DeviceCmdSetMode(std::unique_lock& lock, + CS_StatusValue DeviceCmdSetMode(std::unique_lock& lock, const Message& msg); - CS_StatusValue DeviceCmdSetProperty(std::unique_lock& lock, + CS_StatusValue DeviceCmdSetProperty(std::unique_lock& lock, const Message& msg); - CS_StatusValue DeviceCmdSetPath(std::unique_lock& lock, + CS_StatusValue DeviceCmdSetPath(std::unique_lock& lock, const Message& msg); // Property helper functions @@ -170,12 +170,12 @@ class UsbCameraImpl : public SourceImpl { // Message queues mutable std::vector m_commands; mutable std::vector> m_responses; - mutable wpi::condition_variable m_responseCv; + mutable wpi::util::condition_variable m_responseCv; // Path std::string m_path; }; -} // namespace cs +} // namespace wpi::cs #endif // CSCORE_USBCAMERAIMPL_HPP_ diff --git a/cscore/src/main/native/linux/UsbCameraListener.cpp b/cscore/src/main/native/linux/UsbCameraListener.cpp index 55dc9836dd..5d5d83a510 100644 --- a/cscore/src/main/native/linux/UsbCameraListener.cpp +++ b/cscore/src/main/native/linux/UsbCameraListener.cpp @@ -13,7 +13,7 @@ #include "Notifier.hpp" #include "wpi/util/StringExtras.hpp" -using namespace cs; +using namespace wpi::cs; class UsbCameraListener::Impl { public: @@ -21,28 +21,28 @@ class UsbCameraListener::Impl { Notifier& m_notifier; - std::unique_ptr m_runner; + std::unique_ptr m_runner; }; -UsbCameraListener::UsbCameraListener(wpi::Logger& logger, Notifier& notifier) +UsbCameraListener::UsbCameraListener(wpi::util::Logger& logger, Notifier& notifier) : m_impl(std::make_unique(notifier)) {} UsbCameraListener::~UsbCameraListener() = default; void UsbCameraListener::Start() { if (!m_impl->m_runner) { - m_impl->m_runner = std::make_unique(); - m_impl->m_runner->ExecAsync([impl = m_impl.get()](wpi::uv::Loop& loop) { - auto refreshTimer = wpi::uv::Timer::Create(loop); + m_impl->m_runner = std::make_unique(); + m_impl->m_runner->ExecAsync([impl = m_impl.get()](wpi::net::uv::Loop& loop) { + auto refreshTimer = wpi::net::uv::Timer::Create(loop); refreshTimer->timeout.connect([notifier = &impl->m_notifier] { notifier->NotifyUsbCamerasChanged(); }); refreshTimer->Unreference(); - auto devEvents = wpi::uv::FsEvent::Create(loop); + auto devEvents = wpi::net::uv::FsEvent::Create(loop); devEvents->fsEvent.connect([refreshTimer](const char* fn, int flags) { - if (wpi::starts_with(fn, "video")) { - refreshTimer->Start(wpi::uv::Timer::Time(200)); + if (wpi::util::starts_with(fn, "video")) { + refreshTimer->Start(wpi::net::uv::Timer::Time(200)); } }); devEvents->Start("/dev"); diff --git a/cscore/src/main/native/linux/UsbCameraProperty.cpp b/cscore/src/main/native/linux/UsbCameraProperty.cpp index bec5dd770d..9d02f8cbde 100644 --- a/cscore/src/main/native/linux/UsbCameraProperty.cpp +++ b/cscore/src/main/native/linux/UsbCameraProperty.cpp @@ -14,7 +14,7 @@ #include "wpi/util/SmallString.hpp" #include "wpi/util/StringExtras.hpp" -using namespace cs; +using namespace wpi::cs; static int GetIntCtrlIoctl(int fd, unsigned id, int type, int64_t* value) { unsigned ctrl_class = V4L2_CTRL_ID2CLASS(id); @@ -98,7 +98,7 @@ static int GetStringCtrlIoctl(int fd, int id, int maximum, std::string* value) { static int SetStringCtrlIoctl(int fd, int id, int maximum, std::string_view value) { - wpi::SmallString<64> str{wpi::substr(value, 0, maximum)}; + wpi::util::SmallString<64> str{wpi::util::substr(value, 0, maximum)}; struct v4l2_ext_control ctrl; struct v4l2_ext_controls ctrls; @@ -116,7 +116,7 @@ static int SetStringCtrlIoctl(int fd, int id, int maximum, // Removes non-alphanumeric characters and replaces spaces with underscores. // e.g. "Zoom, Absolute" -> "zoom_absolute", "Pan (Absolute)" -> "pan_absolute" static std::string_view NormalizeName(std::string_view name, - wpi::SmallVectorImpl& buf) { + wpi::util::SmallVectorImpl& buf) { bool newWord = false; for (auto ch : name) { if (std::isalnum(ch)) { @@ -170,7 +170,7 @@ UsbCameraProperty::UsbCameraProperty(const struct v4l2_query_ext_ctrl& ctrl) while (len < sizeof(ctrl.name) && ctrl.name[len] != '\0') { ++len; } - wpi::SmallString<64> name_buf; + wpi::util::SmallString<64> name_buf; name = NormalizeName({ctrl.name, len}, name_buf); } #endif @@ -209,7 +209,7 @@ UsbCameraProperty::UsbCameraProperty(const struct v4l2_queryctrl& ctrl) while (len < sizeof(ctrl.name) && ctrl.name[len] != '\0') { ++len; } - wpi::SmallString<64> name_buf; + wpi::util::SmallString<64> name_buf; name = NormalizeName({reinterpret_cast(ctrl.name), len}, name_buf); } @@ -267,7 +267,7 @@ std::unique_ptr UsbCameraProperty::DeviceQuery(int fd, return prop; } -bool UsbCameraProperty::DeviceGet(std::unique_lock& lock, int fd) { +bool UsbCameraProperty::DeviceGet(std::unique_lock& lock, int fd) { if (fd < 0) { return true; } @@ -306,14 +306,14 @@ bool UsbCameraProperty::DeviceGet(std::unique_lock& lock, int fd) { return rv >= 0; } -bool UsbCameraProperty::DeviceSet(std::unique_lock& lock, +bool UsbCameraProperty::DeviceSet(std::unique_lock& lock, int fd) const { // Make a copy of the string as we're about to release the lock - wpi::SmallString<128> valueStrCopy{valueStr}; + wpi::util::SmallString<128> valueStrCopy{valueStr}; return DeviceSet(lock, fd, value, valueStrCopy.str()); } -bool UsbCameraProperty::DeviceSet(std::unique_lock& lock, int fd, +bool UsbCameraProperty::DeviceSet(std::unique_lock& lock, int fd, int newValue, std::string_view newValueStr) const { if (!device || fd < 0) { diff --git a/cscore/src/main/native/linux/UsbCameraProperty.hpp b/cscore/src/main/native/linux/UsbCameraProperty.hpp index 712b5a2b2f..bb880d8da5 100644 --- a/cscore/src/main/native/linux/UsbCameraProperty.hpp +++ b/cscore/src/main/native/linux/UsbCameraProperty.hpp @@ -13,7 +13,7 @@ #include "PropertyImpl.hpp" #include "wpi/util/mutex.hpp" -namespace cs { +namespace wpi::cs { // Property data class UsbCameraProperty : public PropertyImpl { @@ -52,9 +52,9 @@ class UsbCameraProperty : public PropertyImpl { static std::unique_ptr DeviceQuery(int fd, __u32* id); - bool DeviceGet(std::unique_lock& lock, int fd); - bool DeviceSet(std::unique_lock& lock, int fd) const; - bool DeviceSet(std::unique_lock& lock, int fd, int newValue, + bool DeviceGet(std::unique_lock& lock, int fd); + bool DeviceSet(std::unique_lock& lock, int fd) const; + bool DeviceSet(std::unique_lock& lock, int fd, int newValue, std::string_view newValueStr) const; // If this is a device (rather than software) property @@ -73,6 +73,6 @@ class UsbCameraProperty : public PropertyImpl { bool intMenu{false}; }; -} // namespace cs +} // namespace wpi::cs #endif // CSCORE_USBCAMERAPROPERTY_HPP_ diff --git a/cscore/src/main/native/linux/UsbUtil.cpp b/cscore/src/main/native/linux/UsbUtil.cpp index 1c40d8c374..a0d09e99ff 100644 --- a/cscore/src/main/native/linux/UsbUtil.cpp +++ b/cscore/src/main/native/linux/UsbUtil.cpp @@ -19,7 +19,7 @@ #include "wpi/util/raw_istream.hpp" #include "wpi/util/raw_ostream.hpp" -namespace cs { +namespace wpi::cs { static std::string GetUsbNameFromFile(int vendor, int product) { int fd = open("/var/lib/usbutils/usb.ids", O_RDONLY); @@ -27,15 +27,15 @@ static std::string GetUsbNameFromFile(int vendor, int product) { return {}; } - wpi::SmallString<128> buf; - wpi::raw_fd_istream is{fd, true}; + wpi::util::SmallString<128> buf; + wpi::util::raw_fd_istream is{fd, true}; // build vendor and product 4-char hex strings auto vendorStr = fmt::format("{:04x}", vendor); auto productStr = fmt::format("{:04x}", product); // scan file - wpi::SmallString<128> lineBuf; + wpi::util::SmallString<128> lineBuf; bool foundVendor = false; for (;;) { auto line = is.getline(lineBuf, 4096); @@ -48,9 +48,9 @@ static std::string GetUsbNameFromFile(int vendor, int product) { } // look for vendor at start of line - if (wpi::starts_with(line, vendorStr)) { + if (wpi::util::starts_with(line, vendorStr)) { foundVendor = true; - buf += wpi::trim(wpi::substr(line, 5)); + buf += wpi::util::trim(wpi::util::substr(line, 5)); buf += ' '; continue; } @@ -63,8 +63,8 @@ static std::string GetUsbNameFromFile(int vendor, int product) { } // look for product - if (wpi::starts_with(wpi::substr(line, 1), productStr)) { - buf += wpi::trim(wpi::substr(line, 6)); + if (wpi::util::starts_with(wpi::util::substr(line, 1), productStr)) { + buf += wpi::util::trim(wpi::util::substr(line, 6)); return std::string{buf}; } } @@ -161,4 +161,4 @@ int CheckedIoctl(int fd, unsigned long req, void* data, // NOLINT(runtime/int) return retval; } -} // namespace cs +} // namespace wpi::cs diff --git a/cscore/src/main/native/linux/UsbUtil.hpp b/cscore/src/main/native/linux/UsbUtil.hpp index 9963821e63..207e95f1ea 100644 --- a/cscore/src/main/native/linux/UsbUtil.hpp +++ b/cscore/src/main/native/linux/UsbUtil.hpp @@ -7,7 +7,7 @@ #include -namespace cs { +namespace wpi::cs { std::string GetUsbNameFromId(int vendor, int product); @@ -19,6 +19,6 @@ int CheckedIoctl(int fd, unsigned long req, void* data, // NOLINT(runtime/int) #define TryIoctl(fd, req, data) \ CheckedIoctl(fd, req, data, #req, __FILE__, __LINE__, true) -} // namespace cs +} // namespace wpi::cs #endif // CSCORE_USBUTIL_HPP_ diff --git a/cscore/src/main/native/objcpp/RunLoopHelpers.mm b/cscore/src/main/native/objcpp/RunLoopHelpers.mm index 86b6048311..f2ddefcbb5 100644 --- a/cscore/src/main/native/objcpp/RunLoopHelpers.mm +++ b/cscore/src/main/native/objcpp/RunLoopHelpers.mm @@ -7,7 +7,7 @@ #include #import -namespace cs { +namespace wpi::cs { void RunMainRunLoop() { if (CFRunLoopGetMain() != CFRunLoopGetCurrent()) { diff --git a/cscore/src/main/native/objcpp/UsbCameraDelegate.hpp b/cscore/src/main/native/objcpp/UsbCameraDelegate.hpp index 61a0473767..9a5b37a5cd 100644 --- a/cscore/src/main/native/objcpp/UsbCameraDelegate.hpp +++ b/cscore/src/main/native/objcpp/UsbCameraDelegate.hpp @@ -7,14 +7,14 @@ #import #include -namespace cs { +namespace wpi::cs { class UsbCameraImpl; } @interface UsbCameraDelegate : NSObject -@property(nonatomic) std::weak_ptr cppImpl; +@property(nonatomic) std::weak_ptr cppImpl; - (void)captureOutput:(AVCaptureOutput*)captureOutput didOutputSampleBuffer:(CMSampleBufferRef)sampleBuffer diff --git a/cscore/src/main/native/objcpp/UsbCameraDelegate.mm b/cscore/src/main/native/objcpp/UsbCameraDelegate.mm index 22a603dd79..136698b6f5 100644 --- a/cscore/src/main/native/objcpp/UsbCameraDelegate.mm +++ b/cscore/src/main/native/objcpp/UsbCameraDelegate.mm @@ -21,7 +21,7 @@ (void)sampleBuffer; (void)connection; - auto currentTime = wpi::Now(); + auto currentTime = wpi::util::Now(); auto sharedThis = self.cppImpl.lock(); if (!sharedThis) { @@ -51,7 +51,7 @@ return; } - std::unique_ptr image = cs::CreateImageFromBGRA( + std::unique_ptr image = wpi::cs::CreateImageFromBGRA( sharedThis.get(), width, height, rowBytes, reinterpret_cast(baseaddress)); CVPixelBufferUnlockBaseAddress(imageBuffer, 0); diff --git a/cscore/src/main/native/objcpp/UsbCameraImpl.hpp b/cscore/src/main/native/objcpp/UsbCameraImpl.hpp index 3d35fdb1ab..4fe886d2df 100644 --- a/cscore/src/main/native/objcpp/UsbCameraImpl.hpp +++ b/cscore/src/main/native/objcpp/UsbCameraImpl.hpp @@ -16,7 +16,7 @@ #include "SourceImpl.hpp" -namespace cs { +namespace wpi::cs { struct CameraFPSRange { int min; int max; @@ -32,9 +32,9 @@ struct CameraModeStore { class UsbCameraImpl : public SourceImpl { public: - UsbCameraImpl(std::string_view name, wpi::Logger& logger, Notifier& notifier, + UsbCameraImpl(std::string_view name, wpi::util::Logger& logger, Notifier& notifier, Telemetry& telemetry, std::string_view path); - UsbCameraImpl(std::string_view name, wpi::Logger& logger, Notifier& notifier, + UsbCameraImpl(std::string_view name, wpi::util::Logger& logger, Notifier& notifier, Telemetry& telemetry, int deviceId); ~UsbCameraImpl() override; @@ -64,7 +64,7 @@ class UsbCameraImpl : public SourceImpl { void NumSinksChanged() override; void NumSinksEnabledChanged() override; - cs::Notifier& objcGetNotifier() { return m_notifier; } + wpi::cs::Notifier& objcGetNotifier() { return m_notifier; } void objcSwapVideoModes(std::vector& modes) { std::scoped_lock lock(m_mutex); @@ -86,7 +86,7 @@ class UsbCameraImpl : public SourceImpl { return m_platformModes; } - wpi::Logger& objcGetLogger() { return m_logger; } + wpi::util::Logger& objcGetLogger() { return m_logger; } UsbCameraImplObjc* cppGetObjc() { return m_objc; } @@ -106,18 +106,18 @@ class UsbCameraImpl : public SourceImpl { UpdatePropertyValue(property, setString, value, valueStr); } - wpi::mutex& GetMutex() { return m_mutex; } + wpi::util::mutex& GetMutex() { return m_mutex; } // Property cache accessors - wpi::StringMap& GetPropertyCache() { return m_propertyCache; } - wpi::StringMap& GetPropertyAutoCache() { return m_propertyAutoCache; } + wpi::util::StringMap& GetPropertyCache() { return m_propertyCache; } + wpi::util::StringMap& GetPropertyAutoCache() { return m_propertyAutoCache; } private: UsbCameraImplObjc* m_objc; std::vector m_platformModes; // Property caches - wpi::StringMap m_propertyCache; - wpi::StringMap m_propertyAutoCache; + wpi::util::StringMap m_propertyCache; + wpi::util::StringMap m_propertyAutoCache; }; -} // namespace cs +} // namespace wpi::cs diff --git a/cscore/src/main/native/objcpp/UsbCameraImpl.mm b/cscore/src/main/native/objcpp/UsbCameraImpl.mm index 3b4483d591..95dafa45c7 100644 --- a/cscore/src/main/native/objcpp/UsbCameraImpl.mm +++ b/cscore/src/main/native/objcpp/UsbCameraImpl.mm @@ -20,9 +20,9 @@ #include "wpi/cs/cscore_cpp.hpp" #include "UsbCameraImpl.hpp" -namespace cs { +namespace wpi::cs { -UsbCameraImpl::UsbCameraImpl(std::string_view name, wpi::Logger& logger, +UsbCameraImpl::UsbCameraImpl(std::string_view name, wpi::util::Logger& logger, Notifier& notifier, Telemetry& telemetry, std::string_view path) : SourceImpl{name, logger, notifier, telemetry} { @@ -32,7 +32,7 @@ UsbCameraImpl::UsbCameraImpl(std::string_view name, wpi::Logger& logger, encoding:NSUTF8StringEncoding]; m_objc = objc; } -UsbCameraImpl::UsbCameraImpl(std::string_view name, wpi::Logger& logger, +UsbCameraImpl::UsbCameraImpl(std::string_view name, wpi::util::Logger& logger, Notifier& notifier, Telemetry& telemetry, int deviceId) : SourceImpl{name, logger, notifier, telemetry} { @@ -108,7 +108,7 @@ void UsbCameraImpl::NumSinksEnabledChanged() { CS_Source CreateUsbCameraDev(std::string_view name, int dev, CS_Status* status) { - std::vector devices = cs::EnumerateUsbCameras(status); + std::vector devices = wpi::cs::EnumerateUsbCameras(status); if (static_cast(devices.size()) > dev) { return CreateUsbCameraPath(name, devices[dev].path, status); } @@ -203,4 +203,4 @@ UsbCameraInfo GetUsbCameraInfo(CS_Source source, CS_Status* status) { return info; } -} // namespace cs +} // namespace wpi::cs diff --git a/cscore/src/main/native/objcpp/UsbCameraImplObjc.hpp b/cscore/src/main/native/objcpp/UsbCameraImplObjc.hpp index fc54f89ee3..f80eadfca3 100644 --- a/cscore/src/main/native/objcpp/UsbCameraImplObjc.hpp +++ b/cscore/src/main/native/objcpp/UsbCameraImplObjc.hpp @@ -38,7 +38,7 @@ #define kPropertyAutoWhiteBalance "white_balance_automatic" #define kPropertyAutoFocus "focus_auto" -namespace cs { +namespace wpi::cs { class UsbCameraImpl; } @@ -46,7 +46,7 @@ class UsbCameraImpl; @property(nonatomic) AVCaptureDeviceFormat* currentFormat; @property(nonatomic) int currentFPS; -@property(nonatomic) std::weak_ptr cppImpl; +@property(nonatomic) std::weak_ptr cppImpl; @property(nonatomic) dispatch_queue_t sessionQueue; @property(nonatomic) NSString* path; @property(nonatomic) int deviceId; @@ -82,8 +82,8 @@ class UsbCameraImpl; - (void)setExposureHoldCurrent:(CS_Status*)status; - (void)setExposureManual:(int)value status:(CS_Status*)status; -- (bool)setVideoMode:(const cs::VideoMode&)mode status:(CS_Status*)status; -- (bool)setPixelFormat:(cs::VideoMode::PixelFormat)pixelFormat +- (bool)setVideoMode:(const wpi::cs::VideoMode&)mode status:(CS_Status*)status; +- (bool)setPixelFormat:(wpi::cs::VideoMode::PixelFormat)pixelFormat status:(CS_Status*)status; - (bool)setResolutionWidth:(int)width withHeight:(int)height diff --git a/cscore/src/main/native/objcpp/UsbCameraImplObjc.mm b/cscore/src/main/native/objcpp/UsbCameraImplObjc.mm index 2a4d596737..d9f2861b66 100644 --- a/cscore/src/main/native/objcpp/UsbCameraImplObjc.mm +++ b/cscore/src/main/native/objcpp/UsbCameraImplObjc.mm @@ -20,11 +20,11 @@ inline void NamedLog(UsbCameraImplObjc* objc, unsigned int level, return; } - wpi::Logger& logger = sharedThis->objcGetLogger(); + wpi::util::Logger& logger = sharedThis->objcGetLogger(); std::string_view name = sharedThis->GetName(); if (logger.HasLogger() && level >= logger.min_level()) { - cs::NamedLogV(logger, level, file, line, name, format, + wpi::cs::NamedLogV(logger, level, file, line, name, format, fmt::make_format_args(args...)); } } @@ -34,11 +34,11 @@ inline void NamedLog(UsbCameraImplObjc* objc, unsigned int level, format __VA_OPT__(, ) __VA_ARGS__) #define OBJCERROR(format, ...) \ - OBJCLOG(::wpi::WPI_LOG_ERROR, format __VA_OPT__(, ) __VA_ARGS__) + OBJCLOG(::wpi::util::WPI_LOG_ERROR, format __VA_OPT__(, ) __VA_ARGS__) #define OBJCWARNING(format, ...) \ - OBJCLOG(::wpi::WPI_LOG_WARNING, format __VA_OPT__(, ) __VA_ARGS__) + OBJCLOG(::wpi::util::WPI_LOG_WARNING, format __VA_OPT__(, ) __VA_ARGS__) #define OBJCINFO(format, ...) \ - OBJCLOG(::wpi::WPI_LOG_INFO, format __VA_OPT__(, ) __VA_ARGS__) + OBJCLOG(::wpi::util::WPI_LOG_INFO, format __VA_OPT__(, ) __VA_ARGS__) #ifdef NDEBUG #define OBJCDEBUG(format, ...) \ @@ -58,18 +58,18 @@ inline void NamedLog(UsbCameraImplObjc* objc, unsigned int level, } while (0) #else #define OBJCDEBUG(format, ...) \ - OBJCLOG(::wpi::WPI_LOG_DEBUG, format __VA_OPT__(, ) __VA_ARGS__) + OBJCLOG(::wpi::util::WPI_LOG_DEBUG, format __VA_OPT__(, ) __VA_ARGS__) #define OBJCDEBUG1(format, ...) \ - OBJCLOG(::wpi::WPI_LOG_DEBUG1, format __VA_OPT__(, ) __VA_ARGS__) + OBJCLOG(::wpi::util::WPI_LOG_DEBUG1, format __VA_OPT__(, ) __VA_ARGS__) #define OBJCDEBUG2(format, ...) \ - OBJCLOG(::wpi::WPI_LOG_DEBUG2, format __VA_OPT__(, ) __VA_ARGS__) + OBJCLOG(::wpi::util::WPI_LOG_DEBUG2, format __VA_OPT__(, ) __VA_ARGS__) #define OBJCDEBUG3(format, ...) \ - OBJCLOG(::wpi::WPI_LOG_DEBUG3, format __VA_OPT__(, ) __VA_ARGS__) + OBJCLOG(::wpi::util::WPI_LOG_DEBUG3, format __VA_OPT__(, ) __VA_ARGS__) #define OBJCDEBUG4(format, ...) \ - OBJCLOG(::wpi::WPI_LOG_DEBUG4, format __VA_OPT__(, ) __VA_ARGS__) + OBJCLOG(::wpi::util::WPI_LOG_DEBUG4, format __VA_OPT__(, ) __VA_ARGS__) #endif -using namespace cs; +using namespace wpi::cs; @implementation UsbCameraImplObjc @@ -169,7 +169,7 @@ using namespace cs; } // Get the property name from the property index - wpi::SmallString<128> nameBuf; + wpi::util::SmallString<128> nameBuf; std::string_view propName = sharedThis->GetPropertyName(property, nameBuf, status); if (*status != 0) { OBJCERROR("Failed to get property name for index {}", property); @@ -402,7 +402,7 @@ using namespace cs; sharedThis->SetProperty(prop, value, status); } -- (bool)setVideoMode:(const cs::VideoMode&)mode status:(CS_Status*)status { +- (bool)setVideoMode:(const wpi::cs::VideoMode&)mode status:(CS_Status*)status { dispatch_async_and_wait(self.sessionQueue, ^{ auto sharedThis = self.cppImpl.lock(); if (!sharedThis) { @@ -414,7 +414,7 @@ using namespace cs; }); return true; } -- (bool)setPixelFormat:(cs::VideoMode::PixelFormat)pixelFormat +- (bool)setPixelFormat:(wpi::cs::VideoMode::PixelFormat)pixelFormat status:(CS_Status*)status { dispatch_async_and_wait(self.sessionQueue, ^{ auto sharedThis = self.cppImpl.lock(); @@ -449,7 +449,7 @@ using namespace cs; return true; } -- (void)internalSetMode:(const cs::VideoMode&)newMode +- (void)internalSetMode:(const wpi::cs::VideoMode&)newMode status:(CS_Status*)status { auto sharedThis = self.cppImpl.lock(); if (!sharedThis) { @@ -693,13 +693,13 @@ using namespace cs; propertyAutoCache[nameStr] = propID; } -static cs::VideoMode::PixelFormat FourCCToPixelFormat(FourCharCode fourcc) { +static wpi::cs::VideoMode::PixelFormat FourCCToPixelFormat(FourCharCode fourcc) { switch (fourcc) { case kCVPixelFormatType_422YpCbCr8_yuvs: case kCVPixelFormatType_422YpCbCr8FullRange: - return cs::VideoMode::PixelFormat::kYUYV; + return wpi::cs::VideoMode::PixelFormat::kYUYV; default: - return cs::VideoMode::PixelFormat::kBGR; + return wpi::cs::VideoMode::PixelFormat::kBGR; } } @@ -761,7 +761,7 @@ static cs::VideoMode::PixelFormat FourCCToPixelFormat(FourCharCode fourcc) { CS_SOURCE_VIDEOMODES_UPDATED); } -- (AVCaptureDeviceFormat*)deviceCheckModeValid:(const cs::VideoMode*)toCheck +- (AVCaptureDeviceFormat*)deviceCheckModeValid:(const wpi::cs::VideoMode*)toCheck withFps:(int*)fps { auto sharedThis = self.cppImpl.lock(); if (!sharedThis) { @@ -995,7 +995,7 @@ static cs::VideoMode::PixelFormat FourCCToPixelFormat(FourCharCode fourcc) { OBJCINFO("Starting for device id {}", self.deviceId); // Enumerate Devices CS_Status status = 0; - auto cameras = cs::EnumerateUsbCameras(&status); + auto cameras = wpi::cs::EnumerateUsbCameras(&status); if (static_cast(cameras.size()) <= self.deviceId) { return false; } diff --git a/cscore/src/main/native/objcpp/UsbCameraListener.mm b/cscore/src/main/native/objcpp/UsbCameraListener.mm index b7c66341a9..b1e7e919e4 100644 --- a/cscore/src/main/native/objcpp/UsbCameraListener.mm +++ b/cscore/src/main/native/objcpp/UsbCameraListener.mm @@ -8,7 +8,7 @@ #pragma GCC diagnostic ignored "-Wunused-parameter" #include "Notifier.hpp" -using namespace cs; +using namespace wpi::cs; @interface UsbCameraListenerImpl : NSObject @property(nonatomic) Notifier* notifier; @@ -99,7 +99,7 @@ class UsbCameraListener::Impl { } }; -UsbCameraListener::UsbCameraListener(wpi::Logger&, Notifier& notifier) +UsbCameraListener::UsbCameraListener(wpi::util::Logger&, Notifier& notifier) : m_impl{std::make_unique(notifier)} {} UsbCameraListener::~UsbCameraListener() { diff --git a/cscore/src/main/native/objcpp/UvcControlImpl.hpp b/cscore/src/main/native/objcpp/UvcControlImpl.hpp index a3c2fb19cc..810e2a0ea1 100644 --- a/cscore/src/main/native/objcpp/UvcControlImpl.hpp +++ b/cscore/src/main/native/objcpp/UvcControlImpl.hpp @@ -82,7 +82,7 @@ #define CAPPROPID_POWERLINEFREQ 13 #define CAPPROPID_LAST 14 -namespace cs { +namespace wpi::cs { class UsbCameraImpl; } @@ -90,7 +90,7 @@ class UsbCameraImpl; @property(nonatomic) IOUSBInterfaceInterface190** controlInterface; @property(nonatomic) uint32_t processingUnitID; -@property(nonatomic) std::weak_ptr cppImpl; +@property(nonatomic) std::weak_ptr cppImpl; // Create from AVCaptureDevice + (instancetype)createFromAVCaptureDevice:(AVCaptureDevice*)device status:(CS_Status*)status; diff --git a/cscore/src/main/native/objcpp/UvcControlImpl.mm b/cscore/src/main/native/objcpp/UvcControlImpl.mm index 087164f64a..88699b0a83 100644 --- a/cscore/src/main/native/objcpp/UvcControlImpl.mm +++ b/cscore/src/main/native/objcpp/UvcControlImpl.mm @@ -40,11 +40,11 @@ inline void NamedLog(UvcControlImpl* objc, unsigned int level, return; } - wpi::Logger& logger = sharedThis->objcGetLogger(); + wpi::util::Logger& logger = sharedThis->objcGetLogger(); std::string_view name = sharedThis->GetName(); if (logger.HasLogger() && level >= logger.min_level()) { - cs::NamedLogV(logger, level, file, line, name, format, + wpi::cs::NamedLogV(logger, level, file, line, name, format, fmt::make_format_args(args...)); } } @@ -54,11 +54,11 @@ inline void NamedLog(UvcControlImpl* objc, unsigned int level, format __VA_OPT__(, ) __VA_ARGS__) #define UVCERROR(format, ...) \ - UVCLOG(::wpi::WPI_LOG_ERROR, format __VA_OPT__(, ) __VA_ARGS__) + UVCLOG(::wpi::util::WPI_LOG_ERROR, format __VA_OPT__(, ) __VA_ARGS__) #define UVCWARNING(format, ...) \ - UVCLOG(::wpi::WPI_LOG_WARNING, format __VA_OPT__(, ) __VA_ARGS__) + UVCLOG(::wpi::util::WPI_LOG_WARNING, format __VA_OPT__(, ) __VA_ARGS__) #define UVCINFO(format, ...) \ - UVCLOG(::wpi::WPI_LOG_INFO, format __VA_OPT__(, ) __VA_ARGS__) + UVCLOG(::wpi::util::WPI_LOG_INFO, format __VA_OPT__(, ) __VA_ARGS__) #ifdef NDEBUG #define UVCDEBUG(format, ...) \ @@ -78,15 +78,15 @@ inline void NamedLog(UvcControlImpl* objc, unsigned int level, } while (0) #else #define UVCDEBUG(format, ...) \ - UVCLOG(::wpi::WPI_LOG_DEBUG, format __VA_OPT__(, ) __VA_ARGS__) + UVCLOG(::wpi::util::WPI_LOG_DEBUG, format __VA_OPT__(, ) __VA_ARGS__) #define UVCDEBUG1(format, ...) \ - UVCLOG(::wpi::WPI_LOG_DEBUG1, format __VA_OPT__(, ) __VA_ARGS__) + UVCLOG(::wpi::util::WPI_LOG_DEBUG1, format __VA_OPT__(, ) __VA_ARGS__) #define UVCDEBUG2(format, ...) \ - UVCLOG(::wpi::WPI_LOG_DEBUG2, format __VA_OPT__(, ) __VA_ARGS__) + UVCLOG(::wpi::util::WPI_LOG_DEBUG2, format __VA_OPT__(, ) __VA_ARGS__) #define UVCDEBUG3(format, ...) \ - UVCLOG(::wpi::WPI_LOG_DEBUG3, format __VA_OPT__(, ) __VA_ARGS__) + UVCLOG(::wpi::util::WPI_LOG_DEBUG3, format __VA_OPT__(, ) __VA_ARGS__) #define UVCDEBUG4(format, ...) \ - UVCLOG(::wpi::WPI_LOG_DEBUG4, format __VA_OPT__(, ) __VA_ARGS__) + UVCLOG(::wpi::util::WPI_LOG_DEBUG4, format __VA_OPT__(, ) __VA_ARGS__) #endif // USB descriptor for UVC processing unit diff --git a/cscore/src/main/native/osx/NetworkListener.cpp b/cscore/src/main/native/osx/NetworkListener.cpp index ee7581ef21..9829e4fa0c 100644 --- a/cscore/src/main/native/osx/NetworkListener.cpp +++ b/cscore/src/main/native/osx/NetworkListener.cpp @@ -4,11 +4,11 @@ #include "NetworkListener.hpp" -using namespace cs; +using namespace wpi::cs; class NetworkListener::Impl {}; -NetworkListener::NetworkListener(wpi::Logger& logger, Notifier& notifier) {} +NetworkListener::NetworkListener(wpi::util::Logger& logger, Notifier& notifier) {} NetworkListener::~NetworkListener() = default; diff --git a/cscore/src/main/native/osx/NetworkUtil.cpp b/cscore/src/main/native/osx/NetworkUtil.cpp index 4b12034827..24193f7929 100644 --- a/cscore/src/main/native/osx/NetworkUtil.cpp +++ b/cscore/src/main/native/osx/NetworkUtil.cpp @@ -7,10 +7,10 @@ #include "wpi/cs/cscore_cpp.hpp" -namespace cs { +namespace wpi::cs { std::vector GetNetworkInterfaces() { return std::vector{}; // TODO } -} // namespace cs +} // namespace wpi::cs diff --git a/cscore/src/main/native/windows/COMCreators.cpp b/cscore/src/main/native/windows/COMCreators.cpp index 3d5a99a953..a143e66c8a 100644 --- a/cscore/src/main/native/windows/COMCreators.cpp +++ b/cscore/src/main/native/windows/COMCreators.cpp @@ -31,10 +31,10 @@ #pragma comment(lib, "Mfreadwrite.lib") #pragma comment(lib, "Shlwapi.lib") -namespace cs { +namespace wpi::cs { -SourceReaderCB::SourceReaderCB(std::weak_ptr source, - const cs::VideoMode& mode) +SourceReaderCB::SourceReaderCB(std::weak_ptr source, + const wpi::cs::VideoMode& mode) : m_nRefCount(1), m_source(source), m_mode{mode} {} // IUnknown methods @@ -94,7 +94,7 @@ STDMETHODIMP SourceReaderCB::OnReadSample(HRESULT hrStatus, DWORD dwStreamIndex, // Create a Source Reader COM Smart Object ComPtr CreateSourceReaderCB( - std::weak_ptr source, const cs::VideoMode& mode) { + std::weak_ptr source, const wpi::cs::VideoMode& mode) { SourceReaderCB* ptr = new SourceReaderCB(source, mode); ComPtr sourceReaderCB; sourceReaderCB.Attach(ptr); @@ -157,4 +157,4 @@ ComPtr CreateSourceReader(IMFMediaSource* mediaSource, return sourceReader; } -} // namespace cs +} // namespace wpi::cs diff --git a/cscore/src/main/native/windows/COMCreators.hpp b/cscore/src/main/native/windows/COMCreators.hpp index dcbcbb21cb..782f8fc850 100644 --- a/cscore/src/main/native/windows/COMCreators.hpp +++ b/cscore/src/main/native/windows/COMCreators.hpp @@ -12,7 +12,7 @@ #include "ComPtr.hpp" #include "wpi/cs/cscore_cpp.hpp" -namespace cs { +namespace wpi::cs { class UsbCameraImpl; @@ -20,8 +20,8 @@ class UsbCameraImpl; // COM object, so it needs a to ref count itself. class SourceReaderCB : public IMFSourceReaderCallback { public: - explicit SourceReaderCB(std::weak_ptr source, - const cs::VideoMode& mode); + explicit SourceReaderCB(std::weak_ptr source, + const wpi::cs::VideoMode& mode); void SetVideoMode(const VideoMode& mode) { m_mode = mode; } STDMETHODIMP QueryInterface(REFIID iid, void** ppv); @@ -35,7 +35,7 @@ class SourceReaderCB : public IMFSourceReaderCallback { IMFSample* pSample // Can be NULL ); - void InvalidateCapture() { m_source = std::weak_ptr(); } + void InvalidateCapture() { m_source = std::weak_ptr(); } private: // Destructor is private. Caller should call Release. @@ -43,13 +43,13 @@ class SourceReaderCB : public IMFSourceReaderCallback { void NotifyError(HRESULT hr); ULONG m_nRefCount; - std::weak_ptr m_source; - cs::VideoMode m_mode; + std::weak_ptr m_source; + wpi::cs::VideoMode m_mode; }; ComPtr CreateSourceReaderCB( - std::weak_ptr source, const cs::VideoMode& mode); + std::weak_ptr source, const wpi::cs::VideoMode& mode); ComPtr CreateSourceReader(IMFMediaSource* mediaSource, IMFSourceReaderCallback* callback); ComPtr CreateVideoCaptureDevice(LPCWSTR pszSymbolicLink); -} // namespace cs +} // namespace wpi::cs diff --git a/cscore/src/main/native/windows/ComPtr.hpp b/cscore/src/main/native/windows/ComPtr.hpp index 2d9f241b5d..f67c1095ca 100644 --- a/cscore/src/main/native/windows/ComPtr.hpp +++ b/cscore/src/main/native/windows/ComPtr.hpp @@ -9,7 +9,7 @@ #include -namespace cs { +namespace wpi::cs { template class RemoveAddRefRelease : public Interface { @@ -146,4 +146,4 @@ void swap( left.Swap(right); } -} // namespace cs +} // namespace wpi::cs diff --git a/cscore/src/main/native/windows/NetworkListener.cpp b/cscore/src/main/native/windows/NetworkListener.cpp index d2de28216a..51424830d2 100644 --- a/cscore/src/main/native/windows/NetworkListener.cpp +++ b/cscore/src/main/native/windows/NetworkListener.cpp @@ -22,13 +22,13 @@ #pragma comment(lib, "Iphlpapi.lib") -using namespace cs; +using namespace wpi::cs; class NetworkListener::Impl { public: - Impl(wpi::Logger& logger, Notifier& notifier) + Impl(wpi::util::Logger& logger, Notifier& notifier) : m_logger(logger), m_notifier(notifier) {} - wpi::Logger& m_logger; + wpi::util::Logger& m_logger; Notifier& m_notifier; HANDLE eventHandle = 0; }; @@ -41,7 +41,7 @@ static void WINAPI OnInterfaceChange(PVOID callerContext, notifier->NotifyNetworkInterfacesChanged(); } -NetworkListener::NetworkListener(wpi::Logger& logger, Notifier& notifier) +NetworkListener::NetworkListener(wpi::util::Logger& logger, Notifier& notifier) : m_impl(std::make_unique(logger, notifier)) {} NetworkListener::~NetworkListener() { diff --git a/cscore/src/main/native/windows/NetworkUtil.cpp b/cscore/src/main/native/windows/NetworkUtil.cpp index 3365cf1397..ac7b561cc1 100644 --- a/cscore/src/main/native/windows/NetworkUtil.cpp +++ b/cscore/src/main/native/windows/NetworkUtil.cpp @@ -12,7 +12,7 @@ #pragma comment(lib, "Ws2_32.lib") -namespace cs { +namespace wpi::cs { std::vector GetNetworkInterfaces() { uv_interface_address_t* adrs; @@ -42,4 +42,4 @@ std::vector GetNetworkInterfaces() { return addresses; } -} // namespace cs +} // namespace wpi::cs diff --git a/cscore/src/main/native/windows/RunLoopHelpers.cpp b/cscore/src/main/native/windows/RunLoopHelpers.cpp index 4c0c9d6b2e..936312240a 100644 --- a/cscore/src/main/native/windows/RunLoopHelpers.cpp +++ b/cscore/src/main/native/windows/RunLoopHelpers.cpp @@ -5,22 +5,22 @@ #include "wpi/cs/cscore_runloop.hpp" #include "wpi/util/Synchronization.h" -static wpi::Event& GetInstance() { - static wpi::Event event; +static wpi::util::Event& GetInstance() { + static wpi::util::Event event; return event; } -namespace cs { +namespace wpi::cs { void RunMainRunLoop() { - wpi::Event& event = GetInstance(); - wpi::WaitForObject(event.GetHandle()); + wpi::util::Event& event = GetInstance(); + wpi::util::WaitForObject(event.GetHandle()); } int RunMainRunLoopTimeout(double timeout) { - wpi::Event& event = GetInstance(); + wpi::util::Event& event = GetInstance(); bool timedOut = false; - bool signaled = wpi::WaitForObject(event.GetHandle(), timeout, &timedOut); + bool signaled = wpi::util::WaitForObject(event.GetHandle(), timeout, &timedOut); if (timedOut) { return 3; } @@ -31,8 +31,8 @@ int RunMainRunLoopTimeout(double timeout) { } void StopMainRunLoop() { - wpi::Event& event = GetInstance(); + wpi::util::Event& event = GetInstance(); event.Set(); } -} // namespace cs +} // namespace wpi::cs diff --git a/cscore/src/main/native/windows/UsbCameraImpl.cpp b/cscore/src/main/native/windows/UsbCameraImpl.cpp index 0bee6fb6df..d9d77bfeae 100644 --- a/cscore/src/main/native/windows/UsbCameraImpl.cpp +++ b/cscore/src/main/native/windows/UsbCameraImpl.cpp @@ -63,22 +63,22 @@ static constexpr char const* kPropConnectVerbose = "connect_verbose"; static constexpr unsigned kPropConnectVerboseId = 0; -using namespace cs; +using namespace wpi::cs; -namespace cs { +namespace wpi::cs { -UsbCameraImpl::UsbCameraImpl(std::string_view name, wpi::Logger& logger, +UsbCameraImpl::UsbCameraImpl(std::string_view name, wpi::util::Logger& logger, Notifier& notifier, Telemetry& telemetry, std::string_view path) : SourceImpl{name, logger, notifier, telemetry}, m_path{path} { - wpi::SmallVector wideStorage; - wpi::sys::windows::UTF8ToUTF16(m_path, wideStorage); + wpi::util::SmallVector wideStorage; + wpi::util::sys::windows::UTF8ToUTF16(m_path, wideStorage); m_widePath = std::wstring{wideStorage.data(), wideStorage.size()}; m_deviceId = -1; StartMessagePump(); } -UsbCameraImpl::UsbCameraImpl(std::string_view name, wpi::Logger& logger, +UsbCameraImpl::UsbCameraImpl(std::string_view name, wpi::util::Logger& logger, Notifier& notifier, Telemetry& telemetry, int deviceId) : SourceImpl{name, logger, notifier, telemetry}, m_deviceId(deviceId) { @@ -242,7 +242,7 @@ bool UsbCameraImpl::CheckDeviceChange(WPARAM wParam, DEV_BROADCAST_HDR* pHdr, pDi = reinterpret_cast(pHdr); - if (wpi::equals_lower(m_path, pDi->dbcc_name)) { + if (wpi::util::equals_lower(m_path, pDi->dbcc_name)) { if (wParam == DBT_DEVICEARRIVAL) { *connected = true; return true; @@ -268,8 +268,8 @@ void UsbCameraImpl::DeviceDisconnect() { } static bool IsPercentageProperty(std::string_view name) { - if (wpi::starts_with(name, "raw_")) { - name = wpi::substr(name, 4); + if (wpi::util::starts_with(name, "raw_")) { + name = wpi::util::substr(name, 4); } return name == "Brightness" || name == "Contrast" || name == "Saturation" || name == "Hue" || name == "Sharpness" || name == "Gain" || @@ -282,7 +282,7 @@ void UsbCameraImpl::ProcessFrame(IMFSample* videoSample, return; } - auto currentTime = wpi::Now(); + auto currentTime = wpi::util::Now(); ComPtr buf; @@ -378,7 +378,7 @@ LRESULT UsbCameraImpl::PumpMain(HWND hwnd, UINT uiMsg, WPARAM wParam, // If path is empty, we attempted to connect with a device ID. Enumerate // and check CS_Status status = 0; - auto devices = cs::EnumerateUsbCameras(&status); + auto devices = wpi::cs::EnumerateUsbCameras(&status); if (devices.size() > m_deviceId) { // If has device ID, use the device ID from the event // because of windows bug @@ -386,8 +386,8 @@ LRESULT UsbCameraImpl::PumpMain(HWND hwnd, UINT uiMsg, WPARAM wParam, DEV_BROADCAST_DEVICEINTERFACE_A* pDi = reinterpret_cast(parameter); m_path = pDi->dbcc_name; - wpi::SmallVector wideStorage; - wpi::sys::windows::UTF8ToUTF16(m_path, wideStorage); + wpi::util::SmallVector wideStorage; + wpi::util::sys::windows::UTF8ToUTF16(m_path, wideStorage); m_widePath = std::wstring{wideStorage.data(), wideStorage.size()}; } else { // This device not found @@ -425,22 +425,22 @@ LRESULT UsbCameraImpl::PumpMain(HWND hwnd, UINT uiMsg, WPARAM wParam, return 0l; } -static cs::VideoMode::PixelFormat GetFromGUID(const GUID& guid) { +static wpi::cs::VideoMode::PixelFormat GetFromGUID(const GUID& guid) { // Compare GUID to one of the supported ones if (IsEqualGUID(guid, MFVideoFormat_L8)) { - return cs::VideoMode::PixelFormat::kGray; + return wpi::cs::VideoMode::PixelFormat::kGray; } else if (IsEqualGUID(guid, MFVideoFormat_L16)) { - return cs::VideoMode::PixelFormat::kY16; + return wpi::cs::VideoMode::PixelFormat::kY16; } else if (IsEqualGUID(guid, MFVideoFormat_YUY2)) { - return cs::VideoMode::PixelFormat::kYUYV; + return wpi::cs::VideoMode::PixelFormat::kYUYV; } else if (IsEqualGUID(guid, MFVideoFormat_MJPG)) { - return cs::VideoMode::PixelFormat::kMJPEG; + return wpi::cs::VideoMode::PixelFormat::kMJPEG; } else if (IsEqualGUID(guid, MFVideoFormat_RGB565)) { - return cs::VideoMode::PixelFormat::kRGB565; + return wpi::cs::VideoMode::PixelFormat::kRGB565; } else if (IsEqualGUID(guid, MFVideoFormat_UYVY)) { - return cs::VideoMode::PixelFormat::kUYVY; + return wpi::cs::VideoMode::PixelFormat::kUYVY; } else { - return cs::VideoMode::PixelFormat::kUnknown; + return wpi::cs::VideoMode::PixelFormat::kUnknown; } } @@ -713,7 +713,7 @@ void UsbCameraImpl::DeviceCacheProperty( } CS_StatusValue UsbCameraImpl::DeviceProcessCommand( - std::unique_lock& lock, Message::Kind msgKind, + std::unique_lock& lock, Message::Kind msgKind, const Message* msg) { if (msgKind == Message::kCmdSetMode || msgKind == Message::kCmdSetPixelFormat || @@ -736,8 +736,8 @@ CS_StatusValue UsbCameraImpl::DeviceProcessCommand( { std::scoped_lock lock(m_mutex); m_path = msg->dataStr; - wpi::SmallVector wideStorage; - wpi::sys::windows::UTF8ToUTF16(m_path, wideStorage); + wpi::util::SmallVector wideStorage; + wpi::util::sys::windows::UTF8ToUTF16(m_path, wideStorage); m_widePath = std::wstring{wideStorage.data(), wideStorage.size()}; } DeviceDisconnect(); @@ -749,7 +749,7 @@ CS_StatusValue UsbCameraImpl::DeviceProcessCommand( } CS_StatusValue UsbCameraImpl::DeviceCmdSetProperty( - std::unique_lock& lock, const Message& msg) { + std::unique_lock& lock, const Message& msg) { bool setString = (msg.kind == Message::kCmdSetPropertyStr); int property = msg.data[0]; int value = msg.data[1]; @@ -826,7 +826,7 @@ ComPtr UsbCameraImpl::DeviceCheckModeValid( } CS_StatusValue UsbCameraImpl::DeviceCmdSetMode( - std::unique_lock& lock, const Message& msg) { + std::unique_lock& lock, const Message& msg) { VideoMode newMode; if (msg.kind == Message::kCmdSetMode) { newMode.pixelFormat = msg.data[0]; @@ -1021,19 +1021,19 @@ void UsbCameraImpl::DeviceCacheVideoModes() { } static void ParseVidAndPid(std::string_view path, int* pid, int* vid) { - auto vidIndex = wpi::find_lower(path, "vid_"); - auto pidIndex = wpi::find_lower(path, "pid_"); + auto vidIndex = wpi::util::find_lower(path, "vid_"); + auto pidIndex = wpi::util::find_lower(path, "pid_"); if (vidIndex != std::string_view::npos) { - auto vidSlice = wpi::slice(path, vidIndex + 4, vidIndex + 8); - if (auto v = wpi::parse_integer(vidSlice, 16)) { + auto vidSlice = wpi::util::slice(path, vidIndex + 4, vidIndex + 8); + if (auto v = wpi::util::parse_integer(vidSlice, 16)) { *vid = v.value(); } } if (pidIndex != std::string_view::npos) { - auto pidSlice = wpi::slice(path, pidIndex + 4, pidIndex + 8); - if (auto v = wpi::parse_integer(pidSlice, 16)) { + auto pidSlice = wpi::util::slice(path, pidIndex + 4, pidIndex + 8); + if (auto v = wpi::util::parse_integer(pidSlice, 16)) { *pid = v.value(); } } @@ -1045,7 +1045,7 @@ std::vector EnumerateUsbCameras(CS_Status* status) { // Ensure we are initialized by grabbing the message pump // GetMessagePump(); - wpi::SmallString<128> storage; + wpi::util::SmallString<128> storage; WCHAR buf[512]; ComPtr pAttributes; IMFActivate** ppDevices = nullptr; @@ -1083,13 +1083,13 @@ std::vector EnumerateUsbCameras(CS_Status* status) { ppDevices[i]->GetString(MF_DEVSOURCE_ATTRIBUTE_FRIENDLY_NAME, buf, sizeof(buf) / sizeof(WCHAR), &characters); storage.clear(); - wpi::sys::windows::UTF16ToUTF8(buf, characters, storage); + wpi::util::sys::windows::UTF16ToUTF8(buf, characters, storage); info.name = std::string{storage}; ppDevices[i]->GetString( MF_DEVSOURCE_ATTRIBUTE_SOURCE_TYPE_VIDCAP_SYMBOLIC_LINK, buf, sizeof(buf) / sizeof(WCHAR), &characters); storage.clear(); - wpi::sys::windows::UTF16ToUTF8(buf, characters, storage); + wpi::util::sys::windows::UTF16ToUTF8(buf, characters, storage); info.path = std::string{storage}; // Try to parse path from symbolic link @@ -1117,7 +1117,7 @@ done: CS_Source CreateUsbCameraDev(std::string_view name, int dev, CS_Status* status) { // First check if device exists - auto devices = cs::EnumerateUsbCameras(status); + auto devices = wpi::cs::EnumerateUsbCameras(status); if (devices.size() > dev) { return CreateUsbCameraPath(name, devices[dev].path, status); } @@ -1163,11 +1163,11 @@ UsbCameraInfo GetUsbCameraInfo(CS_Source source, CS_Status* status) { } info.path = static_cast(*data->source).GetPath(); - wpi::SmallVector buf; + wpi::util::SmallVector buf; info.name = static_cast(*data->source).GetDescription(buf); ParseVidAndPid(info.path, &info.productId, &info.vendorId); info.dev = -1; // We have lost dev information by this point in time. return info; } -} // namespace cs +} // namespace wpi::cs diff --git a/cscore/src/main/native/windows/UsbCameraImpl.hpp b/cscore/src/main/native/windows/UsbCameraImpl.hpp index 86ae606211..a97754fe8f 100644 --- a/cscore/src/main/native/windows/UsbCameraImpl.hpp +++ b/cscore/src/main/native/windows/UsbCameraImpl.hpp @@ -34,14 +34,14 @@ #include "wpi/util/raw_istream.hpp" #include "wpi/util/raw_ostream.hpp" -namespace cs { +namespace wpi::cs { class UsbCameraImpl : public SourceImpl, public std::enable_shared_from_this { public: - UsbCameraImpl(std::string_view name, wpi::Logger& logger, Notifier& notifier, + UsbCameraImpl(std::string_view name, wpi::util::Logger& logger, Notifier& notifier, Telemetry& telemetry, std::string_view path); - UsbCameraImpl(std::string_view name, wpi::Logger& logger, Notifier& notifier, + UsbCameraImpl(std::string_view name, wpi::util::Logger& logger, Notifier& notifier, Telemetry& telemetry, int deviceId); ~UsbCameraImpl() override; @@ -137,12 +137,12 @@ class UsbCameraImpl : public SourceImpl, ComPtr DeviceCheckModeValid(const VideoMode& toCheck); // Command helper functions - CS_StatusValue DeviceProcessCommand(std::unique_lock& lock, + CS_StatusValue DeviceProcessCommand(std::unique_lock& lock, Message::Kind msgKind, const Message* msg); - CS_StatusValue DeviceCmdSetMode(std::unique_lock& lock, + CS_StatusValue DeviceCmdSetMode(std::unique_lock& lock, const Message& msg); - CS_StatusValue DeviceCmdSetProperty(std::unique_lock& lock, + CS_StatusValue DeviceCmdSetProperty(std::unique_lock& lock, const Message& msg); // Property helper functions @@ -163,7 +163,7 @@ class UsbCameraImpl : public SourceImpl, ComPtr m_mediaSource; ComPtr m_sourceReader; ComPtr m_imageCallback; - std::unique_ptr m_messagePump; + std::unique_ptr m_messagePump; ComPtr m_currentMode; std::string m_path; @@ -174,6 +174,6 @@ class UsbCameraImpl : public SourceImpl, std::vector>> m_windowsVideoModes; }; -} // namespace cs +} // namespace wpi::cs #endif // CSCORE_USBCAMERAIMPL_HPP_ diff --git a/cscore/src/main/native/windows/UsbCameraListener.cpp b/cscore/src/main/native/windows/UsbCameraListener.cpp index 61570cceba..740b4fd934 100644 --- a/cscore/src/main/native/windows/UsbCameraListener.cpp +++ b/cscore/src/main/native/windows/UsbCameraListener.cpp @@ -13,7 +13,7 @@ #define IDT_TIMER1 1001 -using namespace cs; +using namespace wpi::cs; class UsbCameraListener::Impl { public: @@ -55,10 +55,10 @@ class UsbCameraListener::Impl { } Notifier& m_notifier; - std::unique_ptr m_messagePump; + std::unique_ptr m_messagePump; }; -UsbCameraListener::UsbCameraListener(wpi::Logger& logger, Notifier& notifier) +UsbCameraListener::UsbCameraListener(wpi::util::Logger& logger, Notifier& notifier) : m_impl{std::make_unique(notifier)} {} UsbCameraListener::~UsbCameraListener() { diff --git a/cscore/src/main/native/windows/UsbCameraProperty.cpp b/cscore/src/main/native/windows/UsbCameraProperty.cpp index 6f89c749a5..b82d997a21 100644 --- a/cscore/src/main/native/windows/UsbCameraProperty.cpp +++ b/cscore/src/main/native/windows/UsbCameraProperty.cpp @@ -8,7 +8,7 @@ #include "ComPtr.hpp" -using namespace cs; +using namespace wpi::cs; UsbCameraProperty::UsbCameraProperty(std::string_view name_, tagVideoProcAmpProperty tag, bool autoProp, @@ -38,7 +38,7 @@ UsbCameraProperty::UsbCameraProperty(std::string_view name_, } } -bool UsbCameraProperty::DeviceGet(std::unique_lock& lock, +bool UsbCameraProperty::DeviceGet(std::unique_lock& lock, IAMVideoProcAmp* pProcAmp) { if (!pProcAmp) { return true; @@ -54,11 +54,11 @@ bool UsbCameraProperty::DeviceGet(std::unique_lock& lock, return false; } -bool UsbCameraProperty::DeviceSet(std::unique_lock& lock, +bool UsbCameraProperty::DeviceSet(std::unique_lock& lock, IAMVideoProcAmp* pProcAmp) const { return DeviceSet(lock, pProcAmp, value); } -bool UsbCameraProperty::DeviceSet(std::unique_lock& lock, +bool UsbCameraProperty::DeviceSet(std::unique_lock& lock, IAMVideoProcAmp* pProcAmp, int newValue) const { if (!pProcAmp) { @@ -104,7 +104,7 @@ UsbCameraProperty::UsbCameraProperty(std::string_view name_, } } -bool UsbCameraProperty::DeviceGet(std::unique_lock& lock, +bool UsbCameraProperty::DeviceGet(std::unique_lock& lock, IAMCameraControl* pProcAmp) { if (!pProcAmp) { return true; @@ -120,11 +120,11 @@ bool UsbCameraProperty::DeviceGet(std::unique_lock& lock, return false; } -bool UsbCameraProperty::DeviceSet(std::unique_lock& lock, +bool UsbCameraProperty::DeviceSet(std::unique_lock& lock, IAMCameraControl* pProcAmp) const { return DeviceSet(lock, pProcAmp, value); } -bool UsbCameraProperty::DeviceSet(std::unique_lock& lock, +bool UsbCameraProperty::DeviceSet(std::unique_lock& lock, IAMCameraControl* pProcAmp, int newValue) const { if (!pProcAmp) { @@ -141,7 +141,7 @@ bool UsbCameraProperty::DeviceSet(std::unique_lock& lock, return false; } -bool UsbCameraProperty::DeviceGet(std::unique_lock& lock, +bool UsbCameraProperty::DeviceGet(std::unique_lock& lock, IMFSourceReader* sourceReader) { if (!sourceReader) { return true; @@ -167,11 +167,11 @@ bool UsbCameraProperty::DeviceGet(std::unique_lock& lock, } } } -bool UsbCameraProperty::DeviceSet(std::unique_lock& lock, +bool UsbCameraProperty::DeviceSet(std::unique_lock& lock, IMFSourceReader* sourceReader) const { return DeviceSet(lock, sourceReader, value); } -bool UsbCameraProperty::DeviceSet(std::unique_lock& lock, +bool UsbCameraProperty::DeviceSet(std::unique_lock& lock, IMFSourceReader* sourceReader, int newValue) const { if (!sourceReader) { diff --git a/cscore/src/main/native/windows/UsbCameraProperty.hpp b/cscore/src/main/native/windows/UsbCameraProperty.hpp index 2f0c056839..3a81f413b8 100644 --- a/cscore/src/main/native/windows/UsbCameraProperty.hpp +++ b/cscore/src/main/native/windows/UsbCameraProperty.hpp @@ -16,7 +16,7 @@ #include "PropertyImpl.hpp" #include "wpi/util/mutex.hpp" -namespace cs { +namespace wpi::cs { // Property data class UsbCameraProperty : public PropertyImpl { @@ -54,11 +54,11 @@ class UsbCameraProperty : public PropertyImpl { UsbCameraProperty(std::string_view name_, tagCameraControlProperty tag, bool autoProp, IAMCameraControl* pProcAmp, bool* isValid); - bool DeviceGet(std::unique_lock& lock, + bool DeviceGet(std::unique_lock& lock, IMFSourceReader* sourceReader); - bool DeviceSet(std::unique_lock& lock, + bool DeviceSet(std::unique_lock& lock, IMFSourceReader* sourceReader) const; - bool DeviceSet(std::unique_lock& lock, + bool DeviceSet(std::unique_lock& lock, IMFSourceReader* sourceReader, int newValue) const; // If this is a device (rather than software) property @@ -81,17 +81,17 @@ class UsbCameraProperty : public PropertyImpl { int type{0}; // implementation type, not CS_PropertyKind! private: - bool DeviceGet(std::unique_lock& lock, + bool DeviceGet(std::unique_lock& lock, IAMCameraControl* pProcAmp); - bool DeviceSet(std::unique_lock& lock, + bool DeviceSet(std::unique_lock& lock, IAMCameraControl* pProcAmp) const; - bool DeviceSet(std::unique_lock& lock, IAMCameraControl* pProcAmp, + bool DeviceSet(std::unique_lock& lock, IAMCameraControl* pProcAmp, int newValue) const; - bool DeviceGet(std::unique_lock& lock, IAMVideoProcAmp* pProcAmp); - bool DeviceSet(std::unique_lock& lock, + bool DeviceGet(std::unique_lock& lock, IAMVideoProcAmp* pProcAmp); + bool DeviceSet(std::unique_lock& lock, IAMVideoProcAmp* pProcAmp) const; - bool DeviceSet(std::unique_lock& lock, IAMVideoProcAmp* pProcAmp, + bool DeviceSet(std::unique_lock& lock, IAMVideoProcAmp* pProcAmp, int newValue) const; }; -} // namespace cs +} // namespace wpi::cs diff --git a/cscore/src/main/native/windows/WindowsMessagePump.cpp b/cscore/src/main/native/windows/WindowsMessagePump.cpp index cc9dede479..3f0d93ff60 100644 --- a/cscore/src/main/native/windows/WindowsMessagePump.cpp +++ b/cscore/src/main/native/windows/WindowsMessagePump.cpp @@ -21,7 +21,7 @@ #pragma comment(lib, "Ole32.lib") #pragma comment(lib, "User32.lib") -namespace cs { +namespace wpi::cs { static LRESULT CALLBACK pWndProc(HWND hwnd, UINT uiMsg, WPARAM wParam, LPARAM lParam) { @@ -148,4 +148,4 @@ void WindowsMessagePump::ThreadMain(HANDLE eventHandle) { CoUninitialize(); } -} // namespace cs +} // namespace wpi::cs diff --git a/cscore/src/main/native/windows/WindowsMessagePump.hpp b/cscore/src/main/native/windows/WindowsMessagePump.hpp index 97a3f2d018..2bcb533659 100644 --- a/cscore/src/main/native/windows/WindowsMessagePump.hpp +++ b/cscore/src/main/native/windows/WindowsMessagePump.hpp @@ -9,7 +9,7 @@ #include #include -namespace cs { +namespace wpi::cs { class WindowsMessagePump { public: explicit WindowsMessagePump( @@ -60,4 +60,4 @@ class WindowsMessagePump { std::thread m_mainThread; }; -} // namespace cs +} // namespace wpi::cs diff --git a/cscore/src/test/native/cpp/CameraSourceTest.cpp b/cscore/src/test/native/cpp/CameraSourceTest.cpp index c73d8c29a5..bcc51e2965 100644 --- a/cscore/src/test/native/cpp/CameraSourceTest.cpp +++ b/cscore/src/test/native/cpp/CameraSourceTest.cpp @@ -6,7 +6,7 @@ #include "wpi/cs/cscore.h" -namespace cs { +namespace wpi::cs { class CameraSourceTest : public ::testing::Test { protected: @@ -15,7 +15,7 @@ class CameraSourceTest : public ::testing::Test { TEST_F(CameraSourceTest, HTTPCamera) { auto source = HttpCamera("axis", "http://localhost:8000"); - cs::Shutdown(); + wpi::cs::Shutdown(); } -} // namespace cs +} // namespace wpi::cs diff --git a/datalog/examples/printlog/printlog.cpp b/datalog/examples/printlog/printlog.cpp index c4e966fdf1..ac9586a1a0 100644 --- a/datalog/examples/printlog/printlog.cpp +++ b/datalog/examples/printlog/printlog.cpp @@ -17,74 +17,74 @@ int main(int argc, const char** argv) { if (argc != 2) { - wpi::print(stderr, "Usage: printlog \n"); + wpi::util::print(stderr, "Usage: printlog \n"); return EXIT_FAILURE; } - auto fileBuffer = wpi::MemoryBuffer::GetFile(argv[1]); + auto fileBuffer = wpi::util::MemoryBuffer::GetFile(argv[1]); if (!fileBuffer) { - wpi::print(stderr, "could not open file: {}\n", + wpi::util::print(stderr, "could not open file: {}\n", fileBuffer.error().message()); return EXIT_FAILURE; } wpi::log::DataLogReader reader{std::move(*fileBuffer)}; if (!reader) { - wpi::print(stderr, "not a log file\n"); + wpi::util::print(stderr, "not a log file\n"); return EXIT_FAILURE; } - wpi::DenseMap entries; + wpi::util::DenseMap entries; for (auto&& record : reader) { if (record.IsStart()) { wpi::log::StartRecordData data; if (record.GetStartData(&data)) { - wpi::print("Start({}, name='{}', type='{}', metadata='{}') [{}]\n", + wpi::util::print("Start({}, name='{}', type='{}', metadata='{}') [{}]\n", data.entry, data.name, data.type, data.metadata, record.GetTimestamp() / 1000000.0); if (entries.find(data.entry) != entries.end()) { - wpi::print("...DUPLICATE entry ID, overriding\n"); + wpi::util::print("...DUPLICATE entry ID, overriding\n"); } entries[data.entry] = data; } else { - wpi::print("Start(INVALID)\n"); + wpi::util::print("Start(INVALID)\n"); } } else if (record.IsFinish()) { int entry; if (record.GetFinishEntry(&entry)) { - wpi::print("Finish({}) [{}]\n", entry, + wpi::util::print("Finish({}) [{}]\n", entry, record.GetTimestamp() / 1000000.0); auto it = entries.find(entry); if (it == entries.end()) { - wpi::print("...ID not found\n"); + wpi::util::print("...ID not found\n"); } else { entries.erase(it); } } else { - wpi::print("Finish(INVALID)\n"); + wpi::util::print("Finish(INVALID)\n"); } } else if (record.IsSetMetadata()) { wpi::log::MetadataRecordData data; if (record.GetSetMetadataData(&data)) { - wpi::print("SetMetadata({}, '{}') [{}]\n", data.entry, data.metadata, + wpi::util::print("SetMetadata({}, '{}') [{}]\n", data.entry, data.metadata, record.GetTimestamp() / 1000000.0); auto it = entries.find(data.entry); if (it == entries.end()) { - wpi::print("...ID not found\n"); + wpi::util::print("...ID not found\n"); } else { it->second.metadata = data.metadata; } } else { - wpi::print("SetMetadata(INVALID)\n"); + wpi::util::print("SetMetadata(INVALID)\n"); } } else if (record.IsControl()) { - wpi::print("Unrecognized control record\n"); + wpi::util::print("Unrecognized control record\n"); } else { - wpi::print("Data({}, size={}) ", record.GetEntry(), record.GetSize()); + wpi::util::print("Data({}, size={}) ", record.GetEntry(), record.GetSize()); auto entry = entries.find(record.GetEntry()); if (entry == entries.end()) { - wpi::print("\n"); + wpi::util::print("\n"); continue; } - wpi::print(" [{}]\n", entry->second.name, + wpi::util::print(" [{}]\n", entry->second.name, entry->second.type, record.GetTimestamp() / 1000000.0); // handle systemTime specially @@ -92,10 +92,10 @@ int main(int argc, const char** argv) { int64_t val; if (record.GetInteger(&val)) { std::time_t timeval = val / 1000000; - wpi::print(" {:%Y-%m-%d %H:%M:%S}.{:06}\n", + wpi::util::print(" {:%Y-%m-%d %H:%M:%S}.{:06}\n", *std::localtime(&timeval), val % 1000000); } else { - wpi::print(" invalid\n"); + wpi::util::print(" invalid\n"); } continue; } @@ -103,63 +103,63 @@ int main(int argc, const char** argv) { if (entry->second.type == "double") { double val; if (record.GetDouble(&val)) { - wpi::print(" {}\n", val); + wpi::util::print(" {}\n", val); } else { - wpi::print(" invalid\n"); + wpi::util::print(" invalid\n"); } } else if (entry->second.type == "int64") { int64_t val; if (record.GetInteger(&val)) { - wpi::print(" {}\n", val); + wpi::util::print(" {}\n", val); } else { - wpi::print(" invalid\n"); + wpi::util::print(" invalid\n"); } } else if (entry->second.type == "string" || entry->second.type == "json") { std::string_view val; record.GetString(&val); - wpi::print(" '{}'\n", val); + wpi::util::print(" '{}'\n", val); } else if (entry->second.type == "boolean") { bool val; if (record.GetBoolean(&val)) { - wpi::print(" {}\n", val); + wpi::util::print(" {}\n", val); } else { - wpi::print(" invalid\n"); + wpi::util::print(" invalid\n"); } } else if (entry->second.type == "boolean[]") { std::vector val; if (record.GetBooleanArray(&val)) { - wpi::print(" {}\n", fmt::join(val, ", ")); + wpi::util::print(" {}\n", fmt::join(val, ", ")); } else { - wpi::print(" invalid\n"); + wpi::util::print(" invalid\n"); } } else if (entry->second.type == "double[]") { std::vector val; if (record.GetDoubleArray(&val)) { - wpi::print(" {}\n", fmt::join(val, ", ")); + wpi::util::print(" {}\n", fmt::join(val, ", ")); } else { - wpi::print(" invalid\n"); + wpi::util::print(" invalid\n"); } } else if (entry->second.type == "float[]") { std::vector val; if (record.GetFloatArray(&val)) { - wpi::print(" {}\n", fmt::join(val, ", ")); + wpi::util::print(" {}\n", fmt::join(val, ", ")); } else { - wpi::print(" invalid\n"); + wpi::util::print(" invalid\n"); } } else if (entry->second.type == "int64[]") { std::vector val; if (record.GetIntegerArray(&val)) { - wpi::print(" {}\n", fmt::join(val, ", ")); + wpi::util::print(" {}\n", fmt::join(val, ", ")); } else { - wpi::print(" invalid\n"); + wpi::util::print(" invalid\n"); } } else if (entry->second.type == "string[]") { std::vector val; if (record.GetStringArray(&val)) { - wpi::print(" {}\n", fmt::join(val, ", ")); + wpi::util::print(" {}\n", fmt::join(val, ", ")); } else { - wpi::print(" invalid\n"); + wpi::util::print(" invalid\n"); } } } diff --git a/datalog/examples/writelog/writelog.cpp b/datalog/examples/writelog/writelog.cpp index 154a97dcd1..6e6d23bd33 100644 --- a/datalog/examples/writelog/writelog.cpp +++ b/datalog/examples/writelog/writelog.cpp @@ -65,7 +65,7 @@ int main(int argc, char** argv) { for (const auto& [name, fn] : testVec) { auto resVec = std::vector(); - wpi::print("{}: ", name); + wpi::util::print("{}: ", name); for (int i = 0; i < kNumRuns; ++i) { auto start = high_resolution_clock::now(); @@ -74,7 +74,7 @@ int main(int argc, char** argv) { resVec.push_back(duration_cast(stop - start).count()); } - wpi::print("{}us\n", + wpi::util::print("{}us\n", std::accumulate(resVec.begin(), resVec.end(), 0) / kNumRuns); } diff --git a/datalog/src/main/native/cpp/DataLog.cpp b/datalog/src/main/native/cpp/DataLog.cpp index b48fffc5ad..50ffa32105 100644 --- a/datalog/src/main/native/cpp/DataLog.cpp +++ b/datalog/src/main/native/cpp/DataLog.cpp @@ -25,14 +25,14 @@ static constexpr size_t kRecordMaxHeaderSize = 17; static void DefaultLog(unsigned int level, const char* file, unsigned int line, const char* msg) { - if (level > wpi::WPI_LOG_INFO) { - wpi::print(stderr, "DataLog: {}\n", msg); - } else if (level == wpi::WPI_LOG_INFO) { - wpi::print("DataLog: {}\n", msg); + if (level > wpi::util::WPI_LOG_INFO) { + wpi::util::print(stderr, "DataLog: {}\n", msg); + } else if (level == wpi::util::WPI_LOG_INFO) { + wpi::util::print("DataLog: {}\n", msg); } } -wpi::Logger DataLog::s_defaultMessageLog{DefaultLog}; +wpi::util::Logger DataLog::s_defaultMessageLog{DefaultLog}; template static unsigned int WriteVarInt(uint8_t* buf, T val) { @@ -56,7 +56,7 @@ static unsigned int WriteRecordHeader(uint8_t* buf, uint32_t entry, unsigned int payloadLen = WriteVarInt(buf, payloadSize); buf += payloadLen; unsigned int timestampLen = - WriteVarInt(buf, timestamp == 0 ? wpi::Now() : timestamp); + WriteVarInt(buf, timestamp == 0 ? wpi::util::Now() : timestamp); buf += timestampLen; *origbuf = ((timestampLen - 1) << 4) | ((payloadLen - 1) << 2) | (entryLen - 1); @@ -78,7 +78,7 @@ void DataLog::StartFile() { uint8_t* buf = Reserve(m_extraHeader.size() + 12); static const uint8_t header[] = {'W', 'P', 'I', 'L', 'O', 'G', 0, 1}; std::memcpy(buf, header, 8); - support::endian::write32le(buf + 8, m_extraHeader.size()); + wpi::util::support::endian::write32le(buf + 8, m_extraHeader.size()); std::memcpy(buf + 12, m_extraHeader.data(), m_extraHeader.size()); // Existing start and schema data records @@ -145,7 +145,7 @@ void DataLog::AddSchema(std::string_view name, std::string_view type, return; // don't add duplicates } schemaInfo.data.assign(schema.begin(), schema.end()); - wpi::SmallString<128> fullName{"/.schema/"}; + wpi::util::SmallString<128> fullName{"/.schema/"}; fullName += name; int entry = StartImpl(fullName, type, {}, timestamp); @@ -206,7 +206,7 @@ void DataLog::AppendStartRecord(int id, std::string_view name, size_t strsize = name.size() + type.size() + metadata.size(); uint8_t* buf = StartRecord(0, timestamp, 5 + 12 + strsize, 5); *buf++ = impl::kControlStart; - wpi::support::endian::write32le(buf, id); + wpi::util::support::endian::write32le(buf, id); AppendStringImpl(name); AppendStringImpl(type); AppendStringImpl(metadata); @@ -241,7 +241,7 @@ void DataLog::Finish(int entry, int64_t timestamp) { } uint8_t* buf = StartRecord(0, timestamp, 5, 5); *buf++ = impl::kControlFinish; - wpi::support::endian::write32le(buf, entry); + wpi::util::support::endian::write32le(buf, entry); } void DataLog::SetMetadata(int entry, std::string_view metadata, @@ -256,7 +256,7 @@ void DataLog::SetMetadata(int entry, std::string_view metadata, } uint8_t* buf = StartRecord(0, timestamp, 5 + 4 + metadata.size(), 5); *buf++ = impl::kControlSetMetadata; - wpi::support::endian::write32le(buf, entry); + wpi::util::support::endian::write32le(buf, entry); AppendStringImpl(metadata); } @@ -305,7 +305,7 @@ void DataLog::AppendImpl(std::span data) { void DataLog::AppendStringImpl(std::string_view str) { uint8_t* buf = Reserve(4); - wpi::support::endian::write32le(buf, str.size()); + wpi::util::support::endian::write32le(buf, str.size()); AppendImpl({reinterpret_cast(str.data()), str.size()}); } @@ -363,7 +363,7 @@ void DataLog::AppendInteger(int entry, int64_t value, int64_t timestamp) { [[unlikely]] return; } uint8_t* buf = StartRecord(entry, timestamp, 8, 8); - wpi::support::endian::write64le(buf, value); + wpi::util::support::endian::write64le(buf, value); } void DataLog::AppendFloat(int entry, float value, int64_t timestamp) { @@ -378,7 +378,7 @@ void DataLog::AppendFloat(int entry, float value, int64_t timestamp) { if constexpr (std::endian::native == std::endian::little) { std::memcpy(buf, &value, 4); } else { - wpi::support::endian::write32le(buf, std::bit_cast(value)); + wpi::util::support::endian::write32le(buf, std::bit_cast(value)); } } @@ -394,7 +394,7 @@ void DataLog::AppendDouble(int entry, double value, int64_t timestamp) { if constexpr (std::endian::native == std::endian::little) { std::memcpy(buf, &value, 8); } else { - wpi::support::endian::write64le(buf, std::bit_cast(value)); + wpi::util::support::endian::write64le(buf, std::bit_cast(value)); } } @@ -477,14 +477,14 @@ void DataLog::AppendIntegerArray(int entry, std::span arr, while ((arr.size() * 8) > kBlockSize) { buf = Reserve(kBlockSize); for (auto val : arr.subspan(0, kBlockSize / 8)) { - wpi::support::endian::write64le(buf, val); + wpi::util::support::endian::write64le(buf, val); buf += 8; } arr = arr.subspan(kBlockSize / 8); } buf = Reserve(arr.size() * 8); for (auto val : arr) { - wpi::support::endian::write64le(buf, val); + wpi::util::support::endian::write64le(buf, val); buf += 8; } } @@ -509,14 +509,14 @@ void DataLog::AppendFloatArray(int entry, std::span arr, while ((arr.size() * 4) > kBlockSize) { buf = Reserve(kBlockSize); for (auto val : arr.subspan(0, kBlockSize / 4)) { - wpi::support::endian::write32le(buf, std::bit_cast(val)); + wpi::util::support::endian::write32le(buf, std::bit_cast(val)); buf += 4; } arr = arr.subspan(kBlockSize / 4); } buf = Reserve(arr.size() * 4); for (auto val : arr) { - wpi::support::endian::write32le(buf, std::bit_cast(val)); + wpi::util::support::endian::write32le(buf, std::bit_cast(val)); buf += 4; } } @@ -541,14 +541,14 @@ void DataLog::AppendDoubleArray(int entry, std::span arr, while ((arr.size() * 8) > kBlockSize) { buf = Reserve(kBlockSize); for (auto val : arr.subspan(0, kBlockSize / 8)) { - wpi::support::endian::write64le(buf, std::bit_cast(val)); + wpi::util::support::endian::write64le(buf, std::bit_cast(val)); buf += 8; } arr = arr.subspan(kBlockSize / 8); } buf = Reserve(arr.size() * 8); for (auto val : arr) { - wpi::support::endian::write64le(buf, std::bit_cast(val)); + wpi::util::support::endian::write64le(buf, std::bit_cast(val)); buf += 8; } } @@ -570,7 +570,7 @@ void DataLog::AppendStringArray(int entry, std::span arr, [[unlikely]] return; } uint8_t* buf = StartRecord(entry, timestamp, size, 4); - wpi::support::endian::write32le(buf, arr.size()); + wpi::util::support::endian::write32le(buf, arr.size()); for (auto&& str : arr) { AppendStringImpl(str); } @@ -593,7 +593,7 @@ void DataLog::AppendStringArray(int entry, [[unlikely]] return; } uint8_t* buf = StartRecord(entry, timestamp, size, 4); - wpi::support::endian::write32le(buf, arr.size()); + wpi::util::support::endian::write32le(buf, arr.size()); for (auto&& sv : arr) { AppendStringImpl(sv); } @@ -616,7 +616,7 @@ void DataLog::AppendStringArray(int entry, [[unlikely]] return; } uint8_t* buf = StartRecord(entry, timestamp, size, 4); - wpi::support::endian::write32le(buf, arr.size()); + wpi::util::support::endian::write32le(buf, arr.size()); for (auto&& sv : arr) { AppendStringImpl(sv.str); } @@ -750,8 +750,8 @@ int WPI_DataLog_Start(struct WPI_DataLog* datalog, const struct WPI_String* type, const struct WPI_String* metadata, int64_t timestamp) { return reinterpret_cast(datalog)->Start( - wpi::to_string_view(name), wpi::to_string_view(type), - wpi::to_string_view(metadata), timestamp); + wpi::util::to_string_view(name), wpi::util::to_string_view(type), + wpi::util::to_string_view(metadata), timestamp); } void WPI_DataLog_Finish(struct WPI_DataLog* datalog, int entry, @@ -763,7 +763,7 @@ void WPI_DataLog_SetMetadata(struct WPI_DataLog* datalog, int entry, const struct WPI_String* metadata, int64_t timestamp) { reinterpret_cast(datalog)->SetMetadata( - entry, wpi::to_string_view(metadata), timestamp); + entry, wpi::util::to_string_view(metadata), timestamp); } void WPI_DataLog_AppendRaw(struct WPI_DataLog* datalog, int entry, @@ -846,8 +846,8 @@ void WPI_DataLog_AddSchemaString(struct WPI_DataLog* datalog, const struct WPI_String* schema, int64_t timestamp) { reinterpret_cast(datalog)->AddSchema( - wpi::to_string_view(name), wpi::to_string_view(type), - wpi::to_string_view(schema), timestamp); + wpi::util::to_string_view(name), wpi::util::to_string_view(type), + wpi::util::to_string_view(schema), timestamp); } void WPI_DataLog_AddSchema(struct WPI_DataLog* datalog, @@ -855,7 +855,7 @@ void WPI_DataLog_AddSchema(struct WPI_DataLog* datalog, const struct WPI_String* type, const uint8_t* schema, size_t schema_len, int64_t timestamp) { reinterpret_cast(datalog)->AddSchema( - wpi::to_string_view(name), wpi::to_string_view(type), + wpi::util::to_string_view(name), wpi::util::to_string_view(type), std::span{schema, schema_len}, timestamp); } diff --git a/datalog/src/main/native/cpp/DataLogBackgroundWriter.cpp b/datalog/src/main/native/cpp/DataLogBackgroundWriter.cpp index 9181954754..45e9a1c59f 100644 --- a/datalog/src/main/native/cpp/DataLogBackgroundWriter.cpp +++ b/datalog/src/main/native/cpp/DataLogBackgroundWriter.cpp @@ -53,7 +53,7 @@ DataLogBackgroundWriter::DataLogBackgroundWriter(std::string_view dir, : DataLogBackgroundWriter{s_defaultMessageLog, dir, filename, period, extraHeader} {} -DataLogBackgroundWriter::DataLogBackgroundWriter(wpi::Logger& msglog, +DataLogBackgroundWriter::DataLogBackgroundWriter(wpi::util::Logger& msglog, std::string_view dir, std::string_view filename, double period, @@ -70,7 +70,7 @@ DataLogBackgroundWriter::DataLogBackgroundWriter( extraHeader} {} DataLogBackgroundWriter::DataLogBackgroundWriter( - wpi::Logger& msglog, + wpi::util::Logger& msglog, std::function data)> write, double period, std::string_view extraHeader) : DataLog{msglog, extraHeader}, @@ -132,7 +132,7 @@ void DataLogBackgroundWriter::Stop() { } static void WriteToFile(fs::file_t f, std::span data, - std::string_view filename, wpi::Logger& msglog) { + std::string_view filename, wpi::util::Logger& msglog) { do { #ifdef _WIN32 DWORD ret; @@ -469,8 +469,8 @@ struct WPI_DataLog* WPI_DataLog_CreateBackgroundWriter( const struct WPI_String* dir, const struct WPI_String* filename, double period, const struct WPI_String* extraHeader) { return reinterpret_cast(new DataLogBackgroundWriter{ - wpi::to_string_view(dir), wpi::to_string_view(filename), period, - wpi::to_string_view(extraHeader)}); + wpi::util::to_string_view(dir), wpi::util::to_string_view(filename), period, + wpi::util::to_string_view(extraHeader)}); } struct WPI_DataLog* WPI_DataLog_CreateBackgroundWriter_Func( @@ -478,13 +478,13 @@ struct WPI_DataLog* WPI_DataLog_CreateBackgroundWriter_Func( double period, const struct WPI_String* extraHeader) { return reinterpret_cast(new DataLogBackgroundWriter{ [=](auto data) { write(ptr, data.data(), data.size()); }, period, - wpi::to_string_view(extraHeader)}); + wpi::util::to_string_view(extraHeader)}); } void WPI_DataLog_SetBackgroundWriterFilename( struct WPI_DataLog* datalog, const struct WPI_String* filename) { reinterpret_cast(datalog)->SetFilename( - wpi::to_string_view(filename)); + wpi::util::to_string_view(filename)); } } // extern "C" diff --git a/datalog/src/main/native/cpp/DataLogReader.cpp b/datalog/src/main/native/cpp/DataLogReader.cpp index c33346a67c..590a0f5976 100644 --- a/datalog/src/main/native/cpp/DataLogReader.cpp +++ b/datalog/src/main/native/cpp/DataLogReader.cpp @@ -17,7 +17,7 @@ static bool ReadString(std::span* buf, std::string_view* str) { *str = {}; return false; } - uint32_t len = wpi::support::endian::read32le(buf->data()); + uint32_t len = wpi::util::support::endian::read32le(buf->data()); if (len > (buf->size() - 4)) { *str = {}; return false; @@ -46,7 +46,7 @@ bool DataLogRecord::GetStartData(StartRecordData* out) const { if (!IsStart()) { return false; } - out->entry = wpi::support::endian::read32le(&m_data[1]); + out->entry = wpi::util::support::endian::read32le(&m_data[1]); auto buf = m_data.subspan(5); if (!ReadString(&buf, &out->name)) { return false; @@ -64,7 +64,7 @@ bool DataLogRecord::GetFinishEntry(int* out) const { if (!IsFinish()) { return false; } - *out = wpi::support::endian::read32le(&m_data[1]); + *out = wpi::util::support::endian::read32le(&m_data[1]); return true; } @@ -72,7 +72,7 @@ bool DataLogRecord::GetSetMetadataData(MetadataRecordData* out) const { if (!IsSetMetadata()) { return false; } - out->entry = wpi::support::endian::read32le(&m_data[1]); + out->entry = wpi::util::support::endian::read32le(&m_data[1]); auto buf = m_data.subspan(5); return ReadString(&buf, &out->metadata); } @@ -89,7 +89,7 @@ bool DataLogRecord::GetInteger(int64_t* value) const { if (m_data.size() != 8) { return false; } - *value = wpi::support::endian::read64le(m_data.data()); + *value = wpi::util::support::endian::read64le(m_data.data()); return true; } @@ -97,7 +97,7 @@ bool DataLogRecord::GetFloat(float* value) const { if (m_data.size() != 4) { return false; } - *value = std::bit_cast(wpi::support::endian::read32le(m_data.data())); + *value = std::bit_cast(wpi::util::support::endian::read32le(m_data.data())); return true; } @@ -105,7 +105,7 @@ bool DataLogRecord::GetDouble(double* value) const { if (m_data.size() != 8) { return false; } - *value = std::bit_cast(wpi::support::endian::read64le(m_data.data())); + *value = std::bit_cast(wpi::util::support::endian::read64le(m_data.data())); return true; } @@ -130,7 +130,7 @@ bool DataLogRecord::GetIntegerArray(std::vector* arr) const { } arr->reserve(m_data.size() / 8); for (size_t pos = 0; pos < m_data.size(); pos += 8) { - arr->push_back(wpi::support::endian::read64le(&m_data[pos])); + arr->push_back(wpi::util::support::endian::read64le(&m_data[pos])); } return true; } @@ -143,7 +143,7 @@ bool DataLogRecord::GetFloatArray(std::vector* arr) const { arr->reserve(m_data.size() / 4); for (size_t pos = 0; pos < m_data.size(); pos += 4) { arr->push_back( - std::bit_cast(wpi::support::endian::read32le(&m_data[pos]))); + std::bit_cast(wpi::util::support::endian::read32le(&m_data[pos]))); } return true; } @@ -156,7 +156,7 @@ bool DataLogRecord::GetDoubleArray(std::vector* arr) const { arr->reserve(m_data.size() / 8); for (size_t pos = 0; pos < m_data.size(); pos += 8) { arr->push_back( - std::bit_cast(wpi::support::endian::read64le(&m_data[pos]))); + std::bit_cast(wpi::util::support::endian::read64le(&m_data[pos]))); } return true; } @@ -166,7 +166,7 @@ bool DataLogRecord::GetStringArray(std::vector* arr) const { if (m_data.size() < 4) { return false; } - uint32_t size = wpi::support::endian::read32le(m_data.data()); + uint32_t size = wpi::util::support::endian::read32le(m_data.data()); // sanity check size if (size > ((m_data.size() - 4) / 4)) { return false; @@ -189,7 +189,7 @@ bool DataLogRecord::GetStringArray(std::vector* arr) const { return true; } -DataLogReader::DataLogReader(std::unique_ptr buffer) +DataLogReader::DataLogReader(std::unique_ptr buffer) : m_buf{std::move(buffer)} {} bool DataLogReader::IsValid() const { @@ -200,7 +200,7 @@ bool DataLogReader::IsValid() const { return buf.size() >= 12 && std::string_view{reinterpret_cast(buf.data()), 6} == "WPILOG" && - wpi::support::endian::read16le(&buf[6]) >= 0x0100; + wpi::util::support::endian::read16le(&buf[6]) >= 0x0100; } uint16_t DataLogReader::GetVersion() const { @@ -211,7 +211,7 @@ uint16_t DataLogReader::GetVersion() const { if (buf.size() < 12) { return 0; } - return wpi::support::endian::read16le(&buf[6]); + return wpi::util::support::endian::read16le(&buf[6]); } std::string_view DataLogReader::GetExtraHeader() const { @@ -236,7 +236,7 @@ DataLogReader::iterator DataLogReader::begin() const { if (buf.size() < 12) { return end(); } - uint32_t size = wpi::support::endian::read32le(&buf[8]); + uint32_t size = wpi::util::support::endian::read32le(&buf[8]); if (buf.size() < (12 + size)) { return end(); } diff --git a/datalog/src/main/native/cpp/DataLogReaderThread.cpp b/datalog/src/main/native/cpp/DataLogReaderThread.cpp index f6aa0c3e99..e17aa16461 100644 --- a/datalog/src/main/native/cpp/DataLogReaderThread.cpp +++ b/datalog/src/main/native/cpp/DataLogReaderThread.cpp @@ -20,7 +20,7 @@ DataLogReaderThread::~DataLogReaderThread() { } void DataLogReaderThread::ReadMain() { - wpi::SmallDenseMap< + wpi::util::SmallDenseMap< int, std::pair>, 8> schemaEntries; @@ -37,7 +37,7 @@ void DataLogReaderThread::ReadMain() { std::scoped_lock lock{m_mutex}; auto& entryPtr = m_entriesById[data.entry]; if (entryPtr) { - wpi::print("...DUPLICATE entry ID, overriding\n"); + wpi::util::print("...DUPLICATE entry ID, overriding\n"); } auto [it, isNew] = m_entriesByName.emplace(data.name, data); if (isNew) { @@ -51,7 +51,7 @@ void DataLogReaderThread::ReadMain() { } sigEntryAdded(data); } else { - wpi::print("Start(INVALID)\n"); + wpi::util::print("Start(INVALID)\n"); } } else if (record.IsFinish()) { int entry; @@ -59,13 +59,13 @@ void DataLogReaderThread::ReadMain() { std::scoped_lock lock{m_mutex}; auto it = m_entriesById.find(entry); if (it == m_entriesById.end()) { - wpi::print("...ID not found\n"); + wpi::util::print("...ID not found\n"); } else { it->second->ranges.back().m_end = recordIt; m_entriesById.erase(it); } } else { - wpi::print("Finish(INVALID)\n"); + wpi::util::print("Finish(INVALID)\n"); } } else if (record.IsSetMetadata()) { wpi::log::MetadataRecordData data; @@ -73,15 +73,15 @@ void DataLogReaderThread::ReadMain() { std::scoped_lock lock{m_mutex}; auto it = m_entriesById.find(data.entry); if (it == m_entriesById.end()) { - wpi::print("...ID not found\n"); + wpi::util::print("...ID not found\n"); } else { it->second->metadata = data.metadata; } } else { - wpi::print("SetMetadata(INVALID)\n"); + wpi::util::print("SetMetadata(INVALID)\n"); } } else if (record.IsControl()) { - wpi::print("Unrecognized control record\n"); + wpi::util::print("Unrecognized control record\n"); } else { auto it = schemaEntries.find(record.GetEntry()); if (it != schemaEntries.end()) { @@ -97,19 +97,19 @@ void DataLogReaderThread::ReadMain() { if (data.empty()) { continue; } - if (auto strippedName = wpi::remove_prefix(name, "NT:")) { + if (auto strippedName = wpi::util::remove_prefix(name, "NT:")) { name = *strippedName; } - if (auto typeStr = wpi::remove_prefix(name, "/.schema/struct:")) { + if (auto typeStr = wpi::util::remove_prefix(name, "/.schema/struct:")) { std::string_view schema{reinterpret_cast(data.data()), data.size()}; std::string err; auto desc = m_structDb.Add(*typeStr, schema, &err); if (!desc) { - wpi::print("could not decode struct '{}' schema '{}': {}\n", name, + wpi::util::print("could not decode struct '{}' schema '{}': {}\n", name, schema, err); } - } else if (auto filename = wpi::remove_prefix(name, "/.schema/proto:")) { + } else if (auto filename = wpi::util::remove_prefix(name, "/.schema/proto:")) { // protobuf descriptor handling upb_Status status; status.ok = true; @@ -119,7 +119,7 @@ void DataLogReaderThread::ReadMain() { reinterpret_cast(data.data()), data.size(), m_arena), &status); if (!status.ok) { - wpi::print("could not decode protobuf '{}' filename '{}'\n", name, + wpi::util::print("could not decode protobuf '{}' filename '{}'\n", name, *filename); } } diff --git a/datalog/src/main/native/cpp/DataLogWriter.cpp b/datalog/src/main/native/cpp/DataLogWriter.cpp index d5359fa063..ed688ac189 100644 --- a/datalog/src/main/native/cpp/DataLogWriter.cpp +++ b/datalog/src/main/native/cpp/DataLogWriter.cpp @@ -12,9 +12,9 @@ using namespace wpi::log; -static std::unique_ptr CheckOpen(std::string_view filename, +static std::unique_ptr CheckOpen(std::string_view filename, std::error_code& ec) { - auto rv = std::make_unique(filename, ec); + auto rv = std::make_unique(filename, ec); if (ec) { return nullptr; } @@ -25,7 +25,7 @@ DataLogWriter::DataLogWriter(std::string_view filename, std::error_code& ec, std::string_view extraHeader) : DataLogWriter{s_defaultMessageLog, filename, ec, extraHeader} {} -DataLogWriter::DataLogWriter(wpi::Logger& msglog, std::string_view filename, +DataLogWriter::DataLogWriter(wpi::util::Logger& msglog, std::string_view filename, std::error_code& ec, std::string_view extraHeader) : DataLogWriter{msglog, CheckOpen(filename, ec), extraHeader} { if (ec) { @@ -33,12 +33,12 @@ DataLogWriter::DataLogWriter(wpi::Logger& msglog, std::string_view filename, } } -DataLogWriter::DataLogWriter(std::unique_ptr os, +DataLogWriter::DataLogWriter(std::unique_ptr os, std::string_view extraHeader) : DataLogWriter{s_defaultMessageLog, std::move(os), extraHeader} {} -DataLogWriter::DataLogWriter(wpi::Logger& msglog, - std::unique_ptr os, +DataLogWriter::DataLogWriter(wpi::util::Logger& msglog, + std::unique_ptr os, std::string_view extraHeader) : DataLog{msglog, extraHeader}, m_os{std::move(os)} { StartFile(); @@ -80,7 +80,7 @@ struct WPI_DataLog* WPI_DataLog_CreateWriter( const struct WPI_String* extraHeader) { std::error_code ec; auto rv = reinterpret_cast(new DataLogWriter{ - wpi::to_string_view(filename), ec, wpi::to_string_view(extraHeader)}); + wpi::util::to_string_view(filename), ec, wpi::util::to_string_view(extraHeader)}); *errorCode = ec.value(); return rv; } diff --git a/datalog/src/main/native/cpp/FileLogger.cpp b/datalog/src/main/native/cpp/FileLogger.cpp index 67af422dcb..5f5cf834e3 100644 --- a/datalog/src/main/native/cpp/FileLogger.cpp +++ b/datalog/src/main/native/cpp/FileLogger.cpp @@ -88,12 +88,12 @@ FileLogger::~FileLogger() { std::function FileLogger::Buffer( std::function callback) { return [callback, - buf = wpi::SmallVector{}](std::string_view data) mutable { + buf = wpi::util::SmallVector{}](std::string_view data) mutable { buf.append(data.begin(), data.end()); - if (!wpi::contains({data.data(), data.size()}, "\n")) { + if (!wpi::util::contains({data.data(), data.size()}, "\n")) { return; } - auto [wholeData, extra] = wpi::rsplit({buf.data(), buf.size()}, "\n"); + auto [wholeData, extra] = wpi::util::rsplit({buf.data(), buf.size()}, "\n"); std::string leftover{extra}; callback(wholeData); diff --git a/datalog/src/main/native/cpp/jni/DataLogJNI.cpp b/datalog/src/main/native/cpp/jni/DataLogJNI.cpp index f3f11dbfa2..f03880739f 100644 --- a/datalog/src/main/native/cpp/jni/DataLogJNI.cpp +++ b/datalog/src/main/native/cpp/jni/DataLogJNI.cpp @@ -19,7 +19,7 @@ #include "wpi/datalog/FileLogger.hpp" #include "wpi/util/jni_util.hpp" -using namespace wpi::java; +using namespace wpi::util::java; using namespace wpi::log; static bool mockTimeEnabled = false; @@ -53,12 +53,12 @@ void wpi::ThrowNullPointerException(JNIEnv* env, std::string_view msg) { } namespace { -class buf_ostream : public wpi::raw_uvector_ostream { +class buf_ostream : public wpi::util::raw_uvector_ostream { private: std::vector data; public: - buf_ostream() : raw_uvector_ostream{data} {} + buf_ostream() : wpi::util::raw_uvector_ostream{data} {} void clear() { data.clear(); } }; @@ -181,7 +181,7 @@ Java_org_wpilib_util_WPIUtilJNI_now if (mockTimeEnabled) { return mockNow; } else { - return wpi::Now(); + return wpi::util::Now(); } } @@ -599,7 +599,7 @@ Java_org_wpilib_datalog_DataLogJNI_appendIntegerArray entry, {reinterpret_cast(jarr.data()), jarr.size()}, timestamp); } else { - wpi::SmallVector arr; + wpi::util::SmallVector arr; arr.reserve(jarr.size()); for (auto v : jarr) { arr.push_back(v); diff --git a/datalog/src/main/native/include/wpi/datalog/DataLog.hpp b/datalog/src/main/native/include/wpi/datalog/DataLog.hpp index 98c30ef356..da823809a7 100644 --- a/datalog/src/main/native/include/wpi/datalog/DataLog.hpp +++ b/datalog/src/main/native/include/wpi/datalog/DataLog.hpp @@ -29,7 +29,7 @@ #include "wpi/util/struct/Struct.hpp" #include "wpi/util/timestamp.h" -namespace wpi { +namespace wpi::util { class Logger; } // namespace wpi @@ -158,8 +158,8 @@ class DataLog { * @param msg protobuf message * @param timestamp Time stamp (0 to indicate now) */ - template - void AddProtobufSchema(ProtobufMessage& msg, int64_t timestamp = 0) { + template + void AddProtobufSchema(wpi::util::ProtobufMessage& msg, int64_t timestamp = 0) { if (timestamp == 0) { timestamp = Now(); } @@ -179,12 +179,12 @@ class DataLog { * @param timestamp Time stamp (0 to indicate now) */ template - requires StructSerializable + requires wpi::util::StructSerializable void AddStructSchema(const I&... info, int64_t timestamp = 0) { if (timestamp == 0) { timestamp = Now(); } - ForEachStructSchema( + wpi::util::ForEachStructSchema( [this, timestamp](auto typeString, auto schema) { this->AddSchema(typeString, "structschema", schema, timestamp); }, @@ -381,7 +381,7 @@ class DataLog { protected: static constexpr size_t kBlockSize = 16 * 1024; - static wpi::Logger s_defaultMessageLog; + static wpi::util::Logger s_defaultMessageLog; class Buffer { public: @@ -441,7 +441,7 @@ class DataLog { * @param msglog message logger (will be called from separate thread) * @param extraHeader extra header metadata */ - explicit DataLog(wpi::Logger& msglog, std::string_view extraHeader = "") + explicit DataLog(wpi::util::Logger& msglog, std::string_view extraHeader = "") : m_msglog{msglog}, m_extraHeader{extraHeader} {} /** @@ -503,10 +503,10 @@ class DataLog { void DoReleaseBufs(std::vector* bufs); protected: - wpi::Logger& m_msglog; + wpi::util::Logger& m_msglog; private: - mutable wpi::mutex m_mutex; + mutable wpi::util::mutex m_mutex; bool m_active = false; bool m_paused = false; std::string m_extraHeader; @@ -516,17 +516,17 @@ class DataLog { std::string type; int id{0}; }; - wpi::StringMap m_entries; + wpi::util::StringMap m_entries; struct SchemaInfo { std::vector data; int id{0}; }; - wpi::StringMap m_schemas; + wpi::util::StringMap m_schemas; struct EntryInfo2 { std::string metadata; unsigned int count; }; - wpi::DenseMap m_entryIds; + wpi::util::DenseMap m_entryIds; int m_lastId = 0; }; @@ -627,7 +627,7 @@ class DataLogValueEntryImpl : public DataLogEntry { } protected: - mutable wpi::mutex m_mutex; + mutable wpi::util::mutex m_mutex; std::optional m_lastValue; }; @@ -1299,9 +1299,9 @@ class StringArrayLogEntry * Log raw struct serializable objects. */ template - requires StructSerializable + requires wpi::util::StructSerializable class StructLogEntry : public DataLogEntry { - using S = Struct; + using S = wpi::util::Struct; public: StructLogEntry() = default; @@ -1314,7 +1314,7 @@ class StructLogEntry : public DataLogEntry { m_log = &log; log.AddStructSchema(info..., timestamp); m_entry = - log.Start(name, GetStructTypeString(info...), metadata, timestamp); + log.Start(name, wpi::util::GetStructTypeString(info...), metadata, timestamp); } StructLogEntry(StructLogEntry&& rhs) @@ -1338,14 +1338,14 @@ class StructLogEntry : public DataLogEntry { */ void Append(const T& data, int64_t timestamp = 0) { if constexpr (sizeof...(I) == 0) { - if constexpr (wpi::is_constexpr([] { S::GetSize(); })) { + if constexpr (wpi::util::is_constexpr([] { S::GetSize(); })) { uint8_t buf[S::GetSize()]; S::Pack(buf, data); m_log->AppendRaw(m_entry, buf, timestamp); return; } } - wpi::SmallVector buf; + wpi::util::SmallVector buf; buf.resize_for_overwrite(std::apply(S::GetSize, m_info)); std::apply([&](const I&... info) { S::Pack(buf, data, info...); }, m_info); m_log->AppendRaw(m_entry, buf, timestamp); @@ -1363,7 +1363,7 @@ class StructLogEntry : public DataLogEntry { */ void Update(const T& data, int64_t timestamp = 0) { if constexpr (sizeof...(I) == 0) { - if constexpr (wpi::is_constexpr([] { S::GetSize(); })) { + if constexpr (wpi::util::is_constexpr([] { S::GetSize(); })) { uint8_t buf[S::GetSize()]; S::Pack(buf, data); std::scoped_lock lock{m_mutex}; @@ -1376,7 +1376,7 @@ class StructLogEntry : public DataLogEntry { return; } } - wpi::SmallVector buf; + wpi::util::SmallVector buf; buf.resize_for_overwrite(std::apply(S::GetSize, m_info)); std::apply([&](const I&... info) { S::Pack(buf, data, info...); }, m_info); std::scoped_lock lock{m_mutex}; @@ -1417,7 +1417,7 @@ class StructLogEntry : public DataLogEntry { } private: - mutable wpi::mutex m_mutex; + mutable wpi::util::mutex m_mutex; std::vector m_lastValue; [[no_unique_address]] std::tuple m_info; @@ -1427,9 +1427,9 @@ class StructLogEntry : public DataLogEntry { * Log raw struct serializable array of objects. */ template - requires StructSerializable + requires wpi::util::StructSerializable class StructArrayLogEntry : public DataLogEntry { - using S = Struct; + using S = wpi::util::Struct; public: StructArrayLogEntry() = default; @@ -1443,7 +1443,7 @@ class StructArrayLogEntry : public DataLogEntry { m_log = &log; log.AddStructSchema(info..., timestamp); m_entry = log.Start( - name, MakeStructArrayTypeString(info...), + name, wpi::util::MakeStructArrayTypeString(info...), metadata, timestamp); } @@ -1574,8 +1574,8 @@ class StructArrayLogEntry : public DataLogEntry { } private: - mutable wpi::mutex m_mutex; - StructArrayBuffer m_buf; + mutable wpi::util::mutex m_mutex; + wpi::util::StructArrayBuffer m_buf; std::optional> m_lastValue; [[no_unique_address]] std::tuple m_info; @@ -1584,9 +1584,9 @@ class StructArrayLogEntry : public DataLogEntry { /** * Log protobuf serializable objects. */ -template +template class ProtobufLogEntry : public DataLogEntry { - using P = Protobuf; + using P = wpi::util::Protobuf; public: ProtobufLogEntry() = default; @@ -1606,7 +1606,7 @@ class ProtobufLogEntry : public DataLogEntry { * @param timestamp Time stamp (may be 0 to indicate now) */ void Append(const T& data, int64_t timestamp = 0) { - SmallVector buf; + wpi::util::SmallVector buf; { std::scoped_lock lock{m_mutex}; m_msg.Pack(buf, data); @@ -1626,7 +1626,7 @@ class ProtobufLogEntry : public DataLogEntry { */ void Update(const T& data, int64_t timestamp = 0) { std::scoped_lock lock{m_mutex}; - wpi::SmallVector buf; + wpi::util::SmallVector buf; m_msg.Pack(buf, data); if (!m_lastValue.has_value()) { m_lastValue = std::vector(buf.begin(), buf.end()); @@ -1665,8 +1665,8 @@ class ProtobufLogEntry : public DataLogEntry { } private: - mutable wpi::mutex m_mutex; - ProtobufMessage m_msg; + mutable wpi::util::mutex m_mutex; + wpi::util::ProtobufMessage m_msg; std::optional> m_lastValue; }; diff --git a/datalog/src/main/native/include/wpi/datalog/DataLogBackgroundWriter.hpp b/datalog/src/main/native/include/wpi/datalog/DataLogBackgroundWriter.hpp index 2effef25e6..abdac8166f 100644 --- a/datalog/src/main/native/include/wpi/datalog/DataLogBackgroundWriter.hpp +++ b/datalog/src/main/native/include/wpi/datalog/DataLogBackgroundWriter.hpp @@ -16,7 +16,7 @@ #include "wpi/util/condition_variable.hpp" #include "wpi/util/mutex.hpp" -namespace wpi { +namespace wpi::util { class Logger; } // namespace wpi @@ -65,7 +65,7 @@ class DataLogBackgroundWriter final : public DataLog { * this is a time/storage tradeoff * @param extraHeader extra header data */ - explicit DataLogBackgroundWriter(wpi::Logger& msglog, + explicit DataLogBackgroundWriter(wpi::util::Logger& msglog, std::string_view dir = "", std::string_view filename = "", double period = 0.25, @@ -99,7 +99,7 @@ class DataLogBackgroundWriter final : public DataLog { * @param extraHeader extra header data */ explicit DataLogBackgroundWriter( - wpi::Logger& msglog, + wpi::util::Logger& msglog, std::function data)> write, double period = 0.25, std::string_view extraHeader = ""); @@ -152,8 +152,8 @@ class DataLogBackgroundWriter final : public DataLog { void WriterThreadMain( std::function data)> write); - mutable wpi::mutex m_mutex; - wpi::condition_variable m_cond; + mutable wpi::util::mutex m_mutex; + wpi::util::condition_variable m_cond; bool m_doFlush{false}; bool m_shutdown{false}; enum State { diff --git a/datalog/src/main/native/include/wpi/datalog/DataLogReader.hpp b/datalog/src/main/native/include/wpi/datalog/DataLogReader.hpp index d9b29578db..120843889b 100644 --- a/datalog/src/main/native/include/wpi/datalog/DataLogReader.hpp +++ b/datalog/src/main/native/include/wpi/datalog/DataLogReader.hpp @@ -303,7 +303,7 @@ class DataLogReader { using iterator = DataLogIterator; /** Constructs from a memory buffer. */ - explicit DataLogReader(std::unique_ptr buffer); + explicit DataLogReader(std::unique_ptr buffer); /** Returns true if the data log is valid (e.g. has a valid header). */ explicit operator bool() const { return IsValid(); } @@ -342,7 +342,7 @@ class DataLogReader { iterator end() const { return DataLogIterator{this, SIZE_MAX}; } private: - std::unique_ptr m_buf; + std::unique_ptr m_buf; bool GetRecord(size_t* pos, DataLogRecord* out) const; bool GetNextRecord(size_t* pos) const; diff --git a/datalog/src/main/native/include/wpi/datalog/DataLogReaderThread.hpp b/datalog/src/main/native/include/wpi/datalog/DataLogReaderThread.hpp index f3ae461b23..1651389412 100644 --- a/datalog/src/main/native/include/wpi/datalog/DataLogReaderThread.hpp +++ b/datalog/src/main/native/include/wpi/datalog/DataLogReaderThread.hpp @@ -85,27 +85,27 @@ class DataLogReaderThread { return it->second; } - wpi::StructDescriptorDatabase& GetStructDatabase() { return m_structDb; } + wpi::util::StructDescriptorDatabase& GetStructDatabase() { return m_structDb; } upb_DefPool* GetProtobufDatabase() { return m_protoPool; } upb_Arena* GetProtobufArena() { return m_arena; } const wpi::log::DataLogReader& GetReader() const { return m_reader; } // note: these are called on separate thread - wpi::sig::Signal_mt sigEntryAdded; - wpi::sig::Signal_mt<> sigDone; + wpi::util::sig::Signal_mt sigEntryAdded; + wpi::util::sig::Signal_mt<> sigDone; private: void ReadMain(); wpi::log::DataLogReader m_reader; - mutable wpi::mutex m_mutex; + mutable wpi::util::mutex m_mutex; std::atomic_bool m_active{true}; std::atomic_bool m_done{false}; std::atomic m_numRecords{0}; std::map> m_entriesByName; - wpi::DenseMap m_entriesById; - wpi::StructDescriptorDatabase m_structDb; + wpi::util::DenseMap m_entriesById; + wpi::util::StructDescriptorDatabase m_structDb; upb_DefPool* m_protoPool = upb_DefPool_New(); upb_Arena* m_arena = upb_Arena_New(); std::thread m_thread; diff --git a/datalog/src/main/native/include/wpi/datalog/DataLogWriter.hpp b/datalog/src/main/native/include/wpi/datalog/DataLogWriter.hpp index 60813ef165..fdf4f075ac 100644 --- a/datalog/src/main/native/include/wpi/datalog/DataLogWriter.hpp +++ b/datalog/src/main/native/include/wpi/datalog/DataLogWriter.hpp @@ -10,7 +10,7 @@ #include "wpi/datalog/DataLog.hpp" -namespace wpi { +namespace wpi::util { class raw_ostream; class Logger; } // namespace wpi @@ -43,7 +43,7 @@ class DataLogWriter final : public DataLog { * @param ec error code if failed to open file (output) * @param extraHeader extra header data */ - DataLogWriter(wpi::Logger& msglog, std::string_view filename, + DataLogWriter(wpi::util::Logger& msglog, std::string_view filename, std::error_code& ec, std::string_view extraHeader = ""); /** @@ -52,7 +52,7 @@ class DataLogWriter final : public DataLog { * @param os output stream * @param extraHeader extra header data */ - explicit DataLogWriter(std::unique_ptr os, + explicit DataLogWriter(std::unique_ptr os, std::string_view extraHeader = ""); /** @@ -62,7 +62,7 @@ class DataLogWriter final : public DataLog { * @param os output stream * @param extraHeader extra header data */ - DataLogWriter(wpi::Logger& msglog, std::unique_ptr os, + DataLogWriter(wpi::util::Logger& msglog, std::unique_ptr os, std::string_view extraHeader = ""); ~DataLogWriter() final; @@ -86,12 +86,12 @@ class DataLogWriter final : public DataLog { * * @return output stream */ - wpi::raw_ostream& GetStream() { return *m_os; } + wpi::util::raw_ostream& GetStream() { return *m_os; } private: bool BufferFull() final; - std::unique_ptr m_os; + std::unique_ptr m_os; }; } // namespace wpi::log diff --git a/datalog/src/main/python/semiwrap/DataLogBackgroundWriter.yml b/datalog/src/main/python/semiwrap/DataLogBackgroundWriter.yml index 72aea6bb50..97fded96e8 100644 --- a/datalog/src/main/python/semiwrap/DataLogBackgroundWriter.yml +++ b/datalog/src/main/python/semiwrap/DataLogBackgroundWriter.yml @@ -4,10 +4,10 @@ classes: DataLogBackgroundWriter: overloads: std::string_view, std::string_view, double, std::string_view: - wpi::Logger&, std::string_view, std::string_view, double, std::string_view: + wpi::util::Logger&, std::string_view, std::string_view, double, std::string_view: ignore: true std::function data)>, double, std::string_view: - wpi::Logger&, std::function data)>, double, std::string_view: + wpi::util::Logger&, std::function data)>, double, std::string_view: ignore: true SetFilename: Flush: diff --git a/datalog/src/main/python/semiwrap/DataLogReader.yml b/datalog/src/main/python/semiwrap/DataLogReader.yml index 558f7abc82..4a4af4153f 100644 --- a/datalog/src/main/python/semiwrap/DataLogReader.yml +++ b/datalog/src/main/python/semiwrap/DataLogReader.yml @@ -263,7 +263,7 @@ classes: ignore: true wpi::log::DataLogReader: typealias: - - wpi::MemoryBuffer + - wpi::util::MemoryBuffer methods: DataLogReader: ignore: true @@ -294,7 +294,7 @@ inline_code: | cls_DataLogReader .def(py::init([](const std::string &filename) { - auto mbuf = wpi::MemoryBuffer::GetFile(filename); + auto mbuf = wpi::util::MemoryBuffer::GetFile(filename); if (!mbuf) { py::gil_scoped_acquire gil; #ifdef _WIN32 @@ -318,7 +318,7 @@ inline_code: | throw py::value_error("buffer must only have a single dimension"); } - auto mbuf = wpi::MemoryBuffer::GetMemBuffer(std::span((uint8_t*)req.ptr, req.size), name); + auto mbuf = wpi::util::MemoryBuffer::GetMemBuffer(std::span((uint8_t*)req.ptr, req.size), name); { py::gil_scoped_release gil; diff --git a/datalog/src/main/python/semiwrap/DataLogWriter.yml b/datalog/src/main/python/semiwrap/DataLogWriter.yml index 716cc81df3..95a9e30ac2 100644 --- a/datalog/src/main/python/semiwrap/DataLogWriter.yml +++ b/datalog/src/main/python/semiwrap/DataLogWriter.yml @@ -16,11 +16,11 @@ classes: param_override: ec: ignore: true - wpi::Logger&, std::string_view, std::error_code&, std::string_view: + wpi::util::Logger&, std::string_view, std::error_code&, std::string_view: ignore: true - std::unique_ptr, std::string_view: + std::unique_ptr, std::string_view: ignore: true - wpi::Logger&, std::unique_ptr, std::string_view: + wpi::util::Logger&, std::unique_ptr, std::string_view: ignore: true Flush: Stop: diff --git a/datalog/src/test/native/cpp/DataLogTest.cpp b/datalog/src/test/native/cpp/DataLogTest.cpp index eb92dea619..b02a920be5 100644 --- a/datalog/src/test/native/cpp/DataLogTest.cpp +++ b/datalog/src/test/native/cpp/DataLogTest.cpp @@ -40,7 +40,7 @@ struct Info2 { } // namespace template <> -struct wpi::Struct { +struct wpi::util::Struct { static constexpr std::string_view GetTypeName() { return "ThingA"; } static constexpr size_t GetSize() { return 1; } static constexpr std::string_view GetSchema() { return "uint8 value"; } @@ -53,7 +53,7 @@ struct wpi::Struct { }; template <> -struct wpi::Struct { +struct wpi::util::Struct { static constexpr std::string_view GetTypeName(const Info1&) { return "ThingB"; } @@ -70,7 +70,7 @@ struct wpi::Struct { }; template <> -struct wpi::Struct { +struct wpi::util::Struct { static constexpr std::string_view GetTypeName() { return "ThingC"; } static constexpr size_t GetSize() { return 1; } static constexpr std::string_view GetSchema() { return "uint8 value"; } @@ -83,7 +83,7 @@ struct wpi::Struct { }; template <> -struct wpi::Struct { +struct wpi::util::Struct { static constexpr std::string_view GetTypeName(const Info1&) { return "ThingC"; } @@ -100,7 +100,7 @@ struct wpi::Struct { }; template <> -struct wpi::Struct { +struct wpi::util::Struct { static constexpr std::string_view GetTypeName(const Info2&) { return "ThingC"; } @@ -116,23 +116,23 @@ struct wpi::Struct { } }; -static_assert(wpi::StructSerializable); -static_assert(!wpi::StructSerializable); +static_assert(wpi::util::StructSerializable); +static_assert(!wpi::util::StructSerializable); -static_assert(!wpi::StructSerializable); -static_assert(wpi::StructSerializable); -static_assert(!wpi::StructSerializable); +static_assert(!wpi::util::StructSerializable); +static_assert(wpi::util::StructSerializable); +static_assert(!wpi::util::StructSerializable); -static_assert(wpi::StructSerializable); -static_assert(wpi::StructSerializable); -static_assert(wpi::StructSerializable); +static_assert(wpi::util::StructSerializable); +static_assert(wpi::util::StructSerializable); +static_assert(wpi::util::StructSerializable); class DataLogTest : public ::testing::Test { public: - wpi::Logger msglog; + wpi::util::Logger msglog; std::vector data; wpi::log::DataLogWriter log{msglog, - std::make_unique(data)}; + std::make_unique(data)}; }; TEST_F(DataLogTest, SimpleInt) { diff --git a/developerRobot/src/main/native/cpp/Robot.cpp b/developerRobot/src/main/native/cpp/Robot.cpp index 04aa000469..02be50714f 100644 --- a/developerRobot/src/main/native/cpp/Robot.cpp +++ b/developerRobot/src/main/native/cpp/Robot.cpp @@ -4,7 +4,7 @@ #include "wpi/opmode/TimedRobot.hpp" -class Robot : public frc::TimedRobot { +class Robot : public wpi::TimedRobot { public: /** * This function is run when the robot is first started up and should be @@ -44,5 +44,5 @@ class Robot : public frc::TimedRobot { }; int main() { - return frc::StartRobot(); + return wpi::StartRobot(); } diff --git a/fields/src/main/native/cpp/fields.cpp b/fields/src/main/native/cpp/fields.cpp index 71207daf0c..84f91cc468 100644 --- a/fields/src/main/native/cpp/fields.cpp +++ b/fields/src/main/native/cpp/fields.cpp @@ -18,7 +18,7 @@ #include "wpi/fields/2024-crescendo.hpp" #include "wpi/fields/2025-reefscape.hpp" -using namespace fields; +using namespace wpi::fields; static const Field kFields[] = { {"2025 Reefscape", GetResource_2025_reefscape_json, @@ -49,6 +49,6 @@ static const Field kFields[] = { GetResource_2018_field_jpg}, }; -std::span fields::GetFields() { +std::span wpi::fields::GetFields() { return kFields; } diff --git a/fields/src/main/native/include/wpi/fields/2018-powerup.hpp b/fields/src/main/native/include/wpi/fields/2018-powerup.hpp index 1f5b316c13..d909ad34e1 100644 --- a/fields/src/main/native/include/wpi/fields/2018-powerup.hpp +++ b/fields/src/main/native/include/wpi/fields/2018-powerup.hpp @@ -6,7 +6,7 @@ #include -namespace fields { +namespace wpi::fields { std::string_view GetResource_2018_powerup_json(); std::string_view GetResource_2018_field_jpg(); -} // namespace fields +} // namespace wpi::fields diff --git a/fields/src/main/native/include/wpi/fields/2019-deepspace.hpp b/fields/src/main/native/include/wpi/fields/2019-deepspace.hpp index 8d008d024d..b21b8c9f52 100644 --- a/fields/src/main/native/include/wpi/fields/2019-deepspace.hpp +++ b/fields/src/main/native/include/wpi/fields/2019-deepspace.hpp @@ -6,7 +6,7 @@ #include -namespace fields { +namespace wpi::fields { std::string_view GetResource_2019_deepspace_json(); std::string_view GetResource_2019_field_jpg(); -} // namespace fields +} // namespace wpi::fields diff --git a/fields/src/main/native/include/wpi/fields/2020-infiniterecharge.hpp b/fields/src/main/native/include/wpi/fields/2020-infiniterecharge.hpp index 7d9a30cfb7..622a27f7c2 100644 --- a/fields/src/main/native/include/wpi/fields/2020-infiniterecharge.hpp +++ b/fields/src/main/native/include/wpi/fields/2020-infiniterecharge.hpp @@ -6,7 +6,7 @@ #include -namespace fields { +namespace wpi::fields { std::string_view GetResource_2020_infiniterecharge_json(); std::string_view GetResource_2020_field_png(); -} // namespace fields +} // namespace wpi::fields diff --git a/fields/src/main/native/include/wpi/fields/2021-barrel.hpp b/fields/src/main/native/include/wpi/fields/2021-barrel.hpp index 8f5ba1c6f1..bb8e0b2e90 100644 --- a/fields/src/main/native/include/wpi/fields/2021-barrel.hpp +++ b/fields/src/main/native/include/wpi/fields/2021-barrel.hpp @@ -6,7 +6,7 @@ #include -namespace fields { +namespace wpi::fields { std::string_view GetResource_2021_barrelracingpath_json(); std::string_view GetResource_2021_barrel_png(); -} // namespace fields +} // namespace wpi::fields diff --git a/fields/src/main/native/include/wpi/fields/2021-bounce.hpp b/fields/src/main/native/include/wpi/fields/2021-bounce.hpp index 66207fd8ce..1d2fc19141 100644 --- a/fields/src/main/native/include/wpi/fields/2021-bounce.hpp +++ b/fields/src/main/native/include/wpi/fields/2021-bounce.hpp @@ -6,7 +6,7 @@ #include -namespace fields { +namespace wpi::fields { std::string_view GetResource_2021_bouncepath_json(); std::string_view GetResource_2021_bounce_png(); -} // namespace fields +} // namespace wpi::fields diff --git a/fields/src/main/native/include/wpi/fields/2021-galacticsearcha.hpp b/fields/src/main/native/include/wpi/fields/2021-galacticsearcha.hpp index df74800ec2..813f8145ba 100644 --- a/fields/src/main/native/include/wpi/fields/2021-galacticsearcha.hpp +++ b/fields/src/main/native/include/wpi/fields/2021-galacticsearcha.hpp @@ -6,7 +6,7 @@ #include -namespace fields { +namespace wpi::fields { std::string_view GetResource_2021_galacticsearcha_json(); std::string_view GetResource_2021_galacticsearcha_png(); -} // namespace fields +} // namespace wpi::fields diff --git a/fields/src/main/native/include/wpi/fields/2021-galacticsearchb.hpp b/fields/src/main/native/include/wpi/fields/2021-galacticsearchb.hpp index cbf62311a5..61943184cd 100644 --- a/fields/src/main/native/include/wpi/fields/2021-galacticsearchb.hpp +++ b/fields/src/main/native/include/wpi/fields/2021-galacticsearchb.hpp @@ -6,7 +6,7 @@ #include -namespace fields { +namespace wpi::fields { std::string_view GetResource_2021_galacticsearchb_json(); std::string_view GetResource_2021_galacticsearchb_png(); -} // namespace fields +} // namespace wpi::fields diff --git a/fields/src/main/native/include/wpi/fields/2021-infiniterecharge.hpp b/fields/src/main/native/include/wpi/fields/2021-infiniterecharge.hpp index 10ca6585f1..62651a8ae8 100644 --- a/fields/src/main/native/include/wpi/fields/2021-infiniterecharge.hpp +++ b/fields/src/main/native/include/wpi/fields/2021-infiniterecharge.hpp @@ -6,7 +6,7 @@ #include -namespace fields { +namespace wpi::fields { std::string_view GetResource_2021_field_png(); std::string_view GetResource_2021_infiniterecharge_json(); -} // namespace fields +} // namespace wpi::fields diff --git a/fields/src/main/native/include/wpi/fields/2021-slalom.hpp b/fields/src/main/native/include/wpi/fields/2021-slalom.hpp index a660f1bbeb..704072883e 100644 --- a/fields/src/main/native/include/wpi/fields/2021-slalom.hpp +++ b/fields/src/main/native/include/wpi/fields/2021-slalom.hpp @@ -6,7 +6,7 @@ #include -namespace fields { +namespace wpi::fields { std::string_view GetResource_2021_slalompath_json(); std::string_view GetResource_2021_slalom_png(); -} // namespace fields +} // namespace wpi::fields diff --git a/fields/src/main/native/include/wpi/fields/2022-rapidreact.hpp b/fields/src/main/native/include/wpi/fields/2022-rapidreact.hpp index aa4995ce91..6bfe12c9ce 100644 --- a/fields/src/main/native/include/wpi/fields/2022-rapidreact.hpp +++ b/fields/src/main/native/include/wpi/fields/2022-rapidreact.hpp @@ -6,7 +6,7 @@ #include -namespace fields { +namespace wpi::fields { std::string_view GetResource_2022_rapidreact_json(); std::string_view GetResource_2022_field_png(); -} // namespace fields +} // namespace wpi::fields diff --git a/fields/src/main/native/include/wpi/fields/2023-chargedup.hpp b/fields/src/main/native/include/wpi/fields/2023-chargedup.hpp index 54663c5046..674480a794 100644 --- a/fields/src/main/native/include/wpi/fields/2023-chargedup.hpp +++ b/fields/src/main/native/include/wpi/fields/2023-chargedup.hpp @@ -6,7 +6,7 @@ #include -namespace fields { +namespace wpi::fields { std::string_view GetResource_2023_chargedup_json(); std::string_view GetResource_2023_field_png(); -} // namespace fields +} // namespace wpi::fields diff --git a/fields/src/main/native/include/wpi/fields/2024-crescendo.hpp b/fields/src/main/native/include/wpi/fields/2024-crescendo.hpp index 11947efa5e..2b3f8c487b 100644 --- a/fields/src/main/native/include/wpi/fields/2024-crescendo.hpp +++ b/fields/src/main/native/include/wpi/fields/2024-crescendo.hpp @@ -6,7 +6,7 @@ #include -namespace fields { +namespace wpi::fields { std::string_view GetResource_2024_crescendo_json(); std::string_view GetResource_2024_field_png(); -} // namespace fields +} // namespace wpi::fields diff --git a/fields/src/main/native/include/wpi/fields/2025-reefscape.hpp b/fields/src/main/native/include/wpi/fields/2025-reefscape.hpp index ada49b88a6..f73e0924f9 100644 --- a/fields/src/main/native/include/wpi/fields/2025-reefscape.hpp +++ b/fields/src/main/native/include/wpi/fields/2025-reefscape.hpp @@ -6,7 +6,7 @@ #include -namespace fields { +namespace wpi::fields { std::string_view GetResource_2025_reefscape_json(); std::string_view GetResource_2025_field_png(); -} // namespace fields +} // namespace wpi::fields diff --git a/fields/src/main/native/include/wpi/fields/fields.hpp b/fields/src/main/native/include/wpi/fields/fields.hpp index ea6b23e6f6..b09b485744 100644 --- a/fields/src/main/native/include/wpi/fields/fields.hpp +++ b/fields/src/main/native/include/wpi/fields/fields.hpp @@ -7,7 +7,7 @@ #include #include -namespace fields { +namespace wpi::fields { struct Field { const char* name; @@ -17,4 +17,4 @@ struct Field { std::span GetFields(); -} // namespace fields +} // namespace wpi::fields diff --git a/glass/src/app/native/cpp/camerasupport.cpp b/glass/src/app/native/cpp/camerasupport.cpp index 397d51e7af..1c284a1438 100644 --- a/glass/src/app/native/cpp/camerasupport.cpp +++ b/glass/src/app/native/cpp/camerasupport.cpp @@ -30,7 +30,7 @@ static bool TryDelayLoadAllImports(LPCSTR szDll) { } return true; } -namespace glass { +namespace wpi::glass { bool HasCameraSupport() { bool hasCameraSupport = false; hasCameraSupport = TryDelayLoadAllImports("MF.dll"); @@ -42,11 +42,11 @@ bool HasCameraSupport() { } return hasCameraSupport; } -} // namespace glass +} // namespace wpi::glass #else -namespace glass { +namespace wpi::glass { bool HasCameraSupport() { return true; } -} // namespace glass +} // namespace wpi::glass #endif diff --git a/glass/src/app/native/cpp/camerasupport.hpp b/glass/src/app/native/cpp/camerasupport.hpp index 0be62c73ba..007412f121 100644 --- a/glass/src/app/native/cpp/camerasupport.hpp +++ b/glass/src/app/native/cpp/camerasupport.hpp @@ -4,6 +4,6 @@ #pragma once -namespace glass { +namespace wpi::glass { bool HasCameraSupport(); -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/app/native/cpp/main.cpp b/glass/src/app/native/cpp/main.cpp index 03a439b3bb..aceaa81b6a 100644 --- a/glass/src/app/native/cpp/main.cpp +++ b/glass/src/app/native/cpp/main.cpp @@ -27,7 +27,7 @@ namespace gui = wpi::gui; const char* GetWPILibVersion(); -namespace glass { +namespace wpi::glass { std::string_view GetResource_glass_16_png(); std::string_view GetResource_glass_32_png(); std::string_view GetResource_glass_48_png(); @@ -35,20 +35,20 @@ std::string_view GetResource_glass_64_png(); std::string_view GetResource_glass_128_png(); std::string_view GetResource_glass_256_png(); std::string_view GetResource_glass_512_png(); -} // namespace glass +} // namespace wpi::glass -static std::unique_ptr gPlotProvider; -static std::unique_ptr gNtProvider; +static std::unique_ptr gPlotProvider; +static std::unique_ptr gNtProvider; -static std::unique_ptr gNetworkTablesModel; -static std::unique_ptr gNetworkTablesSettings; -static glass::LogData gNetworkTablesLog; -static std::unique_ptr gNetworkTablesWindow; -static std::unique_ptr gNetworkTablesInfoWindow; -static std::unique_ptr gNetworkTablesSettingsWindow; -static std::unique_ptr gNetworkTablesLogWindow; +static std::unique_ptr gNetworkTablesModel; +static std::unique_ptr gNetworkTablesSettings; +static wpi::glass::LogData gNetworkTablesLog; +static std::unique_ptr gNetworkTablesWindow; +static std::unique_ptr gNetworkTablesInfoWindow; +static std::unique_ptr gNetworkTablesSettingsWindow; +static std::unique_ptr gNetworkTablesLogWindow; -static glass::MainMenuBar gMainMenu; +static wpi::glass::MainMenuBar gMainMenu; static bool gAbout = false; static bool gSetEnterKey = false; static bool gKeyEdit = false; @@ -77,10 +77,10 @@ static void RemapEnterKeyCallback(GLFWwindow* window, int key, int scancode, * Generates the proper title bar title based on current instance state and * event. */ -static std::string MakeTitle(NT_Inst inst, nt::Event event) { - auto mode = nt::GetNetworkMode(inst); +static std::string MakeTitle(NT_Inst inst, wpi::nt::Event event) { + auto mode = wpi::nt::GetNetworkMode(inst); if (mode & NT_NET_MODE_SERVER) { - auto numClients = nt::GetConnections(inst).size(); + auto numClients = wpi::nt::GetConnections(inst).size(); return fmt::format("Glass - {} Client{} Connected", numClients, (numClients == 1 ? "" : "s")); } else if (mode & NT_NET_MODE_CLIENT) { @@ -93,23 +93,23 @@ static std::string MakeTitle(NT_Inst inst, nt::Event event) { } static void NtInitialize() { - auto inst = nt::GetDefaultInstance(); - auto poller = nt::CreateListenerPoller(inst); - nt::AddPolledListener(poller, inst, NT_EVENT_CONNECTION | NT_EVENT_IMMEDIATE); - nt::AddPolledLogger(poller, NT_LOG_INFO, 100); + auto inst = wpi::nt::GetDefaultInstance(); + auto poller = wpi::nt::CreateListenerPoller(inst); + wpi::nt::AddPolledListener(poller, inst, NT_EVENT_CONNECTION | NT_EVENT_IMMEDIATE); + wpi::nt::AddPolledLogger(poller, NT_LOG_INFO, 100); gui::AddEarlyExecute([inst, poller] { auto win = gui::GetSystemWindow(); if (!win) { return; } bool updateTitle = false; - nt::Event connectionEvent; - if (nt::GetNetworkMode(inst) != gPrevMode) { - gPrevMode = nt::GetNetworkMode(inst); + wpi::nt::Event connectionEvent; + if (wpi::nt::GetNetworkMode(inst) != gPrevMode) { + gPrevMode = wpi::nt::GetNetworkMode(inst); updateTitle = true; } - for (auto&& event : nt::ReadListenerQueue(poller)) { + for (auto&& event : wpi::nt::ReadListenerQueue(poller)) { if (event.Is(NT_EVENT_CONNECTION)) { updateTitle = true; connectionEvent = event; @@ -134,51 +134,51 @@ static void NtInitialize() { } }); - gNetworkTablesLogWindow = std::make_unique( - glass::GetStorageRoot().GetChild("NetworkTables Log"), - "NetworkTables Log", glass::Window::kHide); + gNetworkTablesLogWindow = std::make_unique( + wpi::glass::GetStorageRoot().GetChild("NetworkTables Log"), + "NetworkTables Log", wpi::glass::Window::kHide); gNetworkTablesLogWindow->SetView( - std::make_unique(&gNetworkTablesLog)); + std::make_unique(&gNetworkTablesLog)); gNetworkTablesLogWindow->SetDefaultPos(250, 615); gNetworkTablesLogWindow->SetDefaultSize(600, 130); gNetworkTablesLogWindow->DisableRenamePopup(); gui::AddLateExecute([] { gNetworkTablesLogWindow->Display(); }); // NetworkTables table window - gNetworkTablesModel = std::make_unique(); + gNetworkTablesModel = std::make_unique(); gui::AddEarlyExecute([] { gNetworkTablesModel->Update(); }); - gNetworkTablesWindow = std::make_unique( - glass::GetStorageRoot().GetChild("NetworkTables View"), "NetworkTables"); + gNetworkTablesWindow = std::make_unique( + wpi::glass::GetStorageRoot().GetChild("NetworkTables View"), "NetworkTables"); gNetworkTablesWindow->SetView( - std::make_unique(gNetworkTablesModel.get())); + std::make_unique(gNetworkTablesModel.get())); gNetworkTablesWindow->SetDefaultPos(250, 277); gNetworkTablesWindow->SetDefaultSize(750, 185); gNetworkTablesWindow->DisableRenamePopup(); gui::AddLateExecute([] { gNetworkTablesWindow->Display(); }); // NetworkTables info window - gNetworkTablesInfoWindow = std::make_unique( - glass::GetStorageRoot().GetChild("NetworkTables Info"), + gNetworkTablesInfoWindow = std::make_unique( + wpi::glass::GetStorageRoot().GetChild("NetworkTables Info"), "NetworkTables Info"); - gNetworkTablesInfoWindow->SetView(glass::MakeFunctionView( - [&] { glass::DisplayNetworkTablesInfo(gNetworkTablesModel.get()); })); + gNetworkTablesInfoWindow->SetView(wpi::glass::MakeFunctionView( + [&] { wpi::glass::DisplayNetworkTablesInfo(gNetworkTablesModel.get()); })); gNetworkTablesInfoWindow->SetDefaultPos(250, 130); gNetworkTablesInfoWindow->SetDefaultSize(750, 145); - gNetworkTablesInfoWindow->SetDefaultVisibility(glass::Window::kHide); + gNetworkTablesInfoWindow->SetDefaultVisibility(wpi::glass::Window::kHide); gNetworkTablesInfoWindow->DisableRenamePopup(); gui::AddLateExecute([] { gNetworkTablesInfoWindow->Display(); }); // NetworkTables settings window - gNetworkTablesSettings = std::make_unique( - "glass", glass::GetStorageRoot().GetChild("NetworkTables Settings")); + gNetworkTablesSettings = std::make_unique( + "glass", wpi::glass::GetStorageRoot().GetChild("NetworkTables Settings")); gui::AddEarlyExecute([] { gNetworkTablesSettings->Update(); }); - gNetworkTablesSettingsWindow = std::make_unique( - glass::GetStorageRoot().GetChild("NetworkTables Settings"), + gNetworkTablesSettingsWindow = std::make_unique( + wpi::glass::GetStorageRoot().GetChild("NetworkTables Settings"), "NetworkTables Settings"); gNetworkTablesSettingsWindow->SetView( - glass::MakeFunctionView([] { gNetworkTablesSettings->Display(); })); + wpi::glass::MakeFunctionView([] { gNetworkTablesSettings->Display(); })); gNetworkTablesSettingsWindow->SetDefaultPos(30, 30); gNetworkTablesSettingsWindow->SetFlags(ImGuiWindowFlags_AlwaysAutoResize); gNetworkTablesSettingsWindow->DisableRenamePopup(); @@ -206,35 +206,35 @@ int main(int argc, char** argv) { } gui::CreateContext(); - glass::CreateContext(); + wpi::glass::CreateContext(); - gui::AddIcon(glass::GetResource_glass_16_png()); - gui::AddIcon(glass::GetResource_glass_32_png()); - gui::AddIcon(glass::GetResource_glass_48_png()); - gui::AddIcon(glass::GetResource_glass_64_png()); - gui::AddIcon(glass::GetResource_glass_128_png()); - gui::AddIcon(glass::GetResource_glass_256_png()); - gui::AddIcon(glass::GetResource_glass_512_png()); + gui::AddIcon(wpi::glass::GetResource_glass_16_png()); + gui::AddIcon(wpi::glass::GetResource_glass_32_png()); + gui::AddIcon(wpi::glass::GetResource_glass_48_png()); + gui::AddIcon(wpi::glass::GetResource_glass_64_png()); + gui::AddIcon(wpi::glass::GetResource_glass_128_png()); + gui::AddIcon(wpi::glass::GetResource_glass_256_png()); + gui::AddIcon(wpi::glass::GetResource_glass_512_png()); gui::AddEarlyExecute( [] { ImGui::DockSpaceOverViewport(ImGui::GetMainViewport()); }); gui::AddInit([] { ImGui::GetIO().ConfigDockingWithShift = true; }); - gPlotProvider = std::make_unique( - glass::GetStorageRoot().GetChild("Plots")); - gNtProvider = std::make_unique( - glass::GetStorageRoot().GetChild("NetworkTables")); + gPlotProvider = std::make_unique( + wpi::glass::GetStorageRoot().GetChild("Plots")); + gNtProvider = std::make_unique( + wpi::glass::GetStorageRoot().GetChild("NetworkTables")); - glass::SetStorageName("glass"); - glass::SetStorageDir(saveDir.empty() ? gui::GetPlatformSaveFileDir() + wpi::glass::SetStorageName("glass"); + wpi::glass::SetStorageDir(saveDir.empty() ? gui::GetPlatformSaveFileDir() : saveDir); gPlotProvider->GlobalInit(); - gui::AddInit([] { glass::ResetTime(); }); + gui::AddInit([] { wpi::glass::ResetTime(); }); gNtProvider->GlobalInit(); NtInitialize(); - glass::AddStandardNetworkTablesViews(*gNtProvider); + wpi::glass::AddStandardNetworkTablesViews(*gNtProvider); gui::AddLateExecute([] { gMainMenu.Display(); }); @@ -244,7 +244,7 @@ int main(int argc, char** argv) { gSetEnterKey = true; } if (ImGui::MenuItem("Reset Time")) { - glass::ResetTime(); + wpi::glass::ResetTime(); } ImGui::EndMenu(); } @@ -304,7 +304,7 @@ int main(int argc, char** argv) { ImGui::Separator(); ImGui::Text("v%s", GetWPILibVersion()); ImGui::Separator(); - ImGui::Text("Save location: %s", glass::GetStorageDir().c_str()); + ImGui::Text("Save location: %s", wpi::glass::GetStorageDir().c_str()); ImGui::Text("%.3f ms/frame (%.1f FPS)", 1000.0f / ImGui::GetIO().Framerate, ImGui::GetIO().Framerate); if (ImGui::Button("Close")) { @@ -328,11 +328,11 @@ int main(int argc, char** argv) { char nameBuf[32]; const char* name = glfwGetKeyName(*gEnterKey, 0); if (!name) { - wpi::format_to_n_c_str(nameBuf, sizeof(nameBuf), "{}", *gEnterKey); + wpi::util::format_to_n_c_str(nameBuf, sizeof(nameBuf), "{}", *gEnterKey); name = nameBuf; } - wpi::format_to_n_c_str(editLabel, sizeof(editLabel), "{}###edit", + wpi::util::format_to_n_c_str(editLabel, sizeof(editLabel), "{}###edit", gKeyEdit ? "(press key)" : name); if (ImGui::SmallButton(editLabel)) { @@ -353,7 +353,7 @@ int main(int argc, char** argv) { gui::Initialize("Glass - DISCONNECTED", 1024, 768, ImGuiConfigFlags_DockingEnable); - gEnterKey = &glass::GetStorageRoot().GetInt("enterKey", GLFW_KEY_ENTER); + gEnterKey = &wpi::glass::GetStorageRoot().GetInt("enterKey", GLFW_KEY_ENTER); if (auto win = gui::GetSystemWindow()) { gPrevKeyCallback = glfwSetKeyCallback(win, RemapEnterKeyCallback); } @@ -366,7 +366,7 @@ int main(int argc, char** argv) { gNtProvider.reset(); gPlotProvider.reset(); - glass::DestroyContext(); + wpi::glass::DestroyContext(); gui::DestroyContext(); return 0; diff --git a/glass/src/lib/native/cpp/Context.cpp b/glass/src/lib/native/cpp/Context.cpp index 60c8545617..dcfa9dc345 100644 --- a/glass/src/lib/native/cpp/Context.cpp +++ b/glass/src/lib/native/cpp/Context.cpp @@ -24,9 +24,9 @@ #include "wpi/util/raw_ostream.hpp" #include "wpi/util/timestamp.h" -using namespace glass; +using namespace wpi::glass; -Context* glass::gContext; +Context* wpi::glass::gContext; static void WorkspaceResetImpl() { // call reset functions @@ -57,7 +57,7 @@ static void WorkspaceInit() { } } -static bool JsonToWindow(const wpi::json& jfile, const char* filename) { +static bool JsonToWindow(const wpi::util::json& jfile, const char* filename) { if (!jfile.is_object()) { ImGui::LogText("%s top level is not object", filename); return false; @@ -65,7 +65,7 @@ static bool JsonToWindow(const wpi::json& jfile, const char* filename) { // loop over JSON and generate ini format std::string iniStr; - wpi::raw_string_ostream ini{iniStr}; + wpi::util::raw_string_ostream ini{iniStr}; for (auto&& jsection : jfile.items()) { if (jsection.key() == "Docking") { @@ -87,7 +87,7 @@ static bool JsonToWindow(const wpi::json& jfile, const char* filename) { try { auto& value = jkv.value().get_ref(); ini << jkv.key() << '=' << value << "\n"; - } catch (wpi::json::exception&) { + } catch (wpi::util::json::exception&) { ImGui::LogText("%s section %s subsection %s value %s is not string", filename, jsection.key().c_str(), jsubsection.key().c_str(), jkv.key().c_str()); @@ -112,7 +112,7 @@ static bool JsonToWindow(const wpi::json& jfile, const char* filename) { try { auto& value = jv.get_ref(); ini << value << "\n"; - } catch (wpi::json::exception&) { + } catch (wpi::util::json::exception&) { ImGui::LogText("%s section %s subsection %s value is not string", filename, "Docking", jsubsection.key().c_str()); return false; @@ -129,16 +129,16 @@ static bool JsonToWindow(const wpi::json& jfile, const char* filename) { } static bool LoadWindowStorageImpl(const std::string& filename) { - auto fileBuffer = wpi::MemoryBuffer::GetFile(filename); + auto fileBuffer = wpi::util::MemoryBuffer::GetFile(filename); if (!fileBuffer) { ImGui::LogText("error opening %s: %s", filename.c_str(), fileBuffer.error().message().c_str()); return false; } try { - return JsonToWindow(wpi::json::parse(fileBuffer.value()->GetCharBuffer()), + return JsonToWindow(wpi::util::json::parse(fileBuffer.value()->GetCharBuffer()), filename.c_str()); - } catch (wpi::json::parse_error& e) { + } catch (wpi::util::json::parse_error& e) { ImGui::LogText("Error loading %s: %s", filename.c_str(), e.what()); return false; } @@ -146,7 +146,7 @@ static bool LoadWindowStorageImpl(const std::string& filename) { static bool LoadStorageRootImpl(Context* ctx, const std::string& filename, std::string_view rootName) { - auto fileBuffer = wpi::MemoryBuffer::GetFile(filename); + auto fileBuffer = wpi::util::MemoryBuffer::GetFile(filename); if (!fileBuffer) { ImGui::LogText("error opening %s: %s", filename.c_str(), fileBuffer.error().message().c_str()); @@ -154,9 +154,9 @@ static bool LoadStorageRootImpl(Context* ctx, const std::string& filename, } auto [it, createdStorage] = ctx->storageRoots.try_emplace(rootName); try { - it->second.FromJson(wpi::json::parse(fileBuffer.value()->GetCharBuffer()), + it->second.FromJson(wpi::util::json::parse(fileBuffer.value()->GetCharBuffer()), filename.c_str()); - } catch (wpi::json::parse_error& e) { + } catch (wpi::util::json::parse_error& e) { ImGui::LogText("Error loading %s: %s", filename.c_str(), e.what()); if (createdStorage) { ctx->storageRoots.erase(it); @@ -187,7 +187,7 @@ static bool LoadStorageImpl(Context* ctx, std::string_view dir, return rv; } -static wpi::json WindowToJson() { +static wpi::util::json WindowToJson() { size_t iniLen; const char* iniData = ImGui::SaveIniSettingsToMemory(&iniLen); std::string_view ini{iniData, iniLen}; @@ -202,30 +202,30 @@ static wpi::json WindowToJson() { // } // } - wpi::json out = wpi::json::object(); - wpi::json* curSection = nullptr; + wpi::util::json out = wpi::util::json::object(); + wpi::util::json* curSection = nullptr; while (!ini.empty()) { std::string_view line; - std::tie(line, ini) = wpi::split(ini, '\n'); - line = wpi::trim(line); + std::tie(line, ini) = wpi::util::split(ini, '\n'); + line = wpi::util::trim(line); if (line.empty()) { continue; } if (line[0] == '[') { // new section - auto [section, subsection] = wpi::split(line, ']'); - section = wpi::drop_front(section); // drop '['; ']' was dropped by split - subsection = wpi::drop_back(wpi::drop_front(subsection)); // drop [] + auto [section, subsection] = wpi::util::split(line, ']'); + section = wpi::util::drop_front(section); // drop '['; ']' was dropped by split + subsection = wpi::util::drop_back(wpi::util::drop_front(subsection)); // drop [] auto& jsection = out[section]; if (jsection.is_null()) { - jsection = wpi::json::object(); + jsection = wpi::util::json::object(); } curSection = &jsection[subsection]; if (curSection->is_null()) { if (section == "Docking") { - *curSection = wpi::json::array(); + *curSection = wpi::util::json::array(); } else { - *curSection = wpi::json::object(); + *curSection = wpi::util::json::object(); } } } else { @@ -233,7 +233,7 @@ static wpi::json WindowToJson() { if (!curSection) { continue; // shouldn't happen, but just in case } - auto [name, value] = wpi::split(line, '='); + auto [name, value] = wpi::util::split(line, '='); if (curSection->is_object()) { (*curSection)[name] = value; } else if (curSection->is_array()) { @@ -247,7 +247,7 @@ static wpi::json WindowToJson() { bool SaveWindowStorageImpl(const std::string& filename) { std::error_code ec; - wpi::raw_fd_ostream os{filename, ec}; + wpi::util::raw_fd_ostream os{filename, ec}; if (ec) { ImGui::LogText("error opening %s: %s", filename.c_str(), ec.message().c_str()); @@ -261,7 +261,7 @@ bool SaveWindowStorageImpl(const std::string& filename) { static bool SaveStorageRootImpl(Context* ctx, const std::string& filename, const Storage& storage) { std::error_code ec; - wpi::raw_fd_ostream os{filename, ec}; + wpi::util::raw_fd_ostream os{filename, ec}; if (ec) { ImGui::LogText("error opening %s: %s", filename.c_str(), ec.message().c_str()); @@ -335,7 +335,7 @@ Context::~Context() { wpi::gui::ConfigureCustomSaveSettings(nullptr, nullptr, nullptr); } -Context* glass::CreateContext() { +Context* wpi::glass::CreateContext() { Context* ctx = new Context; if (!gContext) { SetCurrentContext(ctx); @@ -343,7 +343,7 @@ Context* glass::CreateContext() { return ctx; } -void glass::DestroyContext(Context* ctx) { +void wpi::glass::DestroyContext(Context* ctx) { if (!ctx) { ctx = gContext; } @@ -353,44 +353,44 @@ void glass::DestroyContext(Context* ctx) { delete ctx; } -Context* glass::GetCurrentContext() { +Context* wpi::glass::GetCurrentContext() { return gContext; } -void glass::SetCurrentContext(Context* ctx) { +void wpi::glass::SetCurrentContext(Context* ctx) { gContext = ctx; } -void glass::ResetTime() { - gContext->zeroTime = wpi::Now(); +void wpi::glass::ResetTime() { + gContext->zeroTime = wpi::util::Now(); } -uint64_t glass::GetZeroTime() { +uint64_t wpi::glass::GetZeroTime() { return gContext->zeroTime; } -void glass::WorkspaceReset() { +void wpi::glass::WorkspaceReset() { WorkspaceResetImpl(); WorkspaceInit(); } -void glass::AddWorkspaceInit(std::function init) { +void wpi::glass::AddWorkspaceInit(std::function init) { if (init) { gContext->workspaceInit.emplace_back(std::move(init)); } } -void glass::AddWorkspaceReset(std::function reset) { +void wpi::glass::AddWorkspaceReset(std::function reset) { if (reset) { gContext->workspaceReset.emplace_back(std::move(reset)); } } -void glass::SetStorageName(std::string_view name) { +void wpi::glass::SetStorageName(std::string_view name) { gContext->storageName = name; } -void glass::SetStorageDir(std::string_view dir) { +void wpi::glass::SetStorageDir(std::string_view dir) { if (dir.empty()) { gContext->storageLoadDir = "."; gContext->storageAutoSaveDir = "."; @@ -401,11 +401,11 @@ void glass::SetStorageDir(std::string_view dir) { } } -std::string glass::GetStorageDir() { +std::string wpi::glass::GetStorageDir() { return gContext->storageAutoSaveDir; } -bool glass::LoadStorage(std::string_view dir) { +bool wpi::glass::LoadStorage(std::string_view dir) { SaveStorage(); SetStorageDir(dir); WorkspaceResetImpl(); @@ -415,24 +415,24 @@ bool glass::LoadStorage(std::string_view dir) { return LoadStorageImpl(gContext, dir, gContext->storageName); } -bool glass::SaveStorage() { +bool wpi::glass::SaveStorage() { return SaveStorageImpl(gContext, gContext->storageAutoSaveDir, gContext->storageName, false); } -bool glass::SaveStorage(std::string_view dir) { +bool wpi::glass::SaveStorage(std::string_view dir) { return SaveStorageImpl(gContext, dir, gContext->storageName, false); } -Storage& glass::GetCurStorageRoot() { +Storage& wpi::glass::GetCurStorageRoot() { return *gContext->storageStack.front(); } -Storage& glass::GetStorageRoot(std::string_view rootName) { +Storage& wpi::glass::GetStorageRoot(std::string_view rootName) { return gContext->storageRoots[rootName]; } -void glass::ResetStorageStack(std::string_view rootName) { +void wpi::glass::ResetStorageStack(std::string_view rootName) { if (gContext->storageStack.size() != 1) { ImGui::LogText("resetting non-empty storage stack"); } @@ -440,20 +440,20 @@ void glass::ResetStorageStack(std::string_view rootName) { gContext->storageStack.emplace_back(&GetStorageRoot(rootName)); } -Storage& glass::GetStorage() { +Storage& wpi::glass::GetStorage() { return *gContext->storageStack.back(); } -void glass::PushStorageStack(std::string_view label_id) { +void wpi::glass::PushStorageStack(std::string_view label_id) { gContext->storageStack.emplace_back( &gContext->storageStack.back()->GetChild(label_id)); } -void glass::PushStorageStack(Storage& storage) { +void wpi::glass::PushStorageStack(Storage& storage) { gContext->storageStack.emplace_back(&storage); } -void glass::PopStorageStack() { +void wpi::glass::PopStorageStack() { if (gContext->storageStack.size() <= 1) { ImGui::LogText("attempted to pop empty storage stack, mismatch push/pop?"); return; // ignore @@ -461,28 +461,28 @@ void glass::PopStorageStack() { gContext->storageStack.pop_back(); } -bool glass::Begin(const char* name, bool* p_open, ImGuiWindowFlags flags) { +bool wpi::glass::Begin(const char* name, bool* p_open, ImGuiWindowFlags flags) { PushStorageStack(name); return ImGui::Begin(name, p_open, flags); } -void glass::End() { +void wpi::glass::End() { ImGui::End(); PopStorageStack(); } -bool glass::BeginChild(const char* str_id, const ImVec2& size, bool border, +bool wpi::glass::BeginChild(const char* str_id, const ImVec2& size, bool border, ImGuiWindowFlags flags) { PushStorageStack(str_id); return ImGui::BeginChild(str_id, size, border, flags); } -void glass::EndChild() { +void wpi::glass::EndChild() { ImGui::EndChild(); PopStorageStack(); } -bool glass::CollapsingHeader(const char* label, ImGuiTreeNodeFlags flags) { +bool wpi::glass::CollapsingHeader(const char* label, ImGuiTreeNodeFlags flags) { bool& open = GetStorage().GetChild(label).GetBool( "open", (flags & ImGuiTreeNodeFlags_DefaultOpen) != 0); ImGui::SetNextItemOpen(open); @@ -490,7 +490,7 @@ bool glass::CollapsingHeader(const char* label, ImGuiTreeNodeFlags flags) { return open; } -bool glass::TreeNodeEx(const char* label, ImGuiTreeNodeFlags flags) { +bool wpi::glass::TreeNodeEx(const char* label, ImGuiTreeNodeFlags flags) { PushStorageStack(label); bool& open = GetStorage().GetBool( "open", (flags & ImGuiTreeNodeFlags_DefaultOpen) != 0); @@ -502,35 +502,35 @@ bool glass::TreeNodeEx(const char* label, ImGuiTreeNodeFlags flags) { return open; } -void glass::TreePop() { +void wpi::glass::TreePop() { ImGui::TreePop(); PopStorageStack(); } -void glass::PushID(const char* str_id) { +void wpi::glass::PushID(const char* str_id) { PushStorageStack(str_id); ImGui::PushID(str_id); } -void glass::PushID(const char* str_id_begin, const char* str_id_end) { +void wpi::glass::PushID(const char* str_id_begin, const char* str_id_end) { PushStorageStack(std::string_view(str_id_begin, str_id_end - str_id_begin)); ImGui::PushID(str_id_begin, str_id_end); } -void glass::PushID(int int_id) { +void wpi::glass::PushID(int int_id) { char buf[16]; - wpi::format_to_n_c_str(buf, sizeof(buf), "{}", int_id); + wpi::util::format_to_n_c_str(buf, sizeof(buf), "{}", int_id); PushStorageStack(buf); ImGui::PushID(int_id); } -void glass::PopID() { +void wpi::glass::PopID() { ImGui::PopID(); PopStorageStack(); } -bool glass::PopupEditName(const char* label, std::string* name) { +bool wpi::glass::PopupEditName(const char* label, std::string* name) { bool rv = false; if (ImGui::BeginPopupContextItem(label)) { rv = ItemEditName(name); @@ -540,7 +540,7 @@ bool glass::PopupEditName(const char* label, std::string* name) { return rv; } -bool glass::ItemEditName(std::string* name) { +bool wpi::glass::ItemEditName(std::string* name) { bool rv = false; ImGui::Text("Edit name:"); diff --git a/glass/src/lib/native/cpp/DataSource.cpp b/glass/src/lib/native/cpp/DataSource.cpp index 42dab210a0..133daa72e6 100644 --- a/glass/src/lib/native/cpp/DataSource.cpp +++ b/glass/src/lib/native/cpp/DataSource.cpp @@ -12,15 +12,15 @@ #include "wpi/glass/ContextInternal.hpp" -using namespace glass; +using namespace wpi::glass; -wpi::sig::Signal DataSource::sourceCreated; +wpi::util::sig::Signal DataSource::sourceCreated; -std::string glass::MakeSourceId(std::string_view id, int index) { +std::string wpi::glass::MakeSourceId(std::string_view id, int index) { return fmt::format("{}[{}]", id, index); } -std::string glass::MakeSourceId(std::string_view id, int index, int index2) { +std::string wpi::glass::MakeSourceId(std::string_view id, int index, int index2) { return fmt::format("{}[{},{}]", id, index, index2); } diff --git a/glass/src/lib/native/cpp/MainMenuBar.cpp b/glass/src/lib/native/cpp/MainMenuBar.cpp index 3ca982414a..ae870e8bdc 100644 --- a/glass/src/lib/native/cpp/MainMenuBar.cpp +++ b/glass/src/lib/native/cpp/MainMenuBar.cpp @@ -14,7 +14,7 @@ #include "wpi/gui/wpigui.hpp" #include "wpi/util/StringExtras.hpp" -using namespace glass; +using namespace wpi::glass; void MainMenuBar::AddMainMenu(std::function menu) { if (menu) { @@ -54,7 +54,7 @@ void MainMenuBar::Display() { #if 0 char str[64]; - wpi::format_to_n_c_str(str, sizeof(str), "{:.3f} ms/frame ({:.1f} FPS)", + wpi::util::format_to_n_c_str(str, sizeof(str), "{:.3f} ms/frame ({:.1f} FPS)", 1000.0f / ImGui::GetIO().Framerate, ImGui::GetIO().Framerate); diff --git a/glass/src/lib/native/cpp/Model.cpp b/glass/src/lib/native/cpp/Model.cpp index 28b57dd5e1..20f34c074d 100644 --- a/glass/src/lib/native/cpp/Model.cpp +++ b/glass/src/lib/native/cpp/Model.cpp @@ -4,7 +4,7 @@ #include "wpi/glass/Model.hpp" -using namespace glass; +using namespace wpi::glass; bool Model::IsReadOnly() { return false; diff --git a/glass/src/lib/native/cpp/Storage.cpp b/glass/src/lib/native/cpp/Storage.cpp index d37657622c..078db7bddb 100644 --- a/glass/src/lib/native/cpp/Storage.cpp +++ b/glass/src/lib/native/cpp/Storage.cpp @@ -15,7 +15,7 @@ #include "wpi/util/StringExtras.hpp" #include "wpi/util/json.hpp" -using namespace glass; +using namespace wpi::glass; template bool ConvertFromString(To* out, std::string_view str) { @@ -24,19 +24,19 @@ bool ConvertFromString(To* out, std::string_view str) { *out = true; } else if (str == "false") { *out = false; - } else if (auto val = wpi::parse_integer(str, 10)) { + } else if (auto val = wpi::util::parse_integer(str, 10)) { *out = val.value() != 0; } else { return false; } } else if constexpr (std::floating_point) { - if (auto val = wpi::parse_float(str)) { + if (auto val = wpi::util::parse_float(str)) { *out = val.value(); } else { return false; } } else { - if (auto val = wpi::parse_integer(str, 10)) { + if (auto val = wpi::util::parse_integer(str, 10)) { *out = val.value(); } else { return false; @@ -300,7 +300,7 @@ DEFUN(Double, double, double, double, double) DEFUN(String, string, std::string, std::string_view, std::string) Storage& Storage::GetChild(std::string_view label_id) { - auto [label, id] = wpi::split(label_id, "###"); + auto [label, id] = wpi::util::split(label_id, "###"); if (id.empty()) { id = label; } @@ -345,9 +345,9 @@ void Storage::EraseChildren() { }); } -static bool JsonArrayToStorage(Storage::Value* valuePtr, const wpi::json& jarr, +static bool JsonArrayToStorage(Storage::Value* valuePtr, const wpi::util::json& jarr, const char* filename) { - auto& arr = jarr.get_ref(); + auto& arr = jarr.get_ref(); if (arr.empty()) { ImGui::LogText("empty array in %s, ignoring", filename); return false; @@ -355,42 +355,42 @@ static bool JsonArrayToStorage(Storage::Value* valuePtr, const wpi::json& jarr, // guess array type from first element switch (arr[0].type()) { - case wpi::json::value_t::boolean: + case wpi::util::json::value_t::boolean: if (valuePtr->type != Storage::Value::kBoolArray) { valuePtr->Reset(Storage::Value::kBoolArray); valuePtr->boolArray = new std::vector(); valuePtr->boolArrayDefault = nullptr; } break; - case wpi::json::value_t::number_float: + case wpi::util::json::value_t::number_float: if (valuePtr->type != Storage::Value::kDoubleArray) { valuePtr->Reset(Storage::Value::kDoubleArray); valuePtr->doubleArray = new std::vector(); valuePtr->doubleArrayDefault = nullptr; } break; - case wpi::json::value_t::number_integer: - case wpi::json::value_t::number_unsigned: + case wpi::util::json::value_t::number_integer: + case wpi::util::json::value_t::number_unsigned: if (valuePtr->type != Storage::Value::kInt64Array) { valuePtr->Reset(Storage::Value::kInt64Array); valuePtr->int64Array = new std::vector(); valuePtr->int64ArrayDefault = nullptr; } break; - case wpi::json::value_t::string: + case wpi::util::json::value_t::string: if (valuePtr->type != Storage::Value::kStringArray) { valuePtr->Reset(Storage::Value::kStringArray); valuePtr->stringArray = new std::vector(); valuePtr->stringArrayDefault = nullptr; } break; - case wpi::json::value_t::object: + case wpi::util::json::value_t::object: if (valuePtr->type != Storage::Value::kChildArray) { valuePtr->Reset(Storage::Value::kChildArray); valuePtr->childArray = new std::vector>(); } break; - case wpi::json::value_t::array: + case wpi::util::json::value_t::array: ImGui::LogText("nested array in %s, ignoring", filename); return false; default: @@ -401,21 +401,21 @@ static bool JsonArrayToStorage(Storage::Value* valuePtr, const wpi::json& jarr, // loop over array to store elements for (auto jvalue : arr) { switch (jvalue.type()) { - case wpi::json::value_t::boolean: + case wpi::util::json::value_t::boolean: if (valuePtr->type == Storage::Value::kBoolArray) { valuePtr->boolArray->push_back(jvalue.get()); } else { goto error; } break; - case wpi::json::value_t::number_float: + case wpi::util::json::value_t::number_float: if (valuePtr->type == Storage::Value::kDoubleArray) { valuePtr->doubleArray->push_back(jvalue.get()); } else { goto error; } break; - case wpi::json::value_t::number_integer: + case wpi::util::json::value_t::number_integer: if (valuePtr->type == Storage::Value::kInt64Array) { valuePtr->int64Array->push_back(jvalue.get()); } else if (valuePtr->type == Storage::Value::kDoubleArray) { @@ -424,7 +424,7 @@ static bool JsonArrayToStorage(Storage::Value* valuePtr, const wpi::json& jarr, goto error; } break; - case wpi::json::value_t::number_unsigned: + case wpi::util::json::value_t::number_unsigned: if (valuePtr->type == Storage::Value::kInt64Array) { valuePtr->int64Array->push_back(jvalue.get()); } else if (valuePtr->type == Storage::Value::kDoubleArray) { @@ -433,7 +433,7 @@ static bool JsonArrayToStorage(Storage::Value* valuePtr, const wpi::json& jarr, goto error; } break; - case wpi::json::value_t::string: + case wpi::util::json::value_t::string: if (valuePtr->type == Storage::Value::kStringArray) { valuePtr->stringArray->emplace_back( jvalue.get_ref()); @@ -441,7 +441,7 @@ static bool JsonArrayToStorage(Storage::Value* valuePtr, const wpi::json& jarr, goto error; } break; - case wpi::json::value_t::object: + case wpi::util::json::value_t::object: if (valuePtr->type == Storage::Value::kChildArray) { valuePtr->childArray->emplace_back(std::make_unique()); valuePtr->childArray->back()->FromJson(jvalue, filename); @@ -449,7 +449,7 @@ static bool JsonArrayToStorage(Storage::Value* valuePtr, const wpi::json& jarr, goto error; } break; - case wpi::json::value_t::array: + case wpi::util::json::value_t::array: ImGui::LogText("nested array in %s, ignoring", filename); return false; default: @@ -464,7 +464,7 @@ error: return false; } -bool Storage::FromJson(const wpi::json& json, const char* filename) { +bool Storage::FromJson(const wpi::util::json& json, const char* filename) { if (m_fromJson) { return m_fromJson(json, filename); } @@ -482,34 +482,34 @@ bool Storage::FromJson(const wpi::json& json, const char* filename) { } auto& jvalue = jkv.value(); switch (jvalue.type()) { - case wpi::json::value_t::boolean: + case wpi::util::json::value_t::boolean: valuePtr->Reset(Value::kBool); valuePtr->boolVal = jvalue.get(); break; - case wpi::json::value_t::number_float: + case wpi::util::json::value_t::number_float: valuePtr->Reset(Value::kDouble); valuePtr->doubleVal = jvalue.get(); break; - case wpi::json::value_t::number_integer: + case wpi::util::json::value_t::number_integer: valuePtr->Reset(Value::kInt64); valuePtr->int64Val = jvalue.get(); break; - case wpi::json::value_t::number_unsigned: + case wpi::util::json::value_t::number_unsigned: valuePtr->Reset(Value::kInt64); valuePtr->int64Val = jvalue.get(); break; - case wpi::json::value_t::string: + case wpi::util::json::value_t::string: valuePtr->Reset(Value::kString); valuePtr->stringVal = jvalue.get_ref(); break; - case wpi::json::value_t::object: + case wpi::util::json::value_t::object: if (valuePtr->type != Value::kChild) { valuePtr->Reset(Value::kChild); valuePtr->child = new Storage; } valuePtr->child->FromJson(jvalue, filename); // recurse break; - case wpi::json::value_t::array: + case wpi::util::json::value_t::array: if (!JsonArrayToStorage(valuePtr.get(), jvalue, filename)) { if (created) { m_values.erase(jkv.key()); @@ -528,8 +528,8 @@ bool Storage::FromJson(const wpi::json& json, const char* filename) { } template -static wpi::json StorageToJsonArray(const std::vector& arr) { - wpi::json jarr = wpi::json::array(); +static wpi::util::json StorageToJsonArray(const std::vector& arr) { + wpi::util::json jarr = wpi::util::json::array(); for (auto&& v : arr) { jarr.emplace_back(v); } @@ -537,27 +537,27 @@ static wpi::json StorageToJsonArray(const std::vector& arr) { } template <> -wpi::json StorageToJsonArray>( +wpi::util::json StorageToJsonArray>( const std::vector>& arr) { - wpi::json jarr = wpi::json::array(); + wpi::util::json jarr = wpi::util::json::array(); for (auto&& v : arr) { jarr.emplace_back(v->ToJson()); } // remove any trailing empty items while (!jarr.empty() && jarr.back().empty()) { - jarr.get_ref().pop_back(); + jarr.get_ref().pop_back(); } return jarr; } -wpi::json Storage::ToJson() const { +wpi::util::json Storage::ToJson() const { if (m_toJson) { return m_toJson(); } - wpi::json j = wpi::json::object(); + wpi::util::json j = wpi::util::json::object(); for (auto&& kv : m_values) { - wpi::json jelem; + wpi::util::json jelem; auto& value = *kv.second; switch (value.type) { #define CASE(CapsName, LowerName) \ diff --git a/glass/src/lib/native/cpp/View.cpp b/glass/src/lib/native/cpp/View.cpp index 5fa45686b5..c6d1029f53 100644 --- a/glass/src/lib/native/cpp/View.cpp +++ b/glass/src/lib/native/cpp/View.cpp @@ -7,23 +7,23 @@ #include #include -using namespace glass; +using namespace wpi::glass; namespace { class FunctionView : public View { public: - explicit FunctionView(wpi::unique_function display) + explicit FunctionView(wpi::util::unique_function display) : m_display(std::move(display)) {} void Display() override { m_display(); } private: - wpi::unique_function m_display; + wpi::util::unique_function m_display; }; } // namespace -std::unique_ptr glass::MakeFunctionView( - wpi::unique_function display) { +std::unique_ptr wpi::glass::MakeFunctionView( + wpi::util::unique_function display) { return std::make_unique(std::move(display)); } diff --git a/glass/src/lib/native/cpp/Window.cpp b/glass/src/lib/native/cpp/Window.cpp index 7e79bc297c..fe23b6bdef 100644 --- a/glass/src/lib/native/cpp/Window.cpp +++ b/glass/src/lib/native/cpp/Window.cpp @@ -14,7 +14,7 @@ #include "wpi/glass/Storage.hpp" #include "wpi/glass/support/ExtraGuiWidgets.hpp" -using namespace glass; +using namespace wpi::glass; Window::Window(Storage& storage, std::string_view id, Visibility defaultVisibility) diff --git a/glass/src/lib/native/cpp/WindowManager.cpp b/glass/src/lib/native/cpp/WindowManager.cpp index b301477561..5f05251f6b 100644 --- a/glass/src/lib/native/cpp/WindowManager.cpp +++ b/glass/src/lib/native/cpp/WindowManager.cpp @@ -16,7 +16,7 @@ #include "wpi/gui/wpigui.hpp" #include "wpi/util/print.hpp" -using namespace glass; +using namespace wpi::glass; WindowManager::WindowManager(Storage& storage) : m_storage{storage} { storage.SetCustomApply([this] { @@ -27,14 +27,14 @@ WindowManager::WindowManager(Storage& storage) : m_storage{storage} { } Window* WindowManager::AddWindow(std::string_view id, - wpi::unique_function display, + wpi::util::unique_function display, Window::Visibility defaultVisibility) { auto win = GetOrAddWindow(id, false, defaultVisibility); if (!win) { return nullptr; } if (win->HasView()) { - wpi::print(stderr, "GUI: ignoring duplicate window '{}'\n", id); + wpi::util::print(stderr, "GUI: ignoring duplicate window '{}'\n", id); return nullptr; } win->SetView(MakeFunctionView(std::move(display))); @@ -49,7 +49,7 @@ Window* WindowManager::AddWindow(std::string_view id, return nullptr; } if (win->HasView()) { - wpi::print(stderr, "GUI: ignoring duplicate window '{}'\n", id); + wpi::util::print(stderr, "GUI: ignoring duplicate window '{}'\n", id); return nullptr; } win->SetView(std::move(view)); @@ -64,7 +64,7 @@ Window* WindowManager::GetOrAddWindow(std::string_view id, bool duplicateOk, [](const auto& elem, std::string_view s) { return elem->GetId() < s; }); if (it != m_windows.end() && (*it)->GetId() == id) { if (!duplicateOk) { - wpi::print(stderr, "GUI: ignoring duplicate window '{}'\n", id); + wpi::util::print(stderr, "GUI: ignoring duplicate window '{}'\n", id); return nullptr; } return it->get(); diff --git a/glass/src/lib/native/cpp/hardware/AnalogInput.cpp b/glass/src/lib/native/cpp/hardware/AnalogInput.cpp index 7920de1f5c..54d2bfd289 100644 --- a/glass/src/lib/native/cpp/hardware/AnalogInput.cpp +++ b/glass/src/lib/native/cpp/hardware/AnalogInput.cpp @@ -13,9 +13,9 @@ #include "wpi/glass/Storage.hpp" #include "wpi/util/StringExtras.hpp" -using namespace glass; +using namespace wpi::glass; -void glass::DisplayAnalogInput(AnalogInputModel* model, int index) { +void wpi::glass::DisplayAnalogInput(AnalogInputModel* model, int index) { auto voltageData = model->GetVoltageData(); if (!voltageData) { return; @@ -25,9 +25,9 @@ void glass::DisplayAnalogInput(AnalogInputModel* model, int index) { std::string& name = GetStorage().GetString("name"); char label[128]; if (!name.empty()) { - wpi::format_to_n_c_str(label, sizeof(label), "{} [{}]###name", name, index); + wpi::util::format_to_n_c_str(label, sizeof(label), "{} [{}]###name", name, index); } else { - wpi::format_to_n_c_str(label, sizeof(label), "In[{}]###name", index); + wpi::util::format_to_n_c_str(label, sizeof(label), "In[{}]###name", index); } if (auto simDevice = model->GetSimDevice()) { @@ -47,7 +47,7 @@ void glass::DisplayAnalogInput(AnalogInputModel* model, int index) { } } -void glass::DisplayAnalogInputs(AnalogInputsModel* model, +void wpi::glass::DisplayAnalogInputs(AnalogInputsModel* model, std::string_view noneMsg) { ImGui::Text("(Use Ctrl+Click to edit value)"); bool hasAny = false; diff --git a/glass/src/lib/native/cpp/hardware/DIO.cpp b/glass/src/lib/native/cpp/hardware/DIO.cpp index 1cb8818e8e..bf271fb8c3 100644 --- a/glass/src/lib/native/cpp/hardware/DIO.cpp +++ b/glass/src/lib/native/cpp/hardware/DIO.cpp @@ -10,7 +10,7 @@ #include "wpi/glass/hardware/Encoder.hpp" #include "wpi/glass/support/NameSetting.hpp" -using namespace glass; +using namespace wpi::glass; static void LabelSimDevice(const char* name, const char* simDeviceName) { ImGui::PushStyleColor(ImGuiCol_Text, IM_COL32(96, 96, 96, 255)); @@ -99,13 +99,13 @@ void DisplayDIOImpl(DIOModel* model, int index, bool outputsEnabled) { } } -void glass::DisplayDIO(DIOModel* model, int index, bool outputsEnabled) { +void wpi::glass::DisplayDIO(DIOModel* model, int index, bool outputsEnabled) { ImGui::PushItemWidth(ImGui::GetFontSize() * 8); DisplayDIOImpl(model, index, outputsEnabled); ImGui::PopItemWidth(); } -void glass::DisplayDIOs(DIOsModel* model, bool outputsEnabled, +void wpi::glass::DisplayDIOs(DIOsModel* model, bool outputsEnabled, std::string_view noneMsg) { bool hasAny = false; diff --git a/glass/src/lib/native/cpp/hardware/Encoder.cpp b/glass/src/lib/native/cpp/hardware/Encoder.cpp index 092f451009..f5c21f9d14 100644 --- a/glass/src/lib/native/cpp/hardware/Encoder.cpp +++ b/glass/src/lib/native/cpp/hardware/Encoder.cpp @@ -14,7 +14,7 @@ #include "wpi/glass/Storage.hpp" #include "wpi/util/StringExtras.hpp" -using namespace glass; +using namespace wpi::glass; void EncoderModel::SetName(std::string_view name) { if (name.empty()) { @@ -58,7 +58,7 @@ void EncoderModel::SetName(std::string_view name) { } } -void glass::DisplayEncoder(EncoderModel* model) { +void wpi::glass::DisplayEncoder(EncoderModel* model) { if (auto simDevice = model->GetSimDevice()) { ImGui::PushStyleColor(ImGuiCol_Text, IM_COL32(96, 96, 96, 255)); ImGui::TextUnformatted(simDevice); @@ -73,10 +73,10 @@ void glass::DisplayEncoder(EncoderModel* model) { std::string& name = GetStorage().GetString("name"); char label[128]; if (!name.empty()) { - wpi::format_to_n_c_str(label, sizeof(label), "{} [{},{}]###header", name, + wpi::util::format_to_n_c_str(label, sizeof(label), "{} [{},{}]###header", name, chA, chB); } else { - wpi::format_to_n_c_str(label, sizeof(label), "Encoder[{},{}]###header", chA, + wpi::util::format_to_n_c_str(label, sizeof(label), "Encoder[{},{}]###header", chA, chB); } @@ -159,7 +159,7 @@ void glass::DisplayEncoder(EncoderModel* model) { ImGui::PopItemWidth(); } -void glass::DisplayEncoders(EncodersModel* model, std::string_view noneMsg) { +void wpi::glass::DisplayEncoders(EncodersModel* model, std::string_view noneMsg) { bool hasAny = false; model->ForEachEncoder([&](EncoderModel& encoder, int i) { hasAny = true; diff --git a/glass/src/lib/native/cpp/hardware/Gyro.cpp b/glass/src/lib/native/cpp/hardware/Gyro.cpp index 654b3c98fd..4993fa0eec 100644 --- a/glass/src/lib/native/cpp/hardware/Gyro.cpp +++ b/glass/src/lib/native/cpp/hardware/Gyro.cpp @@ -14,9 +14,9 @@ #include "wpi/glass/DataSource.hpp" #include "wpi/util/StringExtras.hpp" -using namespace glass; +using namespace wpi::glass; -void glass::DisplayGyro(GyroModel* m) { +void wpi::glass::DisplayGyro(GyroModel* m) { ImColor primaryColor = ImGui::GetStyle().Colors[ImGuiCol_Text]; ImColor disabledColor = ImGui::GetStyle().Colors[ImGuiCol_TextDisabled]; ImColor secondaryColor = ImGui::GetStyle().Colors[ImGuiCol_Header]; @@ -64,7 +64,7 @@ void glass::DisplayGyro(GyroModel* m) { color, 1.2f); if (major) { char txt[16]; - wpi::format_to_n_c_str(txt, sizeof(txt), "{}°", i); + wpi::util::format_to_n_c_str(txt, sizeof(txt), "{}°", i); draw->AddText( center + (direction * radius * 1.25) - ImGui::CalcTextSize(txt) * 0.5, diff --git a/glass/src/lib/native/cpp/hardware/LEDDisplay.cpp b/glass/src/lib/native/cpp/hardware/LEDDisplay.cpp index fe23b716a3..3f537540f6 100644 --- a/glass/src/lib/native/cpp/hardware/LEDDisplay.cpp +++ b/glass/src/lib/native/cpp/hardware/LEDDisplay.cpp @@ -11,7 +11,7 @@ #include "wpi/glass/support/ExtraGuiWidgets.hpp" #include "wpi/util/SmallVector.hpp" -using namespace glass; +using namespace wpi::glass; namespace { struct IndicatorData { @@ -20,8 +20,8 @@ struct IndicatorData { }; } // namespace -void glass::DisplayLEDDisplay(LEDDisplayModel* model, int index) { - wpi::SmallVector dataBuf; +void wpi::glass::DisplayLEDDisplay(LEDDisplayModel* model, int index) { + wpi::util::SmallVector dataBuf; auto data = model->GetData(dataBuf); int length = data.size(); auto& storage = GetStorage(); @@ -75,7 +75,7 @@ void glass::DisplayLEDDisplay(LEDDisplayModel* model, int index) { config); } -void glass::DisplayLEDDisplays(LEDDisplaysModel* model) { +void wpi::glass::DisplayLEDDisplays(LEDDisplaysModel* model) { bool hasAny = false; model->ForEachLEDDisplay([&](LEDDisplayModel& display, int i) { diff --git a/glass/src/lib/native/cpp/hardware/MotorController.cpp b/glass/src/lib/native/cpp/hardware/MotorController.cpp index 9219d3f66b..ab3c91a4f1 100644 --- a/glass/src/lib/native/cpp/hardware/MotorController.cpp +++ b/glass/src/lib/native/cpp/hardware/MotorController.cpp @@ -9,9 +9,9 @@ #include "wpi/glass/DataSource.hpp" -using namespace glass; +using namespace wpi::glass; -void glass::DisplayMotorController(MotorControllerModel* m) { +void wpi::glass::DisplayMotorController(MotorControllerModel* m) { // Get duty cycle data from the model and do not display anything if the data // is null. auto dc = m->GetPercentData(); diff --git a/glass/src/lib/native/cpp/hardware/PWM.cpp b/glass/src/lib/native/cpp/hardware/PWM.cpp index 20c71ec25e..09fc4bf3b6 100644 --- a/glass/src/lib/native/cpp/hardware/PWM.cpp +++ b/glass/src/lib/native/cpp/hardware/PWM.cpp @@ -13,9 +13,9 @@ #include "wpi/glass/Storage.hpp" #include "wpi/util/StringExtras.hpp" -using namespace glass; +using namespace wpi::glass; -void glass::DisplayPWM(PWMModel* model, int index, bool outputsEnabled) { +void wpi::glass::DisplayPWM(PWMModel* model, int index, bool outputsEnabled) { auto data = model->GetSpeedData(); if (!data) { return; @@ -25,9 +25,9 @@ void glass::DisplayPWM(PWMModel* model, int index, bool outputsEnabled) { std::string& name = GetStorage().GetString("name"); char label[128]; if (!name.empty()) { - wpi::format_to_n_c_str(label, sizeof(label), "{} [{}]###name", name, index); + wpi::util::format_to_n_c_str(label, sizeof(label), "{} [{}]###name", name, index); } else { - wpi::format_to_n_c_str(label, sizeof(label), "PWM[{}]###name", index); + wpi::util::format_to_n_c_str(label, sizeof(label), "PWM[{}]###name", index); } ImGui::SetNextItemWidth(ImGui::GetFontSize() * 4); @@ -38,7 +38,7 @@ void glass::DisplayPWM(PWMModel* model, int index, bool outputsEnabled) { } } -void glass::DisplayPWMs(PWMsModel* model, bool outputsEnabled, +void wpi::glass::DisplayPWMs(PWMsModel* model, bool outputsEnabled, std::string_view noneMsg) { bool hasAny = false; bool first = true; diff --git a/glass/src/lib/native/cpp/hardware/Pneumatic.cpp b/glass/src/lib/native/cpp/hardware/Pneumatic.cpp index fe97d8d008..4c5329be72 100644 --- a/glass/src/lib/native/cpp/hardware/Pneumatic.cpp +++ b/glass/src/lib/native/cpp/hardware/Pneumatic.cpp @@ -19,11 +19,11 @@ #include "wpi/util/SmallVector.hpp" #include "wpi/util/StringExtras.hpp" -using namespace glass; +using namespace wpi::glass; -bool glass::DisplayPneumaticControlSolenoids(PneumaticControlModel* model, +bool wpi::glass::DisplayPneumaticControlSolenoids(PneumaticControlModel* model, int index, bool outputsEnabled) { - wpi::SmallVector channels; + wpi::util::SmallVector channels; model->ForEachSolenoid([&](SolenoidModel& solenoid, int j) { if (auto data = solenoid.GetOutputData()) { if (j >= static_cast(channels.size())) { @@ -48,10 +48,10 @@ bool glass::DisplayPneumaticControlSolenoids(PneumaticControlModel* model, std::string& name = GetStorage().GetString("name"); char label[128]; if (!name.empty()) { - wpi::format_to_n_c_str(label, sizeof(label), "{} [{}]###header", name, + wpi::util::format_to_n_c_str(label, sizeof(label), "{} [{}]###header", name, index); } else { - wpi::format_to_n_c_str(label, sizeof(label), "{}[{}]###header", + wpi::util::format_to_n_c_str(label, sizeof(label), "{}[{}]###header", model->GetName(), index); } @@ -87,7 +87,7 @@ bool glass::DisplayPneumaticControlSolenoids(PneumaticControlModel* model, return true; } -void glass::DisplayPneumaticControlsSolenoids(PneumaticControlsModel* model, +void wpi::glass::DisplayPneumaticControlsSolenoids(PneumaticControlsModel* model, bool outputsEnabled, std::string_view noneMsg) { bool hasAny = false; @@ -105,13 +105,13 @@ void glass::DisplayPneumaticControlsSolenoids(PneumaticControlsModel* model, } } -void glass::DisplayCompressorDevice(CompressorModel* model, int index, +void wpi::glass::DisplayCompressorDevice(CompressorModel* model, int index, bool outputsEnabled) { if (!model || !model->Exists()) { return; } char name[32]; - wpi::format_to_n_c_str(name, sizeof(name), "Compressor[{}]", index); + wpi::util::format_to_n_c_str(name, sizeof(name), "Compressor[{}]", index); if (BeginDevice(name)) { // output enabled @@ -154,7 +154,7 @@ void glass::DisplayCompressorDevice(CompressorModel* model, int index, } } -void glass::DisplayCompressorsDevice(PneumaticControlsModel* model, +void wpi::glass::DisplayCompressorsDevice(PneumaticControlsModel* model, bool outputsEnabled) { model->ForEachPneumaticControl( [&](PneumaticControlModel& pneumaticControl, int i) { diff --git a/glass/src/lib/native/cpp/hardware/PowerDistribution.cpp b/glass/src/lib/native/cpp/hardware/PowerDistribution.cpp index 9b6635bb68..8a474e273a 100644 --- a/glass/src/lib/native/cpp/hardware/PowerDistribution.cpp +++ b/glass/src/lib/native/cpp/hardware/PowerDistribution.cpp @@ -13,7 +13,7 @@ #include "wpi/glass/support/NameSetting.hpp" #include "wpi/util/StringExtras.hpp" -using namespace glass; +using namespace wpi::glass; static float DisplayChannel(PowerDistributionModel& pdp, int channel) { float width = 0; @@ -34,9 +34,9 @@ static float DisplayChannel(PowerDistributionModel& pdp, int channel) { return width; } -void glass::DisplayPowerDistribution(PowerDistributionModel* model, int index) { +void wpi::glass::DisplayPowerDistribution(PowerDistributionModel* model, int index) { char name[128]; - wpi::format_to_n_c_str(name, sizeof(name), "PowerDistribution[{}]", index); + wpi::util::format_to_n_c_str(name, sizeof(name), "PowerDistribution[{}]", index); if (CollapsingHeader(name)) { // temperature @@ -80,7 +80,7 @@ void glass::DisplayPowerDistribution(PowerDistributionModel* model, int index) { } } -void glass::DisplayPowerDistributions(PowerDistributionsModel* model, +void wpi::glass::DisplayPowerDistributions(PowerDistributionsModel* model, std::string_view noneMsg) { bool hasAny = false; model->ForEachPowerDistribution([&](PowerDistributionModel& pdp, int i) { diff --git a/glass/src/lib/native/cpp/hardware/RoboRio.cpp b/glass/src/lib/native/cpp/hardware/RoboRio.cpp index c08e1bb2fa..28b928bbb3 100644 --- a/glass/src/lib/native/cpp/hardware/RoboRio.cpp +++ b/glass/src/lib/native/cpp/hardware/RoboRio.cpp @@ -9,7 +9,7 @@ #include "wpi/glass/Context.hpp" #include "wpi/glass/DataSource.hpp" -using namespace glass; +using namespace wpi::glass; static void DisplayRail(RoboRioRailModel& rail, const char* name) { if (CollapsingHeader(name)) { @@ -46,7 +46,7 @@ static void DisplayRail(RoboRioRailModel& rail, const char* name) { } } -void glass::DisplayRoboRio(RoboRioModel* model) { +void wpi::glass::DisplayRoboRio(RoboRioModel* model) { ImGui::PushItemWidth(ImGui::GetFontSize() * 8); if (CollapsingHeader("RoboRIO Input")) { diff --git a/glass/src/lib/native/cpp/other/Alerts.cpp b/glass/src/lib/native/cpp/other/Alerts.cpp index ee9d591431..fe33b2067b 100644 --- a/glass/src/lib/native/cpp/other/Alerts.cpp +++ b/glass/src/lib/native/cpp/other/Alerts.cpp @@ -7,9 +7,9 @@ #include #include -using namespace glass; +using namespace wpi::glass; -void glass::DisplayAlerts(AlertsModel* model) { +void wpi::glass::DisplayAlerts(AlertsModel* model) { auto& infos = model->GetInfos(); auto& warnings = model->GetWarnings(); auto& errors = model->GetErrors(); diff --git a/glass/src/lib/native/cpp/other/CommandScheduler.cpp b/glass/src/lib/native/cpp/other/CommandScheduler.cpp index f41cf1bba2..da5434ad8d 100644 --- a/glass/src/lib/native/cpp/other/CommandScheduler.cpp +++ b/glass/src/lib/native/cpp/other/CommandScheduler.cpp @@ -9,9 +9,9 @@ #include "wpi/glass/Context.hpp" #include "wpi/glass/DataSource.hpp" -using namespace glass; +using namespace wpi::glass; -void glass::DisplayCommandScheduler(CommandSchedulerModel* m) { +void wpi::glass::DisplayCommandScheduler(CommandSchedulerModel* m) { ImGui::SetNextItemWidth(ImGui::GetFontSize() * 20); ImGui::Text("Scheduled Commands: "); ImGui::Separator(); diff --git a/glass/src/lib/native/cpp/other/CommandSelector.cpp b/glass/src/lib/native/cpp/other/CommandSelector.cpp index c0f357f43d..61e0509b8a 100644 --- a/glass/src/lib/native/cpp/other/CommandSelector.cpp +++ b/glass/src/lib/native/cpp/other/CommandSelector.cpp @@ -8,9 +8,9 @@ #include "wpi/glass/DataSource.hpp" -using namespace glass; +using namespace wpi::glass; -void glass::DisplayCommandSelector(CommandSelectorModel* m) { +void wpi::glass::DisplayCommandSelector(CommandSelectorModel* m) { if (auto name = m->GetName()) { ImGui::Text("%s", name); } diff --git a/glass/src/lib/native/cpp/other/DeviceTree.cpp b/glass/src/lib/native/cpp/other/DeviceTree.cpp index 776cd76145..4e57218ca3 100644 --- a/glass/src/lib/native/cpp/other/DeviceTree.cpp +++ b/glass/src/lib/native/cpp/other/DeviceTree.cpp @@ -14,7 +14,7 @@ #include "wpi/glass/DataSource.hpp" #include "wpi/util/StringExtras.hpp" -using namespace glass; +using namespace wpi::glass; void DeviceTreeModel::Update() { for (auto&& display : m_displays) { @@ -41,11 +41,11 @@ void DeviceTreeModel::Display() { } } -void glass::HideDevice(const char* id) { +void wpi::glass::HideDevice(const char* id) { gContext->deviceHidden[id] = true; } -bool glass::BeginDevice(const char* id, ImGuiTreeNodeFlags flags) { +bool wpi::glass::BeginDevice(const char* id, ImGuiTreeNodeFlags flags) { if (gContext->deviceHidden[id]) { return false; } @@ -56,9 +56,9 @@ bool glass::BeginDevice(const char* id, ImGuiTreeNodeFlags flags) { std::string& name = GetStorage().GetString("name"); char label[128]; if (name.empty()) { - wpi::format_to_n_c_str(label, sizeof(label), "{}###header", id); + wpi::util::format_to_n_c_str(label, sizeof(label), "{}###header", id); } else { - wpi::format_to_n_c_str(label, sizeof(label), "{}###header", name); + wpi::util::format_to_n_c_str(label, sizeof(label), "{}###header", name); } bool open = CollapsingHeader(label, flags); @@ -70,7 +70,7 @@ bool glass::BeginDevice(const char* id, ImGuiTreeNodeFlags flags) { return open; } -void glass::EndDevice() { +void wpi::glass::EndDevice() { PopID(); } @@ -150,29 +150,29 @@ static inline bool DeviceValueImpl(const char* name, bool readonly, } } -bool glass::DeviceBoolean(const char* name, bool readonly, bool* value, +bool wpi::glass::DeviceBoolean(const char* name, bool readonly, bool* value, const DataSource* source) { return DeviceValueImpl(name, readonly, source, DeviceBooleanImpl, value); } -bool glass::DeviceDouble(const char* name, bool readonly, double* value, +bool wpi::glass::DeviceDouble(const char* name, bool readonly, double* value, const DataSource* source) { return DeviceValueImpl(name, readonly, source, DeviceDoubleImpl, value); } -bool glass::DeviceEnum(const char* name, bool readonly, int* value, +bool wpi::glass::DeviceEnum(const char* name, bool readonly, int* value, const char** options, int32_t numOptions, const DataSource* source) { return DeviceValueImpl(name, readonly, source, DeviceEnumImpl, value, options, numOptions); } -bool glass::DeviceInt(const char* name, bool readonly, int32_t* value, +bool wpi::glass::DeviceInt(const char* name, bool readonly, int32_t* value, const DataSource* source) { return DeviceValueImpl(name, readonly, source, DeviceIntImpl, value); } -bool glass::DeviceLong(const char* name, bool readonly, int64_t* value, +bool wpi::glass::DeviceLong(const char* name, bool readonly, int64_t* value, const DataSource* source) { return DeviceValueImpl(name, readonly, source, DeviceLongImpl, value); } diff --git a/glass/src/lib/native/cpp/other/Drive.cpp b/glass/src/lib/native/cpp/other/Drive.cpp index 0c722d9b35..76b5e63c2a 100644 --- a/glass/src/lib/native/cpp/other/Drive.cpp +++ b/glass/src/lib/native/cpp/other/Drive.cpp @@ -13,9 +13,9 @@ #include "wpi/glass/DataSource.hpp" -using namespace glass; +using namespace wpi::glass; -void glass::DisplayDrive(DriveModel* m) { +void wpi::glass::DisplayDrive(DriveModel* m) { // Check if the model exists. if (!m->Exists()) { ImGui::PushStyleColor(ImGuiCol_Text, IM_COL32(96, 96, 96, 255)); diff --git a/glass/src/lib/native/cpp/other/FMS.cpp b/glass/src/lib/native/cpp/other/FMS.cpp index 8d379ebc11..90583d3363 100644 --- a/glass/src/lib/native/cpp/other/FMS.cpp +++ b/glass/src/lib/native/cpp/other/FMS.cpp @@ -12,12 +12,12 @@ #include "wpi/glass/DataSource.hpp" #include "wpi/util/SmallString.hpp" -using namespace glass; +using namespace wpi::glass; static const char* stations[] = {"Invalid", "Red 1", "Red 2", "Red 3", "Blue 1", "Blue 2", "Blue 3"}; -void glass::DisplayFMS(FMSModel* model, bool editableDsAttached) { +void wpi::glass::DisplayFMS(FMSModel* model, bool editableDsAttached) { if (!model->Exists() || model->IsReadOnly()) { return DisplayFMSReadOnly(model); } @@ -89,7 +89,7 @@ void glass::DisplayFMS(FMSModel* model, bool editableDsAttached) { } } -void glass::DisplayFMSReadOnly(FMSModel* model) { +void wpi::glass::DisplayFMSReadOnly(FMSModel* model) { bool exists = model->Exists(); if (!exists) { ImGui::PushStyleColor(ImGuiCol_Text, IM_COL32(96, 96, 96, 255)); @@ -150,7 +150,7 @@ void glass::DisplayFMSReadOnly(FMSModel* model) { } if (auto data = model->GetGameSpecificMessageData()) { if (exists) { - wpi::SmallString<64> gsmBuf; + wpi::util::SmallString<64> gsmBuf; std::string_view gsm = data->GetValue(gsmBuf); ImGui::Text("Game Specific: %.*s", static_cast(gsm.size()), gsm.data()); diff --git a/glass/src/lib/native/cpp/other/Field2D.cpp b/glass/src/lib/native/cpp/other/Field2D.cpp index 85b4456d27..1bcf1b5913 100644 --- a/glass/src/lib/native/cpp/other/Field2D.cpp +++ b/glass/src/lib/native/cpp/other/Field2D.cpp @@ -37,7 +37,7 @@ #include "wpi/util/json.hpp" #include "wpi/util/print.hpp" -using namespace glass; +using namespace wpi::glass; namespace gui = wpi::gui; @@ -47,12 +47,12 @@ enum DisplayUnits { kDisplayMeters = 0, kDisplayFeet, kDisplayInches }; // Per-frame field data (not persistent) struct FieldFrameData { - frc::Translation2d GetPosFromScreen(const ImVec2& cursor) const { + wpi::math::Translation2d GetPosFromScreen(const ImVec2& cursor) const { return { - units::meter_t{(std::clamp(cursor.x, min.x, max.x) - min.x) / scale}, - units::meter_t{(max.y - std::clamp(cursor.y, min.y, max.y)) / scale}}; + wpi::units::meter_t{(std::clamp(cursor.x, min.x, max.x) - min.x) / scale}, + wpi::units::meter_t{(max.y - std::clamp(cursor.y, min.y, max.y)) / scale}}; } - ImVec2 GetScreenFromPos(const frc::Translation2d& pos) const { + ImVec2 GetScreenFromPos(const wpi::math::Translation2d& pos) const { return {min.x + scale * pos.X().to(), max.y - scale * pos.Y().to()}; } @@ -71,7 +71,7 @@ struct SelectedTargetInfo { FieldObjectModel* objModel = nullptr; std::string name; size_t index; - units::radian_t rot; + wpi::units::radian_t rot; ImVec2 poseCenter; // center of the pose (screen coordinates) ImVec2 center; // center of the target (screen coordinates) float radius; // target radius @@ -83,18 +83,18 @@ struct SelectedTargetInfo { struct PoseDragState { SelectedTargetInfo target; ImVec2 initialOffset; - units::radian_t initialAngle = 0_rad; + wpi::units::radian_t initialAngle = 0_rad; }; // Popup edit state class PopupState { public: - void Open(SelectedTargetInfo* target, const frc::Translation2d& pos); + void Open(SelectedTargetInfo* target, const wpi::math::Translation2d& pos); void Close(); SelectedTargetInfo* GetTarget() { return &m_target; } FieldObjectModel* GetInsertModel() { return m_insertModel; } - std::span GetInsertPoses() const { return m_insertPoses; } + std::span GetInsertPoses() const { return m_insertPoses; } void Display(Field2DModel* model, const FieldFrameData& ffd); @@ -106,7 +106,7 @@ class PopupState { // for insert FieldObjectModel* m_insertModel; - std::vector m_insertPoses; + std::vector m_insertPoses; std::string m_insertName; int m_insertIndex; }; @@ -133,8 +133,8 @@ struct DisplayOptions { float weight = kDefaultWeight; int color = kDefaultColor; - units::meter_t width = kDefaultWidth; - units::meter_t length = kDefaultLength; + wpi::units::meter_t width = kDefaultWidth; + wpi::units::meter_t length = kDefaultLength; bool arrows = kDefaultArrows; int arrowSize = kDefaultArrowSize; @@ -149,13 +149,13 @@ struct DisplayOptions { // Per-frame pose data (not persistent) class PoseFrameData { public: - explicit PoseFrameData(const frc::Pose2d& pose, FieldObjectModel& model, + explicit PoseFrameData(const wpi::math::Pose2d& pose, FieldObjectModel& model, size_t index, const FieldFrameData& ffd, const DisplayOptions& displayOptions); - void SetPosition(const frc::Translation2d& pos); - void SetRotation(units::radian_t rot); - const frc::Rotation2d& GetRotation() const { return m_pose.Rotation(); } - const frc::Pose2d& GetPose() const { return m_pose; } + void SetPosition(const wpi::math::Translation2d& pos); + void SetRotation(wpi::units::radian_t rot); + const wpi::math::Rotation2d& GetRotation() const { return m_pose.Rotation(); } + const wpi::math::Pose2d& GetPose() const { return m_pose; } float GetHitRadius() const { return m_hitRadius; } void UpdateFrameData(); std::pair IsHovered(const ImVec2& cursor) const; @@ -181,7 +181,7 @@ class PoseFrameData { float m_hitRadius; - frc::Pose2d m_pose; + wpi::math::Pose2d m_pose; }; class ObjectInfo { @@ -233,7 +233,7 @@ class FieldInfo { FieldFrameData GetFrameData(ImVec2 min, ImVec2 max) const; void Draw(ImDrawList* drawList, const FieldFrameData& frameData) const; - wpi::StringMap m_objects; + wpi::util::StringMap m_objects; private: void Reset(); @@ -266,37 +266,37 @@ static PoseDragState gDragState; static PopupState gPopupState; static DisplayUnits gDisplayUnits = kDisplayMeters; -static double ConvertDisplayLength(units::meter_t v) { +static double ConvertDisplayLength(wpi::units::meter_t v) { switch (gDisplayUnits) { case kDisplayFeet: - return v.convert().value(); + return v.convert().value(); case kDisplayInches: - return v.convert().value(); + return v.convert().value(); case kDisplayMeters: default: return v.value(); } } -static double ConvertDisplayAngle(units::degree_t v) { +static double ConvertDisplayAngle(wpi::units::degree_t v) { return v.value(); } -static bool InputLength(const char* label, units::meter_t* v, double step = 0.0, +static bool InputLength(const char* label, wpi::units::meter_t* v, double step = 0.0, double step_fast = 0.0, const char* format = "%.6f", ImGuiInputTextFlags flags = 0) { double dv = ConvertDisplayLength(*v); if (ImGui::InputDouble(label, &dv, step, step_fast, format, flags)) { switch (gDisplayUnits) { case kDisplayFeet: - *v = units::foot_t{dv}; + *v = wpi::units::foot_t{dv}; break; case kDisplayInches: - *v = units::inch_t{dv}; + *v = wpi::units::inch_t{dv}; break; case kDisplayMeters: default: - *v = units::meter_t{dv}; + *v = wpi::units::meter_t{dv}; break; } return true; @@ -308,7 +308,7 @@ static bool InputFloatLength(const char* label, float* v, double step = 0.0, double step_fast = 0.0, const char* format = "%.3f", ImGuiInputTextFlags flags = 0) { - units::meter_t uv{*v}; + wpi::units::meter_t uv{*v}; if (InputLength(label, &uv, step, step_fast, format, flags)) { *v = uv.to(); return true; @@ -316,18 +316,18 @@ static bool InputFloatLength(const char* label, float* v, double step = 0.0, return false; } -static bool InputAngle(const char* label, units::degree_t* v, double step = 0.0, +static bool InputAngle(const char* label, wpi::units::degree_t* v, double step = 0.0, double step_fast = 0.0, const char* format = "%.6f", ImGuiInputTextFlags flags = 0) { double dv = ConvertDisplayAngle(*v); if (ImGui::InputDouble(label, &dv, step, step_fast, format, flags)) { - *v = units::degree_t{dv}; + *v = wpi::units::degree_t{dv}; return true; } return false; } -static bool InputPose(frc::Pose2d* pose) { +static bool InputPose(wpi::math::Pose2d* pose) { auto x = pose->X(); auto y = pose->Y(); auto rot = pose->Rotation().Degrees(); @@ -337,7 +337,7 @@ static bool InputPose(frc::Pose2d* pose) { changed = InputLength("y", &y) || changed; changed = InputAngle("rot", &rot) || changed; if (changed) { - *pose = frc::Pose2d{x, y, rot}; + *pose = wpi::math::Pose2d{x, y, rot}; } return changed; } @@ -359,7 +359,7 @@ void FieldInfo::DisplaySettings() { if (ImGui::Selectable("Custom", m_builtin.empty())) { Reset(); } - for (auto&& field : fields::GetFields()) { + for (auto&& field : wpi::fields::GetFields()) { bool selected = field.name == m_builtin; if (ImGui::Selectable(field.name, selected)) { Reset(); @@ -406,7 +406,7 @@ void FieldInfo::LoadImage() { if (m_fileOpener && m_fileOpener->ready(0)) { auto result = m_fileOpener->result(); if (!result.empty()) { - if (wpi::ends_with(result[0], ".json")) { + if (wpi::util::ends_with(result[0], ".json")) { LoadJsonFile(result[0]); } else { LoadImageImpl(result[0].c_str()); @@ -420,7 +420,7 @@ void FieldInfo::LoadImage() { } if (!m_texture) { if (!m_builtin.empty()) { - for (auto&& field : fields::GetFields()) { + for (auto&& field : wpi::fields::GetFields()) { if (field.name == m_builtin) { auto jsonstr = field.getJson(); auto imagedata = field.getImage(); @@ -446,11 +446,11 @@ void FieldInfo::LoadImage() { bool FieldInfo::LoadJson(std::span is, std::string_view filename) { // parse file - wpi::json j; + wpi::util::json j; try { - j = wpi::json::parse(is); - } catch (const wpi::json::parse_error& e) { - wpi::print(stderr, "GUI: JSON: could not parse: {}\n", e.what()); + j = wpi::util::json::parse(is); + } catch (const wpi::util::json::parse_error& e) { + wpi::util::print(stderr, "GUI: JSON: could not parse: {}\n", e.what()); return false; } @@ -464,8 +464,8 @@ bool FieldInfo::LoadJson(std::span is, std::string_view filename) { std::string image; try { image = j.at("field-image").get(); - } catch (const wpi::json::exception& e) { - wpi::print(stderr, "GUI: JSON: could not read field-image: {}\n", e.what()); + } catch (const wpi::util::json::exception& e) { + wpi::util::print(stderr, "GUI: JSON: could not read field-image: {}\n", e.what()); return false; } @@ -476,8 +476,8 @@ bool FieldInfo::LoadJson(std::span is, std::string_view filename) { left = j.at("field-corners").at("top-left").at(0).get(); bottom = j.at("field-corners").at("bottom-right").at(1).get(); right = j.at("field-corners").at("bottom-right").at(0).get(); - } catch (const wpi::json::exception& e) { - wpi::print(stderr, "GUI: JSON: could not read field-corners: {}\n", + } catch (const wpi::util::json::exception& e) { + wpi::util::print(stderr, "GUI: JSON: could not read field-corners: {}\n", e.what()); return false; } @@ -488,8 +488,8 @@ bool FieldInfo::LoadJson(std::span is, std::string_view filename) { try { width = j.at("field-size").at(0).get(); height = j.at("field-size").at(1).get(); - } catch (const wpi::json::exception& e) { - wpi::print(stderr, "GUI: JSON: could not read field-size: {}\n", e.what()); + } catch (const wpi::util::json::exception& e) { + wpi::util::print(stderr, "GUI: JSON: could not read field-size: {}\n", e.what()); return false; } @@ -497,22 +497,22 @@ bool FieldInfo::LoadJson(std::span is, std::string_view filename) { std::string unit; try { unit = j.at("field-unit").get(); - } catch (const wpi::json::exception& e) { - wpi::print(stderr, "GUI: JSON: could not read field-unit: {}\n", e.what()); + } catch (const wpi::util::json::exception& e) { + wpi::util::print(stderr, "GUI: JSON: could not read field-unit: {}\n", e.what()); return false; } // convert size units to meters if (unit == "foot" || unit == "feet") { - width = units::convert(width); - height = units::convert(height); + width = wpi::units::convert(width); + height = wpi::units::convert(height); } // check scaling int fieldWidth = m_right - m_left; int fieldHeight = m_bottom - m_top; if (std::abs((fieldWidth / width) - (fieldHeight / height)) > 0.3) { - wpi::print(stderr, + wpi::util::print(stderr, "GUI: Field X and Y scaling substantially different: " "xscale={} yscale={}\n", (fieldWidth / width), (fieldHeight / height)); @@ -540,7 +540,7 @@ bool FieldInfo::LoadJson(std::span is, std::string_view filename) { } void FieldInfo::LoadJsonFile(std::string_view jsonfile) { - auto fileBuffer = wpi::MemoryBuffer::GetFile(jsonfile); + auto fileBuffer = wpi::util::MemoryBuffer::GetFile(jsonfile); if (!fileBuffer) { std::fputs("GUI: could not open field JSON file\n", stderr); return; @@ -551,7 +551,7 @@ void FieldInfo::LoadJsonFile(std::string_view jsonfile) { } bool FieldInfo::LoadImageImpl(const std::string& fn) { - wpi::print("GUI: loading field image '{}'\n", fn); + wpi::util::print("GUI: loading field image '{}'\n", fn); auto texture = gui::Texture::CreateFromFile(fn.c_str()); if (!texture) { std::puts("GUI: could not read field image"); @@ -651,8 +651,8 @@ DisplayOptions ObjectInfo::GetDisplayOptions() const { rv.style = static_cast(m_style.GetValue()); rv.weight = m_weight; rv.color = ImGui::ColorConvertFloat4ToU32(m_color.GetColor()); - rv.width = units::meter_t{m_width}; - rv.length = units::meter_t{m_length}; + rv.width = wpi::units::meter_t{m_width}; + rv.length = wpi::units::meter_t{m_length}; rv.arrows = m_arrows; rv.arrowSize = m_arrowSize; rv.arrowWeight = m_arrowWeight; @@ -761,7 +761,7 @@ void ObjectInfo::LoadImage() { } bool ObjectInfo::LoadImageImpl(const std::string& fn) { - wpi::print("GUI: loading object image '{}'\n", fn); + wpi::util::print("GUI: loading object image '{}'\n", fn); auto texture = gui::Texture::CreateFromFile(fn.c_str()); if (!texture) { std::fputs("GUI: could not read object image\n", stderr); @@ -772,7 +772,7 @@ bool ObjectInfo::LoadImageImpl(const std::string& fn) { return true; } -PoseFrameData::PoseFrameData(const frc::Pose2d& pose, FieldObjectModel& model, +PoseFrameData::PoseFrameData(const wpi::math::Pose2d& pose, FieldObjectModel& model, size_t index, const FieldFrameData& ffd, const DisplayOptions& displayOptions) : m_model{model}, @@ -786,13 +786,13 @@ PoseFrameData::PoseFrameData(const frc::Pose2d& pose, FieldObjectModel& model, UpdateFrameData(); } -void PoseFrameData::SetPosition(const frc::Translation2d& pos) { - m_pose = frc::Pose2d{pos, m_pose.Rotation()}; +void PoseFrameData::SetPosition(const wpi::math::Translation2d& pos) { + m_pose = wpi::math::Pose2d{pos, m_pose.Rotation()}; m_model.SetPose(m_index, m_pose); } -void PoseFrameData::SetRotation(units::radian_t rot) { - m_pose = frc::Pose2d{m_pose.Translation(), rot}; +void PoseFrameData::SetRotation(wpi::units::radian_t rot) { + m_pose = wpi::math::Pose2d{m_pose.Translation(), rot}; m_model.SetPose(m_index, m_pose); } @@ -896,7 +896,7 @@ void PoseFrameData::HandleDrag(const ImVec2& cursor) { } else { ImVec2 off = cursor - m_center; SetRotation(gDragState.initialAngle - - units::radian_t{std::atan2(off.y, off.x)}); + wpi::units::radian_t{std::atan2(off.y, off.x)}); gDragState.target.center = m_corners[gDragState.target.corner - 2]; gDragState.target.rot = GetRotation().Radians(); } @@ -935,7 +935,7 @@ void PoseFrameData::Draw(ImDrawList* drawList, std::vector* center, } } -void glass::DisplayField2DSettings(Field2DModel* model) { +void wpi::glass::DisplayField2DSettings(Field2DModel* model) { auto& storage = GetStorage(); auto field = storage.GetData(); if (!field) { @@ -963,7 +963,7 @@ void glass::DisplayField2DSettings(Field2DModel* model) { } PushID(name); - wpi::SmallString<64> nameBuf{name}; + wpi::util::SmallString<64> nameBuf{name}; if (ImGui::CollapsingHeader(nameBuf.c_str())) { auto& obj = field->m_objects.try_emplace(name, GetStorage()).first->second; @@ -1085,7 +1085,7 @@ void FieldDisplay::Display(FieldInfo* field, Field2DModel* model, gDragState.initialOffset = m_mousePos - target->poseCenter; if (target->corner != 1) { gDragState.initialAngle = - units::radian_t{std::atan2(gDragState.initialOffset.y, + wpi::units::radian_t{std::atan2(gDragState.initialOffset.y, gDragState.initialOffset.x)} + target->rot; } @@ -1152,7 +1152,7 @@ void FieldDisplay::DisplayObject(FieldObjectModel& model, } void PopupState::Open(SelectedTargetInfo* target, - const frc::Translation2d& pos) { + const wpi::math::Translation2d& pos) { if (target) { m_target = *target; } else { @@ -1182,7 +1182,7 @@ void PopupState::Display(Field2DModel* model, const FieldFrameData& ffd) { void PopupState::DisplayTarget(Field2DModel* model, const FieldFrameData& ffd) { ImGui::Text("%s[%d]", m_target.name.c_str(), static_cast(m_target.index)); - frc::Pose2d pose{ffd.GetPosFromScreen(m_target.poseCenter), m_target.rot}; + wpi::math::Pose2d pose{ffd.GetPosFromScreen(m_target.poseCenter), m_target.rot}; if (InputPose(&pose)) { m_target.poseCenter = ffd.GetScreenFromPos(pose.Translation()); m_target.rot = pose.Rotation().Radians(); @@ -1190,7 +1190,7 @@ void PopupState::DisplayTarget(Field2DModel* model, const FieldFrameData& ffd) { } if (ImGui::Button("Delete Pose")) { auto posesRef = m_target.objModel->GetPoses(); - std::vector poses{posesRef.begin(), posesRef.end()}; + std::vector poses{posesRef.begin(), posesRef.end()}; if (m_target.index < poses.size()) { poses.erase(poses.begin() + m_target.index); m_target.objModel->SetPoses(poses); @@ -1277,7 +1277,7 @@ void PopupState::DisplayInsert(Field2DModel* model) { } } -void glass::DisplayField2D(Field2DModel* model, const ImVec2& contentSize) { +void wpi::glass::DisplayField2D(Field2DModel* model, const ImVec2& contentSize) { auto& storage = GetStorage(); auto field = storage.GetData(); if (!field) { diff --git a/glass/src/lib/native/cpp/other/Log.cpp b/glass/src/lib/native/cpp/other/Log.cpp index 253328bdf5..d5191e27d8 100644 --- a/glass/src/lib/native/cpp/other/Log.cpp +++ b/glass/src/lib/native/cpp/other/Log.cpp @@ -8,7 +8,7 @@ #include -using namespace glass; +using namespace wpi::glass; LogData::LogData(size_t maxLines) : m_maxLines{maxLines} {} @@ -36,7 +36,7 @@ const std::string& LogData::GetBuffer() { return m_buf; } -void glass::DisplayLog(LogData* data, bool autoScroll) { +void wpi::glass::DisplayLog(LogData* data, bool autoScroll) { if (data->m_buf.empty()) { return; } diff --git a/glass/src/lib/native/cpp/other/Mechanism2D.cpp b/glass/src/lib/native/cpp/other/Mechanism2D.cpp index 81e9d2f737..464b0e3222 100644 --- a/glass/src/lib/native/cpp/other/Mechanism2D.cpp +++ b/glass/src/lib/native/cpp/other/Mechanism2D.cpp @@ -29,7 +29,7 @@ #include "wpi/units/length.hpp" #include "wpi/util/print.hpp" -using namespace glass; +using namespace wpi::glass; namespace gui = wpi::gui; @@ -37,19 +37,19 @@ namespace { // Per-frame data (not persistent) struct FrameData { - frc::Translation2d GetPosFromScreen(const ImVec2& cursor) const { + wpi::math::Translation2d GetPosFromScreen(const ImVec2& cursor) const { return { - units::meter_t{(std::clamp(cursor.x, min.x, max.x) - min.x) / scale}, - units::meter_t{(max.y - std::clamp(cursor.y, min.y, max.y)) / scale}}; + wpi::units::meter_t{(std::clamp(cursor.x, min.x, max.x) - min.x) / scale}, + wpi::units::meter_t{(max.y - std::clamp(cursor.y, min.y, max.y)) / scale}}; } - ImVec2 GetScreenFromPos(const frc::Translation2d& pos) const { + ImVec2 GetScreenFromPos(const wpi::math::Translation2d& pos) const { return {min.x + scale * pos.X().to(), max.y - scale * pos.Y().to()}; } void DrawObject(ImDrawList* drawList, MechanismObjectModel& objModel, - const frc::Pose2d& pose) const; + const wpi::math::Pose2d& pose) const; void DrawGroup(ImDrawList* drawList, MechanismObjectGroup& group, - const frc::Pose2d& pose) const; + const wpi::math::Pose2d& pose) const; // in screen coordinates ImVec2 imageMin; @@ -67,7 +67,7 @@ class BackgroundInfo { void DisplaySettings(); void LoadImage(); - FrameData GetFrameData(ImVec2 min, ImVec2 max, frc::Translation2d dims) const; + FrameData GetFrameData(ImVec2 min, ImVec2 max, wpi::math::Translation2d dims) const; void Draw(ImDrawList* drawList, const FrameData& frameData, ImU32 bgColor) const; @@ -126,7 +126,7 @@ void BackgroundInfo::LoadImage() { } bool BackgroundInfo::LoadImageImpl(const std::string& fn) { - wpi::print("GUI: loading background image '{}'\n", fn); + wpi::util::print("GUI: loading background image '{}'\n", fn); auto texture = gui::Texture::CreateFromFile(fn.c_str()); if (!texture) { std::puts("GUI: could not read background image"); @@ -140,7 +140,7 @@ bool BackgroundInfo::LoadImageImpl(const std::string& fn) { } FrameData BackgroundInfo::GetFrameData(ImVec2 min, ImVec2 max, - frc::Translation2d dims) const { + wpi::math::Translation2d dims) const { // fit the image into the window if (m_texture && m_imageHeight != 0 && m_imageWidth != 0) { gui::MaxFit(&min, &max, m_imageWidth, m_imageHeight); @@ -170,7 +170,7 @@ void BackgroundInfo::Draw(ImDrawList* drawList, const FrameData& frameData, } } -void glass::DisplayMechanism2DSettings(Mechanism2DModel* model) { +void wpi::glass::DisplayMechanism2DSettings(Mechanism2DModel* model) { auto& storage = GetStorage(); auto bg = storage.GetData(); if (!bg) { @@ -181,14 +181,14 @@ void glass::DisplayMechanism2DSettings(Mechanism2DModel* model) { } void FrameData::DrawObject(ImDrawList* drawList, MechanismObjectModel& objModel, - const frc::Pose2d& pose) const { + const wpi::math::Pose2d& pose) const { const char* type = objModel.GetType(); if (std::string_view{type} == "line") { auto startPose = - pose + frc::Transform2d{frc::Translation2d{}, objModel.GetAngle()}; + pose + wpi::math::Transform2d{wpi::math::Translation2d{}, objModel.GetAngle()}; auto endPose = startPose + - frc::Transform2d{frc::Translation2d{objModel.GetLength(), 0_m}, 0_deg}; + wpi::math::Transform2d{wpi::math::Translation2d{objModel.GetLength(), 0_m}, 0_deg}; drawList->AddLine(GetScreenFromPos(startPose.Translation()), GetScreenFromPos(endPose.Translation()), objModel.GetColor(), objModel.GetWeight()); @@ -197,12 +197,12 @@ void FrameData::DrawObject(ImDrawList* drawList, MechanismObjectModel& objModel, } void FrameData::DrawGroup(ImDrawList* drawList, MechanismObjectGroup& group, - const frc::Pose2d& pose) const { + const wpi::math::Pose2d& pose) const { group.ForEachObject( [&](auto& objModel) { DrawObject(drawList, objModel, pose); }); } -void glass::DisplayMechanism2D(Mechanism2DModel* model, +void wpi::glass::DisplayMechanism2D(Mechanism2DModel* model, const ImVec2& contentSize) { auto& storage = GetStorage(); auto bg = storage.GetData(); @@ -233,7 +233,7 @@ void glass::DisplayMechanism2D(Mechanism2DModel* model, // elements model->ForEachRoot([&](auto& rootModel) { frameData.DrawGroup(drawList, rootModel, - frc::Pose2d{rootModel.GetPosition(), 0_deg}); + wpi::math::Pose2d{rootModel.GetPosition(), 0_deg}); }); #if 0 diff --git a/glass/src/lib/native/cpp/other/PIDController.cpp b/glass/src/lib/native/cpp/other/PIDController.cpp index b9b6471dcc..57ade141d8 100644 --- a/glass/src/lib/native/cpp/other/PIDController.cpp +++ b/glass/src/lib/native/cpp/other/PIDController.cpp @@ -8,9 +8,9 @@ #include "wpi/glass/DataSource.hpp" -using namespace glass; +using namespace wpi::glass; -void glass::DisplayPIDController(PIDControllerModel* m) { +void wpi::glass::DisplayPIDController(PIDControllerModel* m) { if (auto name = m->GetName()) { ImGui::Text("%s", name); ImGui::Separator(); diff --git a/glass/src/lib/native/cpp/other/Plot.cpp b/glass/src/lib/native/cpp/other/Plot.cpp index 79226daa2a..7f9b116f87 100644 --- a/glass/src/lib/native/cpp/other/Plot.cpp +++ b/glass/src/lib/native/cpp/other/Plot.cpp @@ -39,7 +39,7 @@ #include "wpi/glass/support/EnumSetting.hpp" #include "wpi/glass/support/ExtraGuiWidgets.hpp" -using namespace glass; +using namespace wpi::glass; static constexpr int kAxisCount = 3; @@ -89,8 +89,8 @@ class PlotSeries { // source linkage DataSource* m_source = nullptr; bool m_digitalSource = false; - wpi::sig::ScopedConnection m_sourceCreatedConn; - wpi::sig::ScopedConnection m_newValueConn; + wpi::util::sig::ScopedConnection m_sourceCreatedConn; + wpi::util::sig::ScopedConnection m_newValueConn; std::string& m_id; // user settings @@ -292,7 +292,7 @@ void PlotSeries::SetSource(DataSource* source) { } void PlotSeries::AppendValue(double value, int64_t timeUs) { - double time = (timeUs != 0 ? timeUs : wpi::Now()) * 1.0e-6; + double time = (timeUs != 0 ? timeUs : wpi::util::Now()) * 1.0e-6; if (IsDigital()) { if (m_size < kMaxSize) { m_data[m_size] = ImPlotPoint{time, value}; @@ -350,7 +350,7 @@ PlotSeries::Action PlotSeries::EmitPlot(PlotView& view, double now, size_t i, CheckSource(); char label[128]; - wpi::format_to_n_c_str(label, sizeof(label), "{}###name{}_{}", GetName(), + wpi::util::format_to_n_c_str(label, sizeof(label), "{}###name{}_{}", GetName(), static_cast(i), static_cast(plotIndex)); int size = m_size; @@ -618,7 +618,7 @@ void Plot::EmitPlot(PlotView& view, double now, bool paused, size_t i) { } char label[128]; - wpi::format_to_n_c_str(label, sizeof(label), "{}###plot{}", m_name, + wpi::util::format_to_n_c_str(label, sizeof(label), "{}###plot{}", m_name, static_cast(i)); ImPlotFlags plotFlags = (m_legend ? 0 : ImPlotFlags_NoLegend) | @@ -865,7 +865,7 @@ void PlotView::Display() { } } - double now = wpi::Now() * 1.0e-6; + double now = wpi::util::Now() * 1.0e-6; for (size_t i = 0; i < m_plots.size(); ++i) { ImGui::PushID(i); m_plots[i]->EmitPlot(*this, now, m_provider->IsPaused(), i); @@ -976,14 +976,14 @@ void PlotView::Settings() { char name[64]; if (!plot->GetName().empty()) { - wpi::format_to_n_c_str(name, sizeof(name), "{}", plot->GetName().c_str()); + wpi::util::format_to_n_c_str(name, sizeof(name), "{}", plot->GetName().c_str()); } else { - wpi::format_to_n_c_str(name, sizeof(name), "Plot {}", + wpi::util::format_to_n_c_str(name, sizeof(name), "Plot {}", static_cast(i)); } char label[90]; - wpi::format_to_n_c_str(label, sizeof(label), "{}###header{}", name, + wpi::util::format_to_n_c_str(label, sizeof(label), "{}###header{}", name, static_cast(i)); bool open = ImGui::CollapsingHeader(label); @@ -1053,7 +1053,7 @@ void PlotProvider::DisplayMenu() { char id[32]; size_t numWindows = m_windows.size(); for (size_t i = 0; i <= numWindows; ++i) { - wpi::format_to_n_c_str(id, sizeof(id), "Plot <{}>", static_cast(i)); + wpi::util::format_to_n_c_str(id, sizeof(id), "Plot <{}>", static_cast(i)); bool match = false; for (size_t j = 0; j < numWindows; ++j) { diff --git a/glass/src/lib/native/cpp/other/ProfiledPIDController.cpp b/glass/src/lib/native/cpp/other/ProfiledPIDController.cpp index 391e893650..e7d7f38d07 100644 --- a/glass/src/lib/native/cpp/other/ProfiledPIDController.cpp +++ b/glass/src/lib/native/cpp/other/ProfiledPIDController.cpp @@ -8,9 +8,9 @@ #include "wpi/glass/DataSource.hpp" -using namespace glass; +using namespace wpi::glass; -void glass::DisplayProfiledPIDController(ProfiledPIDControllerModel* m) { +void wpi::glass::DisplayProfiledPIDController(ProfiledPIDControllerModel* m) { if (auto name = m->GetName()) { ImGui::Text("%s", name); ImGui::Separator(); diff --git a/glass/src/lib/native/cpp/other/StringChooser.cpp b/glass/src/lib/native/cpp/other/StringChooser.cpp index 00664ec5ee..418c997fca 100644 --- a/glass/src/lib/native/cpp/other/StringChooser.cpp +++ b/glass/src/lib/native/cpp/other/StringChooser.cpp @@ -6,9 +6,9 @@ #include -using namespace glass; +using namespace wpi::glass; -void glass::DisplayStringChooser(StringChooserModel* model) { +void wpi::glass::DisplayStringChooser(StringChooserModel* model) { auto& defaultValue = model->GetDefault(); auto& selected = model->GetSelected(); auto& active = model->GetActive(); diff --git a/glass/src/lib/native/cpp/other/Subsystem.cpp b/glass/src/lib/native/cpp/other/Subsystem.cpp index da03b60e99..e8a4ffaaa8 100644 --- a/glass/src/lib/native/cpp/other/Subsystem.cpp +++ b/glass/src/lib/native/cpp/other/Subsystem.cpp @@ -8,9 +8,9 @@ #include -using namespace glass; +using namespace wpi::glass; -void glass::DisplaySubsystem(SubsystemModel* m) { +void wpi::glass::DisplaySubsystem(SubsystemModel* m) { if (auto name = m->GetName()) { ImGui::Text("%s", name); ImGui::Separator(); diff --git a/glass/src/lib/native/cpp/support/ColorSetting.cpp b/glass/src/lib/native/cpp/support/ColorSetting.cpp index 640c68f603..e76ec57ab9 100644 --- a/glass/src/lib/native/cpp/support/ColorSetting.cpp +++ b/glass/src/lib/native/cpp/support/ColorSetting.cpp @@ -4,7 +4,7 @@ #include "wpi/glass/support/ColorSetting.hpp" -using namespace glass; +using namespace wpi::glass; ColorSetting::ColorSetting(std::vector& color) : m_color{color} { m_color.resize(4); diff --git a/glass/src/lib/native/cpp/support/EnumSetting.cpp b/glass/src/lib/native/cpp/support/EnumSetting.cpp index 8e48603cdd..a98493ee00 100644 --- a/glass/src/lib/native/cpp/support/EnumSetting.cpp +++ b/glass/src/lib/native/cpp/support/EnumSetting.cpp @@ -8,7 +8,7 @@ #include -using namespace glass; +using namespace wpi::glass; EnumSetting::EnumSetting(std::string& str, int defaultValue, std::initializer_list choices) diff --git a/glass/src/lib/native/cpp/support/ExpressionParser.cpp b/glass/src/lib/native/cpp/support/ExpressionParser.cpp index 26dbf6eb60..dd2b0bb723 100644 --- a/glass/src/lib/native/cpp/support/ExpressionParser.cpp +++ b/glass/src/lib/native/cpp/support/ExpressionParser.cpp @@ -12,7 +12,7 @@ #include "wpi/util/StringExtras.hpp" #include "wpi/util/expected" -namespace glass::expression { +namespace wpi::glass::expression { enum class TokenType { Number, @@ -74,7 +74,7 @@ class Lexer { return Token(TokenType::CloseParen); default: currentIdx--; - if (wpi::isDigit(c) || c == '.') { + if (wpi::util::isDigit(c) || c == '.') { return nextNumber(); } return Token(TokenType::Error, &input[currentIdx], 1); @@ -92,7 +92,7 @@ class Lexer { Token nextNumber() { // Read whole part bool hasDigitsBeforeDecimal = false; - while (wpi::isDigit(input[currentIdx])) { + while (wpi::util::isDigit(input[currentIdx])) { currentIdx++; hasDigitsBeforeDecimal = true; } @@ -106,12 +106,12 @@ class Lexer { currentIdx++; // Report a single '.' with no digits as an error - if (!hasDigitsBeforeDecimal && !wpi::isDigit(input[currentIdx])) { + if (!hasDigitsBeforeDecimal && !wpi::util::isDigit(input[currentIdx])) { // Report the decimal as the unexpected char return Token(TokenType::Error, &input[currentIdx - 1], 1); } - while (wpi::isDigit(input[currentIdx])) { + while (wpi::util::isDigit(input[currentIdx])) { currentIdx++; } @@ -205,31 +205,31 @@ std::optional ValueFromString(std::string_view str); template <> std::optional ValueFromString(std::string_view str) { - return wpi::parse_integer(str, 10); + return wpi::util::parse_integer(str, 10); } template <> std::optional ValueFromString(std::string_view str) { - return wpi::parse_float(str); + return wpi::util::parse_float(str); } template <> std::optional ValueFromString(std::string_view str) { - return wpi::parse_float(str); + return wpi::util::parse_float(str); } template -wpi::expected EvalAll(std::stack& operStack, +wpi::util::expected EvalAll(std::stack& operStack, std::stack& valStack) { while (!operStack.empty()) { if (valStack.size() < 2) { - return wpi::unexpected("Missing operand"); + return wpi::util::unexpected("Missing operand"); } ApplyOperator(valStack, operStack.top()); operStack.pop(); } if (valStack.empty()) { - return wpi::unexpected("No value"); + return wpi::util::unexpected("No value"); } // Intentionally leaves the result value on top of valStack so unmatched @@ -238,7 +238,7 @@ wpi::expected EvalAll(std::stack& operStack, } template -wpi::expected ParseExpr(Lexer& lexer, bool insideParen) { +wpi::util::expected ParseExpr(Lexer& lexer, bool insideParen) { std::stack operStack; std::stack valStack; @@ -257,7 +257,7 @@ wpi::expected ParseExpr(Lexer& lexer, bool insideParen) { // is probably not what the user intended in this case, so give them an // error. if (prevType == TokenType::Number) { - return wpi::unexpected("Missing operator"); + return wpi::util::unexpected("Missing operator"); } // Implicit multiplication. Ex: "2(4 + 5)" @@ -270,7 +270,7 @@ wpi::expected ParseExpr(Lexer& lexer, bool insideParen) { if (value) { valStack.push(value.value()); } else { - return wpi::unexpected("Invalid number"); + return wpi::util::unexpected("Invalid number"); } break; @@ -282,7 +282,7 @@ wpi::expected ParseExpr(Lexer& lexer, bool insideParen) { operStack.push(Operator::Multiply); } - wpi::expected result = ParseExpr(lexer, true); + wpi::util::expected result = ParseExpr(lexer, true); if (!result) { return result; } @@ -293,7 +293,7 @@ wpi::expected ParseExpr(Lexer& lexer, bool insideParen) { if (nextType == TokenType::End) { goto end; // Act as if closed at end of expression } - return wpi::unexpected("Expected )"); + return wpi::util::unexpected("Expected )"); } break; } @@ -307,7 +307,7 @@ wpi::expected ParseExpr(Lexer& lexer, bool insideParen) { // Acts as if there was open paren at start of expression. EvalAll will // clear both stacks, and leave the result value on top of valStack. // This makes sure everything inside the parentheses is evaluated first - wpi::expected result = EvalAll(operStack, valStack); + wpi::util::expected result = EvalAll(operStack, valStack); if (!result) { return result; } @@ -315,7 +315,7 @@ wpi::expected ParseExpr(Lexer& lexer, bool insideParen) { } case TokenType::Error: - return wpi::unexpected(std::string("Unexpected character: ") + return wpi::util::unexpected(std::string("Unexpected character: ") .append(token.str, token.strLen)); default: @@ -342,7 +342,7 @@ wpi::expected ParseExpr(Lexer& lexer, bool insideParen) { precedence < prevPrecedence) { operStack.pop(); if (valStack.size() < 2) { - return wpi::unexpected("Missing operand"); + return wpi::util::unexpected("Missing operand"); } ApplyOperator(valStack, prevOp); } else { @@ -363,13 +363,13 @@ end: // expr is null-terminated string, as ImGui::inputText() uses template -wpi::expected TryParseExpr(const char* expr) { +wpi::util::expected TryParseExpr(const char* expr) { Lexer lexer(expr, std::is_integral_v); return ParseExpr(lexer, false); } -template wpi::expected TryParseExpr(const char*); -template wpi::expected TryParseExpr(const char*); -template wpi::expected TryParseExpr(const char*); +template wpi::util::expected TryParseExpr(const char*); +template wpi::util::expected TryParseExpr(const char*); +template wpi::util::expected TryParseExpr(const char*); -} // namespace glass::expression +} // namespace wpi::glass::expression diff --git a/glass/src/lib/native/cpp/support/ExtraGuiWidgets.cpp b/glass/src/lib/native/cpp/support/ExtraGuiWidgets.cpp index 98f45dbbfb..0950b1529a 100644 --- a/glass/src/lib/native/cpp/support/ExtraGuiWidgets.cpp +++ b/glass/src/lib/native/cpp/support/ExtraGuiWidgets.cpp @@ -15,7 +15,7 @@ #include "wpi/glass/support/ExpressionParser.hpp" #include "wpi/util/DenseMap.hpp" -namespace glass { +namespace wpi::glass { void DrawLEDSources(const int* values, BooleanSource** sources, int numValues, int cols, const ImU32* colors, float size, float spacing, @@ -228,7 +228,7 @@ struct InputExprState { char inputBuffer[kBufferSize]; }; -static wpi::DenseMap exprStates; +static wpi::util::DenseMap exprStates; // Shared string buffer for inactive inputs static char previewBuffer[kBufferSize]; @@ -267,7 +267,7 @@ bool InputExpr(const char* label, V* v, const char* format, } // Attempt to parse current value - auto result = glass::expression::TryParseExpr(state.inputBuffer); + auto result = wpi::glass::expression::TryParseExpr(state.inputBuffer); if (result) { *v = result.value(); } else if (active) { @@ -289,4 +289,4 @@ template bool InputExpr(const char*, int64_t*, const char*, template bool InputExpr(const char*, float*, const char*, ImGuiInputTextFlags); template bool InputExpr(const char*, double*, const char*, ImGuiInputTextFlags); -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/lib/native/cpp/support/NameSetting.cpp b/glass/src/lib/native/cpp/support/NameSetting.cpp index 4321b43432..8abfaf0d1d 100644 --- a/glass/src/lib/native/cpp/support/NameSetting.cpp +++ b/glass/src/lib/native/cpp/support/NameSetting.cpp @@ -9,50 +9,50 @@ #include "wpi/util/StringExtras.hpp" -using namespace glass; +using namespace wpi::glass; void NameSetting::GetName(char* buf, size_t size, const char* defaultName) const { if (!m_name.empty()) { - wpi::format_to_n_c_str(buf, size, "{}", m_name); + wpi::util::format_to_n_c_str(buf, size, "{}", m_name); } else { - wpi::format_to_n_c_str(buf, size, "{}", defaultName); + wpi::util::format_to_n_c_str(buf, size, "{}", defaultName); } } void NameSetting::GetName(char* buf, size_t size, const char* defaultName, int index) const { if (!m_name.empty()) { - wpi::format_to_n_c_str(buf, size, "{} [{}]", m_name, index); + wpi::util::format_to_n_c_str(buf, size, "{} [{}]", m_name, index); } else { - wpi::format_to_n_c_str(buf, size, "{}[{}]", defaultName, index); + wpi::util::format_to_n_c_str(buf, size, "{}[{}]", defaultName, index); } } void NameSetting::GetName(char* buf, size_t size, const char* defaultName, int index, int index2) const { if (!m_name.empty()) { - wpi::format_to_n_c_str(buf, size, "{} [{},{}]", m_name, index, index2); + wpi::util::format_to_n_c_str(buf, size, "{} [{},{}]", m_name, index, index2); } else { - wpi::format_to_n_c_str(buf, size, "{}[{},{}]", defaultName, index, index2); + wpi::util::format_to_n_c_str(buf, size, "{}[{},{}]", defaultName, index, index2); } } void NameSetting::GetLabel(char* buf, size_t size, const char* defaultName) const { if (!m_name.empty()) { - wpi::format_to_n_c_str(buf, size, "{}###Name{}", m_name, defaultName); + wpi::util::format_to_n_c_str(buf, size, "{}###Name{}", m_name, defaultName); } else { - wpi::format_to_n_c_str(buf, size, "{}###Name{}", defaultName, defaultName); + wpi::util::format_to_n_c_str(buf, size, "{}###Name{}", defaultName, defaultName); } } void NameSetting::GetLabel(char* buf, size_t size, const char* defaultName, int index) const { if (!m_name.empty()) { - wpi::format_to_n_c_str(buf, size, "{} [{}]###Name{}", m_name, index, index); + wpi::util::format_to_n_c_str(buf, size, "{} [{}]###Name{}", m_name, index, index); } else { - wpi::format_to_n_c_str(buf, size, "{}[{}]###Name{}", defaultName, index, + wpi::util::format_to_n_c_str(buf, size, "{}[{}]###Name{}", defaultName, index, index); } } @@ -60,24 +60,24 @@ void NameSetting::GetLabel(char* buf, size_t size, const char* defaultName, void NameSetting::GetLabel(char* buf, size_t size, const char* defaultName, int index, int index2) const { if (!m_name.empty()) { - wpi::format_to_n_c_str(buf, size, "{} [{},{}]###Name{}", m_name, index, + wpi::util::format_to_n_c_str(buf, size, "{} [{},{}]###Name{}", m_name, index, index2, index); } else { - wpi::format_to_n_c_str(buf, size, "{}[{},{}]###Name{}", defaultName, index, + wpi::util::format_to_n_c_str(buf, size, "{}[{},{}]###Name{}", defaultName, index, index2, index); } } void NameSetting::PushEditNameId(int index) { char id[64]; - wpi::format_to_n_c_str(id, sizeof(id), "Name{}", index); + wpi::util::format_to_n_c_str(id, sizeof(id), "Name{}", index); ImGui::PushID(id); } void NameSetting::PushEditNameId(const char* name) { char id[128]; - wpi::format_to_n_c_str(id, sizeof(id), "Name{}", name); + wpi::util::format_to_n_c_str(id, sizeof(id), "Name{}", name); ImGui::PushID(id); } @@ -86,7 +86,7 @@ bool NameSetting::PopupEditName(int index) { bool rv = false; char id[64]; - wpi::format_to_n_c_str(id, sizeof(id), "Name{}", index); + wpi::util::format_to_n_c_str(id, sizeof(id), "Name{}", index); if (ImGui::BeginPopupContextItem(id)) { ImGui::Text("Edit name:"); @@ -106,7 +106,7 @@ bool NameSetting::PopupEditName(const char* name) { bool rv = false; char id[128]; - wpi::format_to_n_c_str(id, sizeof(id), "Name{}", name); + wpi::util::format_to_n_c_str(id, sizeof(id), "Name{}", name); if (ImGui::BeginPopupContextItem(id)) { ImGui::Text("Edit name:"); diff --git a/glass/src/lib/native/include/wpi/glass/Context.hpp b/glass/src/lib/native/include/wpi/glass/Context.hpp index f343d33582..d7f764c7ea 100644 --- a/glass/src/lib/native/include/wpi/glass/Context.hpp +++ b/glass/src/lib/native/include/wpi/glass/Context.hpp @@ -12,7 +12,7 @@ #include -namespace glass { +namespace wpi::glass { class Context; class Storage; @@ -205,4 +205,4 @@ bool PopupEditName(const char* label, std::string* name); bool ItemEditName(std::string* name); -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/lib/native/include/wpi/glass/ContextInternal.hpp b/glass/src/lib/native/include/wpi/glass/ContextInternal.hpp index 972dfd8b19..b5003382f7 100644 --- a/glass/src/lib/native/include/wpi/glass/ContextInternal.hpp +++ b/glass/src/lib/native/include/wpi/glass/ContextInternal.hpp @@ -15,7 +15,7 @@ #include "wpi/util/SmallVector.hpp" #include "wpi/util/StringMap.hpp" -namespace glass { +namespace wpi::glass { class DataSource; @@ -31,10 +31,10 @@ class Context { std::string storageLoadDir = "."; std::string storageAutoSaveDir = "."; std::string storageName = "imgui"; - wpi::SmallVector storageStack; - wpi::StringMap storageRoots; - wpi::StringMap deviceHidden; - wpi::StringMap sources; + wpi::util::SmallVector storageStack; + wpi::util::StringMap storageRoots; + wpi::util::StringMap deviceHidden; + wpi::util::StringMap sources; Storage& sourceNameStorage; uint64_t zeroTime = 0; bool isPlatformSaveDir = false; @@ -42,4 +42,4 @@ class Context { extern Context* gContext; -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/lib/native/include/wpi/glass/DataSource.hpp b/glass/src/lib/native/include/wpi/glass/DataSource.hpp index 9801d9ae67..a7f1a16397 100644 --- a/glass/src/lib/native/include/wpi/glass/DataSource.hpp +++ b/glass/src/lib/native/include/wpi/glass/DataSource.hpp @@ -18,7 +18,7 @@ #include "wpi/util/SmallVector.hpp" #include "wpi/util/spinlock.hpp" -namespace glass { +namespace wpi::glass { /** * A data source for numeric/boolean data. @@ -62,7 +62,7 @@ class DataSource { static DataSource* Find(std::string_view id); - static wpi::sig::Signal sourceCreated; + static wpi::util::sig::Signal sourceCreated; private: std::string m_id; @@ -78,7 +78,7 @@ class DataSource { virtual void DragDropTooltip() const; - mutable wpi::spinlock m_valueMutex; + mutable wpi::util::spinlock m_valueMutex; int64_t m_valueTime = 0; }; @@ -113,7 +113,7 @@ class ValueSource : public DataSource { return m_value; } - wpi::sig::SignalBase valueChanged; + wpi::util::sig::SignalBase valueChanged; private: T m_value = 0; @@ -202,16 +202,16 @@ class StringSource : public DataSource { return m_value; } - std::string_view GetValue(wpi::SmallVectorImpl& buf) const { + std::string_view GetValue(wpi::util::SmallVectorImpl& buf) const { std::scoped_lock lock{m_valueMutex}; buf.assign(m_value.begin(), m_value.end()); return {buf.begin(), buf.end()}; } - wpi::sig::SignalBase valueChanged; + wpi::util::sig::SignalBase valueChanged; private: std::string m_value; }; -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/lib/native/include/wpi/glass/MainMenuBar.hpp b/glass/src/lib/native/include/wpi/glass/MainMenuBar.hpp index cfcd4db6aa..513e88118d 100644 --- a/glass/src/lib/native/include/wpi/glass/MainMenuBar.hpp +++ b/glass/src/lib/native/include/wpi/glass/MainMenuBar.hpp @@ -10,7 +10,7 @@ #include "wpi/gui/portable-file-dialogs.h" -namespace glass { +namespace wpi::glass { /** * GUI main menu bar. @@ -53,4 +53,4 @@ class MainMenuBar { std::unique_ptr m_saveFolder; }; -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/lib/native/include/wpi/glass/Model.hpp b/glass/src/lib/native/include/wpi/glass/Model.hpp index 28f546fe20..a67888b507 100644 --- a/glass/src/lib/native/include/wpi/glass/Model.hpp +++ b/glass/src/lib/native/include/wpi/glass/Model.hpp @@ -4,7 +4,7 @@ #pragma once -namespace glass { +namespace wpi::glass { class Model { public: @@ -19,4 +19,4 @@ class Model { virtual bool IsReadOnly(); }; -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/lib/native/include/wpi/glass/Provider.hpp b/glass/src/lib/native/include/wpi/glass/Provider.hpp index 8857f3300b..69164fddaf 100644 --- a/glass/src/lib/native/include/wpi/glass/Provider.hpp +++ b/glass/src/lib/native/include/wpi/glass/Provider.hpp @@ -16,7 +16,7 @@ #include "wpi/glass/WindowManager.hpp" #include "wpi/gui/wpigui.hpp" -namespace glass { +namespace wpi::glass { class Storage; @@ -221,4 +221,4 @@ class Provider : public WindowManager { virtual void Show(ViewEntry* entry, Window* window) = 0; }; -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/lib/native/include/wpi/glass/Storage.hpp b/glass/src/lib/native/include/wpi/glass/Storage.hpp index c4e3aced33..ea611ffdce 100644 --- a/glass/src/lib/native/include/wpi/glass/Storage.hpp +++ b/glass/src/lib/native/include/wpi/glass/Storage.hpp @@ -18,7 +18,7 @@ #include "wpi/util/iterator_range.hpp" #include "wpi/util/json_fwd.hpp" -namespace glass { +namespace wpi::glass { namespace detail { template @@ -103,7 +103,7 @@ class Storage { void Reset(Type newType); }; - using ValueMap = wpi::StringMap>; + using ValueMap = wpi::util::StringMap>; template using ChildIterator = detail::ChildIterator; @@ -173,15 +173,15 @@ class Storage { ValueMap& GetValues() { return m_values; } const ValueMap& GetValues() const { return m_values; } - wpi::iterator_range> GetChildren(); + wpi::util::iterator_range> GetChildren(); /** * Erases all children (at top level). */ void EraseChildren(); - bool FromJson(const wpi::json& json, const char* filename); - wpi::json ToJson() const; + bool FromJson(const wpi::util::json& json, const char* filename); + wpi::util::json ToJson() const; /** * Clear settings (set to default). Calls custom clear function (if set), @@ -213,8 +213,8 @@ class Storage { * @param toJson replacement for ToJson() */ void SetCustomJson( - std::function fromJson, - std::function toJson) { + std::function fromJson, + std::function toJson) { m_fromJson = std::move(fromJson); m_toJson = std::move(toJson); } @@ -230,8 +230,8 @@ class Storage { private: mutable ValueMap m_values; std::shared_ptr m_data; - std::function m_fromJson; - std::function m_toJson; + std::function m_fromJson; + std::function m_toJson; std::function m_clear; std::function m_apply; }; @@ -281,8 +281,8 @@ class ChildIterator { } // namespace detail inline auto Storage::GetChildren() - -> wpi::iterator_range> { + -> wpi::util::iterator_range> { return {{m_values.begin(), m_values.end()}, {m_values.end(), m_values.end()}}; } -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/lib/native/include/wpi/glass/View.hpp b/glass/src/lib/native/include/wpi/glass/View.hpp index 8453a01dfb..c81c64a360 100644 --- a/glass/src/lib/native/include/wpi/glass/View.hpp +++ b/glass/src/lib/native/include/wpi/glass/View.hpp @@ -8,7 +8,7 @@ #include "wpi/util/FunctionExtras.hpp" -namespace glass { +namespace wpi::glass { /** * A view is the contents of a window (1:1 mapping). @@ -54,6 +54,6 @@ class View { * @param display Display function * @return unique_ptr to View */ -std::unique_ptr MakeFunctionView(wpi::unique_function display); +std::unique_ptr MakeFunctionView(wpi::util::unique_function display); -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/lib/native/include/wpi/glass/Window.hpp b/glass/src/lib/native/include/wpi/glass/Window.hpp index 77bab71454..f8bf482221 100644 --- a/glass/src/lib/native/include/wpi/glass/Window.hpp +++ b/glass/src/lib/native/include/wpi/glass/Window.hpp @@ -13,7 +13,7 @@ #include "wpi/glass/View.hpp" -namespace glass { +namespace wpi::glass { class Storage; @@ -137,4 +137,4 @@ class Window { ImVec2 m_padding; }; -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/lib/native/include/wpi/glass/WindowManager.hpp b/glass/src/lib/native/include/wpi/glass/WindowManager.hpp index 5e60759420..c7dfdf311c 100644 --- a/glass/src/lib/native/include/wpi/glass/WindowManager.hpp +++ b/glass/src/lib/native/include/wpi/glass/WindowManager.hpp @@ -11,7 +11,7 @@ #include "wpi/glass/Window.hpp" #include "wpi/util/FunctionExtras.hpp" -namespace glass { +namespace wpi::glass { class Storage; @@ -64,7 +64,7 @@ class WindowManager { * @param display window contents display function * @param defaultVisibility default window visibility */ - Window* AddWindow(std::string_view id, wpi::unique_function display, + Window* AddWindow(std::string_view id, wpi::util::unique_function display, Window::Visibility defaultVisibility = Window::kShow); /** @@ -142,4 +142,4 @@ class WindowManager { void DisplayWindows(); }; -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/lib/native/include/wpi/glass/hardware/AnalogInput.hpp b/glass/src/lib/native/include/wpi/glass/hardware/AnalogInput.hpp index c5e48160da..b331e91983 100644 --- a/glass/src/lib/native/include/wpi/glass/hardware/AnalogInput.hpp +++ b/glass/src/lib/native/include/wpi/glass/hardware/AnalogInput.hpp @@ -9,7 +9,7 @@ #include "wpi/glass/Model.hpp" #include "wpi/util/function_ref.hpp" -namespace glass { +namespace wpi::glass { class DoubleSource; @@ -25,11 +25,11 @@ class AnalogInputModel : public Model { class AnalogInputsModel : public Model { public: virtual void ForEachAnalogInput( - wpi::function_ref func) = 0; + wpi::util::function_ref func) = 0; }; void DisplayAnalogInput(AnalogInputModel* model, int index); void DisplayAnalogInputs(AnalogInputsModel* model, std::string_view noneMsg = "No analog inputs"); -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/lib/native/include/wpi/glass/hardware/DIO.hpp b/glass/src/lib/native/include/wpi/glass/hardware/DIO.hpp index 57474ddc2c..878344ece3 100644 --- a/glass/src/lib/native/include/wpi/glass/hardware/DIO.hpp +++ b/glass/src/lib/native/include/wpi/glass/hardware/DIO.hpp @@ -9,7 +9,7 @@ #include "wpi/glass/Model.hpp" #include "wpi/util/function_ref.hpp" -namespace glass { +namespace wpi::glass { class EncoderModel; class BooleanSource; @@ -53,11 +53,11 @@ class DIOModel : public Model { class DIOsModel : public Model { public: virtual void ForEachDIO( - wpi::function_ref func) = 0; + wpi::util::function_ref func) = 0; }; void DisplayDIO(DIOModel* model, int index, bool outputsEnabled); void DisplayDIOs(DIOsModel* model, bool outputsEnabled, std::string_view noneMsg = "No Digital I/O"); -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/lib/native/include/wpi/glass/hardware/Encoder.hpp b/glass/src/lib/native/include/wpi/glass/hardware/Encoder.hpp index 99ffdecbb4..ebf1eccc5f 100644 --- a/glass/src/lib/native/include/wpi/glass/hardware/Encoder.hpp +++ b/glass/src/lib/native/include/wpi/glass/hardware/Encoder.hpp @@ -9,7 +9,7 @@ #include "wpi/glass/Model.hpp" #include "wpi/util/function_ref.hpp" -namespace glass { +namespace wpi::glass { class BooleanSource; class DoubleSource; @@ -48,11 +48,11 @@ class EncoderModel : public Model { class EncodersModel : public Model { public: virtual void ForEachEncoder( - wpi::function_ref func) = 0; + wpi::util::function_ref func) = 0; }; void DisplayEncoder(EncoderModel* model); void DisplayEncoders(EncodersModel* model, std::string_view noneMsg = "No encoders"); -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/lib/native/include/wpi/glass/hardware/Gyro.hpp b/glass/src/lib/native/include/wpi/glass/hardware/Gyro.hpp index 9d8e601940..d2ed977168 100644 --- a/glass/src/lib/native/include/wpi/glass/hardware/Gyro.hpp +++ b/glass/src/lib/native/include/wpi/glass/hardware/Gyro.hpp @@ -6,7 +6,7 @@ #include "wpi/glass/Model.hpp" -namespace glass { +namespace wpi::glass { class DoubleSource; class GyroModel : public Model { public: @@ -17,4 +17,4 @@ class GyroModel : public Model { virtual void SetAngle(double angle) = 0; }; void DisplayGyro(GyroModel* m); -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/lib/native/include/wpi/glass/hardware/LEDDisplay.hpp b/glass/src/lib/native/include/wpi/glass/hardware/LEDDisplay.hpp index 004d3dfeef..d8367b2623 100644 --- a/glass/src/lib/native/include/wpi/glass/hardware/LEDDisplay.hpp +++ b/glass/src/lib/native/include/wpi/glass/hardware/LEDDisplay.hpp @@ -9,14 +9,14 @@ #include "wpi/glass/Model.hpp" #include "wpi/util/function_ref.hpp" -namespace wpi { +namespace wpi::util { template class SmallVectorImpl; } // namespace wpi -namespace glass { +namespace wpi::glass { -class LEDDisplayModel : public glass::Model { +class LEDDisplayModel : public wpi::glass::Model { public: struct Data { uint8_t r; @@ -24,18 +24,18 @@ class LEDDisplayModel : public glass::Model { uint8_t b; }; - virtual std::span GetData(wpi::SmallVectorImpl& buf) = 0; + virtual std::span GetData(wpi::util::SmallVectorImpl& buf) = 0; }; -class LEDDisplaysModel : public glass::Model { +class LEDDisplaysModel : public wpi::glass::Model { public: virtual size_t GetNumLEDDisplays() = 0; virtual void ForEachLEDDisplay( - wpi::function_ref func) = 0; + wpi::util::function_ref func) = 0; }; void DisplayLEDDisplay(LEDDisplayModel* model, int index); void DisplayLEDDisplays(LEDDisplaysModel* model); -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/lib/native/include/wpi/glass/hardware/MotorController.hpp b/glass/src/lib/native/include/wpi/glass/hardware/MotorController.hpp index 232305de3e..524c1d4547 100644 --- a/glass/src/lib/native/include/wpi/glass/hardware/MotorController.hpp +++ b/glass/src/lib/native/include/wpi/glass/hardware/MotorController.hpp @@ -6,7 +6,7 @@ #include "wpi/glass/Model.hpp" -namespace glass { +namespace wpi::glass { class DoubleSource; class MotorControllerModel : public Model { public: @@ -16,4 +16,4 @@ class MotorControllerModel : public Model { virtual void SetPercent(double value) = 0; }; void DisplayMotorController(MotorControllerModel* m); -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/lib/native/include/wpi/glass/hardware/PWM.hpp b/glass/src/lib/native/include/wpi/glass/hardware/PWM.hpp index 4833078912..997458f59c 100644 --- a/glass/src/lib/native/include/wpi/glass/hardware/PWM.hpp +++ b/glass/src/lib/native/include/wpi/glass/hardware/PWM.hpp @@ -9,7 +9,7 @@ #include "wpi/glass/Model.hpp" #include "wpi/util/function_ref.hpp" -namespace glass { +namespace wpi::glass { class DoubleSource; @@ -23,11 +23,11 @@ class PWMModel : public Model { class PWMsModel : public Model { public: virtual void ForEachPWM( - wpi::function_ref func) = 0; + wpi::util::function_ref func) = 0; }; void DisplayPWM(PWMModel* model, int index, bool outputsEnabled); void DisplayPWMs(PWMsModel* model, bool outputsEnabled, std::string_view noneMsg = "No PWM outputs"); -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/lib/native/include/wpi/glass/hardware/Pneumatic.hpp b/glass/src/lib/native/include/wpi/glass/hardware/Pneumatic.hpp index 53be6bc1b5..486a5f6b7d 100644 --- a/glass/src/lib/native/include/wpi/glass/hardware/Pneumatic.hpp +++ b/glass/src/lib/native/include/wpi/glass/hardware/Pneumatic.hpp @@ -11,7 +11,7 @@ #include "wpi/glass/Model.hpp" #include "wpi/util/function_ref.hpp" -namespace glass { +namespace wpi::glass { class BooleanSource; class DoubleSource; @@ -41,7 +41,7 @@ class PneumaticControlModel : public Model { virtual CompressorModel* GetCompressor() = 0; virtual void ForEachSolenoid( - wpi::function_ref func) = 0; + wpi::util::function_ref func) = 0; virtual std::string_view GetName() = 0; }; @@ -49,7 +49,7 @@ class PneumaticControlModel : public Model { class PneumaticControlsModel : public Model { public: virtual void ForEachPneumaticControl( - wpi::function_ref + wpi::util::function_ref func) = 0; }; @@ -77,4 +77,4 @@ void DisplayCompressorDevice(CompressorModel* model, int index, void DisplayCompressorsDevice(PneumaticControlsModel* model, bool outputsEnabled); -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/lib/native/include/wpi/glass/hardware/PowerDistribution.hpp b/glass/src/lib/native/include/wpi/glass/hardware/PowerDistribution.hpp index 011e4b3a34..13802f32eb 100644 --- a/glass/src/lib/native/include/wpi/glass/hardware/PowerDistribution.hpp +++ b/glass/src/lib/native/include/wpi/glass/hardware/PowerDistribution.hpp @@ -9,7 +9,7 @@ #include "wpi/glass/Model.hpp" #include "wpi/util/function_ref.hpp" -namespace glass { +namespace wpi::glass { class DoubleSource; @@ -29,7 +29,7 @@ class PowerDistributionModel : public Model { class PowerDistributionsModel : public Model { public: virtual void ForEachPowerDistribution( - wpi::function_ref + wpi::util::function_ref func) = 0; }; @@ -38,4 +38,4 @@ void DisplayPowerDistributions( PowerDistributionsModel* model, std::string_view noneMsg = "No Power Distributions"); -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/lib/native/include/wpi/glass/hardware/RoboRio.hpp b/glass/src/lib/native/include/wpi/glass/hardware/RoboRio.hpp index 7bc899eca1..61241b63d6 100644 --- a/glass/src/lib/native/include/wpi/glass/hardware/RoboRio.hpp +++ b/glass/src/lib/native/include/wpi/glass/hardware/RoboRio.hpp @@ -6,7 +6,7 @@ #include "wpi/glass/Model.hpp" -namespace glass { +namespace wpi::glass { class BooleanSource; class DoubleSource; @@ -38,4 +38,4 @@ class RoboRioModel : public Model { void DisplayRoboRio(RoboRioModel* model); -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/lib/native/include/wpi/glass/other/Alerts.hpp b/glass/src/lib/native/include/wpi/glass/other/Alerts.hpp index df4013c2c7..3be03da10a 100644 --- a/glass/src/lib/native/include/wpi/glass/other/Alerts.hpp +++ b/glass/src/lib/native/include/wpi/glass/other/Alerts.hpp @@ -9,7 +9,7 @@ #include "wpi/glass/Model.hpp" -namespace glass { +namespace wpi::glass { class AlertsModel : public Model { public: @@ -20,4 +20,4 @@ class AlertsModel : public Model { void DisplayAlerts(AlertsModel* model); -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/lib/native/include/wpi/glass/other/CommandScheduler.hpp b/glass/src/lib/native/include/wpi/glass/other/CommandScheduler.hpp index 475336f9ff..d320f928d5 100644 --- a/glass/src/lib/native/include/wpi/glass/other/CommandScheduler.hpp +++ b/glass/src/lib/native/include/wpi/glass/other/CommandScheduler.hpp @@ -9,7 +9,7 @@ #include "wpi/glass/Model.hpp" -namespace glass { +namespace wpi::glass { class DataSource; class CommandSchedulerModel : public Model { public: @@ -18,4 +18,4 @@ class CommandSchedulerModel : public Model { virtual void CancelCommand(size_t index) = 0; }; void DisplayCommandScheduler(CommandSchedulerModel* m); -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/lib/native/include/wpi/glass/other/CommandSelector.hpp b/glass/src/lib/native/include/wpi/glass/other/CommandSelector.hpp index b7caf19a8a..3f1662e94f 100644 --- a/glass/src/lib/native/include/wpi/glass/other/CommandSelector.hpp +++ b/glass/src/lib/native/include/wpi/glass/other/CommandSelector.hpp @@ -6,7 +6,7 @@ #include "wpi/glass/Model.hpp" -namespace glass { +namespace wpi::glass { class BooleanSource; class CommandSelectorModel : public Model { public: @@ -15,4 +15,4 @@ class CommandSelectorModel : public Model { virtual void SetRunning(bool run) = 0; }; void DisplayCommandSelector(CommandSelectorModel* m); -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/lib/native/include/wpi/glass/other/DeviceTree.hpp b/glass/src/lib/native/include/wpi/glass/other/DeviceTree.hpp index 72be8d25c0..dcc6648734 100644 --- a/glass/src/lib/native/include/wpi/glass/other/DeviceTree.hpp +++ b/glass/src/lib/native/include/wpi/glass/other/DeviceTree.hpp @@ -13,7 +13,7 @@ #include "wpi/glass/Model.hpp" #include "wpi/util/FunctionExtras.hpp" -namespace glass { +namespace wpi::glass { class DataSource; @@ -22,7 +22,7 @@ class DataSource; */ class DeviceTreeModel : public Model { public: - using DisplayFunc = wpi::unique_function; + using DisplayFunc = wpi::util::unique_function; /** * Add a display to the device tree. @@ -137,4 +137,4 @@ bool DeviceInt(const char* name, bool readonly, int32_t* value, bool DeviceLong(const char* name, bool readonly, int64_t* value, const DataSource* source = nullptr); -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/lib/native/include/wpi/glass/other/Drive.hpp b/glass/src/lib/native/include/wpi/glass/other/Drive.hpp index a1f6ef4cbf..39835c9a4f 100644 --- a/glass/src/lib/native/include/wpi/glass/other/Drive.hpp +++ b/glass/src/lib/native/include/wpi/glass/other/Drive.hpp @@ -14,7 +14,7 @@ struct ImVec2; -namespace glass { +namespace wpi::glass { class DoubleSource; class DriveModel : public Model { public: @@ -37,4 +37,4 @@ class DriveModel : public Model { virtual double GetRotation() const = 0; }; void DisplayDrive(DriveModel* m); -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/lib/native/include/wpi/glass/other/FMS.hpp b/glass/src/lib/native/include/wpi/glass/other/FMS.hpp index 05e4d399b9..bcdef5c087 100644 --- a/glass/src/lib/native/include/wpi/glass/other/FMS.hpp +++ b/glass/src/lib/native/include/wpi/glass/other/FMS.hpp @@ -8,12 +8,12 @@ #include "wpi/glass/Model.hpp" -namespace wpi { +namespace wpi::util { template class SmallVectorImpl; } // namespace wpi -namespace glass { +namespace wpi::glass { class BooleanSource; class DoubleSource; @@ -53,4 +53,4 @@ class FMSModel : public Model { void DisplayFMS(FMSModel* model, bool editableDsAttached); void DisplayFMSReadOnly(FMSModel* model); -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/lib/native/include/wpi/glass/other/Field2D.hpp b/glass/src/lib/native/include/wpi/glass/other/Field2D.hpp index 51416f0635..5bcfa70ab4 100644 --- a/glass/src/lib/native/include/wpi/glass/other/Field2D.hpp +++ b/glass/src/lib/native/include/wpi/glass/other/Field2D.hpp @@ -16,17 +16,17 @@ #include "wpi/math/geometry/Translation2d.hpp" #include "wpi/util/function_ref.hpp" -namespace glass { +namespace wpi::glass { class FieldObjectModel : public Model { public: virtual const char* GetName() const = 0; - virtual std::span GetPoses() = 0; - virtual void SetPoses(std::span poses) = 0; - virtual void SetPose(size_t i, frc::Pose2d pose) = 0; - virtual void SetPosition(size_t i, frc::Translation2d pos) = 0; - virtual void SetRotation(size_t i, frc::Rotation2d rot) = 0; + virtual std::span GetPoses() = 0; + virtual void SetPoses(std::span poses) = 0; + virtual void SetPose(size_t i, wpi::math::Pose2d pose) = 0; + virtual void SetPosition(size_t i, wpi::math::Translation2d pos) = 0; + virtual void SetRotation(size_t i, wpi::math::Rotation2d rot) = 0; }; class Field2DModel : public Model { @@ -34,7 +34,7 @@ class Field2DModel : public Model { virtual FieldObjectModel* AddFieldObject(std::string_view name) = 0; virtual void RemoveFieldObject(std::string_view name) = 0; virtual void ForEachFieldObject( - wpi::function_ref + wpi::util::function_ref func) = 0; }; @@ -53,4 +53,4 @@ class Field2DView : public View { Field2DModel* m_model; }; -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/lib/native/include/wpi/glass/other/Log.hpp b/glass/src/lib/native/include/wpi/glass/other/Log.hpp index f595a175e8..ea400c6cc9 100644 --- a/glass/src/lib/native/include/wpi/glass/other/Log.hpp +++ b/glass/src/lib/native/include/wpi/glass/other/Log.hpp @@ -10,7 +10,7 @@ #include "wpi/glass/View.hpp" -namespace glass { +namespace wpi::glass { class LogData { friend void DisplayLog(LogData*, bool); @@ -43,4 +43,4 @@ class LogView : public View { bool m_autoScroll{true}; }; -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/lib/native/include/wpi/glass/other/Mechanism2D.hpp b/glass/src/lib/native/include/wpi/glass/other/Mechanism2D.hpp index 093a1ba939..025c3e1f43 100644 --- a/glass/src/lib/native/include/wpi/glass/other/Mechanism2D.hpp +++ b/glass/src/lib/native/include/wpi/glass/other/Mechanism2D.hpp @@ -12,7 +12,7 @@ #include "wpi/math/geometry/Translation2d.hpp" #include "wpi/util/function_ref.hpp" -namespace glass { +namespace wpi::glass { class MechanismObjectModel; @@ -20,7 +20,7 @@ class MechanismObjectGroup { public: virtual const char* GetName() const = 0; virtual void ForEachObject( - wpi::function_ref func) = 0; + wpi::util::function_ref func) = 0; }; class MechanismObjectModel : public MechanismObjectGroup { @@ -30,21 +30,21 @@ class MechanismObjectModel : public MechanismObjectGroup { // line accessors virtual double GetWeight() const = 0; - virtual frc::Rotation2d GetAngle() const = 0; - virtual units::meter_t GetLength() const = 0; + virtual wpi::math::Rotation2d GetAngle() const = 0; + virtual wpi::units::meter_t GetLength() const = 0; }; class MechanismRootModel : public MechanismObjectGroup { public: - virtual frc::Translation2d GetPosition() const = 0; + virtual wpi::math::Translation2d GetPosition() const = 0; }; class Mechanism2DModel : public Model { public: - virtual frc::Translation2d GetDimensions() const = 0; + virtual wpi::math::Translation2d GetDimensions() const = 0; virtual ImU32 GetBackgroundColor() const = 0; virtual void ForEachRoot( - wpi::function_ref func) = 0; + wpi::util::function_ref func) = 0; }; void DisplayMechanism2D(Mechanism2DModel* model, const ImVec2& contentSize); @@ -62,4 +62,4 @@ class Mechanism2DView : public View { Mechanism2DModel* m_model; }; -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/lib/native/include/wpi/glass/other/PIDController.hpp b/glass/src/lib/native/include/wpi/glass/other/PIDController.hpp index 5b9b5874bd..45c67e2a21 100644 --- a/glass/src/lib/native/include/wpi/glass/other/PIDController.hpp +++ b/glass/src/lib/native/include/wpi/glass/other/PIDController.hpp @@ -6,7 +6,7 @@ #include "wpi/glass/Model.hpp" -namespace glass { +namespace wpi::glass { class DoubleSource; class PIDControllerModel : public Model { public: @@ -25,4 +25,4 @@ class PIDControllerModel : public Model { virtual void SetIZone(double value) = 0; }; void DisplayPIDController(PIDControllerModel* m); -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/lib/native/include/wpi/glass/other/Plot.hpp b/glass/src/lib/native/include/wpi/glass/other/Plot.hpp index a427238b78..c2c6fb13ae 100644 --- a/glass/src/lib/native/include/wpi/glass/other/Plot.hpp +++ b/glass/src/lib/native/include/wpi/glass/other/Plot.hpp @@ -6,7 +6,7 @@ #include "wpi/glass/WindowManager.hpp" -namespace glass { +namespace wpi::glass { class PlotProvider : private WindowManager { public: @@ -33,4 +33,4 @@ class PlotProvider : private WindowManager { bool m_paused = false; }; -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/lib/native/include/wpi/glass/other/ProfiledPIDController.hpp b/glass/src/lib/native/include/wpi/glass/other/ProfiledPIDController.hpp index cea2ea54f0..d495fce762 100644 --- a/glass/src/lib/native/include/wpi/glass/other/ProfiledPIDController.hpp +++ b/glass/src/lib/native/include/wpi/glass/other/ProfiledPIDController.hpp @@ -6,7 +6,7 @@ #include "wpi/glass/Model.hpp" -namespace glass { +namespace wpi::glass { class DoubleSource; class ProfiledPIDControllerModel : public Model { public: @@ -29,4 +29,4 @@ class ProfiledPIDControllerModel : public Model { virtual void SetGoal(double value) = 0; }; void DisplayProfiledPIDController(ProfiledPIDControllerModel* m); -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/lib/native/include/wpi/glass/other/StringChooser.hpp b/glass/src/lib/native/include/wpi/glass/other/StringChooser.hpp index a6d3230fce..9a9dfb4819 100644 --- a/glass/src/lib/native/include/wpi/glass/other/StringChooser.hpp +++ b/glass/src/lib/native/include/wpi/glass/other/StringChooser.hpp @@ -10,7 +10,7 @@ #include "wpi/glass/Model.hpp" -namespace glass { +namespace wpi::glass { class StringChooserModel : public Model { public: @@ -24,4 +24,4 @@ class StringChooserModel : public Model { void DisplayStringChooser(StringChooserModel* model); -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/lib/native/include/wpi/glass/other/Subsystem.hpp b/glass/src/lib/native/include/wpi/glass/other/Subsystem.hpp index 9ef5f34e4a..4487edafbf 100644 --- a/glass/src/lib/native/include/wpi/glass/other/Subsystem.hpp +++ b/glass/src/lib/native/include/wpi/glass/other/Subsystem.hpp @@ -6,7 +6,7 @@ #include "wpi/glass/Model.hpp" -namespace glass { +namespace wpi::glass { class DataSource; class SubsystemModel : public Model { public: @@ -15,4 +15,4 @@ class SubsystemModel : public Model { virtual const char* GetCurrentCommand() const = 0; }; void DisplaySubsystem(SubsystemModel* m); -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/lib/native/include/wpi/glass/support/ColorSetting.hpp b/glass/src/lib/native/include/wpi/glass/support/ColorSetting.hpp index a6604dd747..199bfc96d1 100644 --- a/glass/src/lib/native/include/wpi/glass/support/ColorSetting.hpp +++ b/glass/src/lib/native/include/wpi/glass/support/ColorSetting.hpp @@ -8,7 +8,7 @@ #include -namespace glass { +namespace wpi::glass { class ColorSetting { public: @@ -50,4 +50,4 @@ class ColorSetting { std::vector& m_color; }; -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/lib/native/include/wpi/glass/support/EnumSetting.hpp b/glass/src/lib/native/include/wpi/glass/support/EnumSetting.hpp index ab5b307764..3ead1f62b8 100644 --- a/glass/src/lib/native/include/wpi/glass/support/EnumSetting.hpp +++ b/glass/src/lib/native/include/wpi/glass/support/EnumSetting.hpp @@ -8,7 +8,7 @@ #include "wpi/util/SmallVector.hpp" -namespace glass { +namespace wpi::glass { class EnumSetting { public: @@ -26,9 +26,9 @@ class EnumSetting { void UpdateValue() const; std::string& m_str; - wpi::SmallVector m_choices; + wpi::util::SmallVector m_choices; int m_defaultValue; mutable int m_value = -1; }; -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/lib/native/include/wpi/glass/support/ExpressionParser.hpp b/glass/src/lib/native/include/wpi/glass/support/ExpressionParser.hpp index 0815b56b88..d35a1957cb 100644 --- a/glass/src/lib/native/include/wpi/glass/support/ExpressionParser.hpp +++ b/glass/src/lib/native/include/wpi/glass/support/ExpressionParser.hpp @@ -10,13 +10,13 @@ #include "wpi/util/expected" -namespace glass::expression { +namespace wpi::glass::expression { template -wpi::expected TryParseExpr(const char* expr); +wpi::util::expected TryParseExpr(const char* expr); -extern template wpi::expected TryParseExpr(const char*); -extern template wpi::expected TryParseExpr(const char*); -extern template wpi::expected TryParseExpr(const char*); +extern template wpi::util::expected TryParseExpr(const char*); +extern template wpi::util::expected TryParseExpr(const char*); +extern template wpi::util::expected TryParseExpr(const char*); -} // namespace glass::expression +} // namespace wpi::glass::expression diff --git a/glass/src/lib/native/include/wpi/glass/support/ExtraGuiWidgets.hpp b/glass/src/lib/native/include/wpi/glass/support/ExtraGuiWidgets.hpp index dcf0223445..437e679cff 100644 --- a/glass/src/lib/native/include/wpi/glass/support/ExtraGuiWidgets.hpp +++ b/glass/src/lib/native/include/wpi/glass/support/ExtraGuiWidgets.hpp @@ -8,7 +8,7 @@ #include -namespace glass { +namespace wpi::glass { class BooleanSource; @@ -113,4 +113,4 @@ extern template bool InputExpr(const char*, float*, const char*, extern template bool InputExpr(const char*, double*, const char*, ImGuiInputTextFlags); -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/lib/native/include/wpi/glass/support/NameSetting.hpp b/glass/src/lib/native/include/wpi/glass/support/NameSetting.hpp index e1444e302c..be1f5d6bc7 100644 --- a/glass/src/lib/native/include/wpi/glass/support/NameSetting.hpp +++ b/glass/src/lib/native/include/wpi/glass/support/NameSetting.hpp @@ -9,7 +9,7 @@ #include -namespace glass { +namespace wpi::glass { class NameSetting { public: @@ -40,4 +40,4 @@ class NameSetting { std::string& m_name; }; -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/libnt/native/cpp/NTAlerts.cpp b/glass/src/libnt/native/cpp/NTAlerts.cpp index f4bfcf0888..330546d8a8 100644 --- a/glass/src/libnt/native/cpp/NTAlerts.cpp +++ b/glass/src/libnt/native/cpp/NTAlerts.cpp @@ -8,12 +8,12 @@ #include -using namespace glass; +using namespace wpi::glass; NTAlertsModel::NTAlertsModel(std::string_view path) - : NTAlertsModel{nt::NetworkTableInstance::GetDefault(), path} {} + : NTAlertsModel{wpi::nt::NetworkTableInstance::GetDefault(), path} {} -NTAlertsModel::NTAlertsModel(nt::NetworkTableInstance inst, +NTAlertsModel::NTAlertsModel(wpi::nt::NetworkTableInstance inst, std::string_view path) : m_inst{inst}, m_infos{m_inst.GetStringArrayTopic(fmt::format("{}/infos", path)) diff --git a/glass/src/libnt/native/cpp/NTCommandScheduler.cpp b/glass/src/libnt/native/cpp/NTCommandScheduler.cpp index 7dc2406dde..d23a1bd088 100644 --- a/glass/src/libnt/native/cpp/NTCommandScheduler.cpp +++ b/glass/src/libnt/native/cpp/NTCommandScheduler.cpp @@ -10,12 +10,12 @@ #include "wpi/util/StringExtras.hpp" -using namespace glass; +using namespace wpi::glass; NTCommandSchedulerModel::NTCommandSchedulerModel(std::string_view path) - : NTCommandSchedulerModel(nt::NetworkTableInstance::GetDefault(), path) {} + : NTCommandSchedulerModel(wpi::nt::NetworkTableInstance::GetDefault(), path) {} -NTCommandSchedulerModel::NTCommandSchedulerModel(nt::NetworkTableInstance inst, +NTCommandSchedulerModel::NTCommandSchedulerModel(wpi::nt::NetworkTableInstance inst, std::string_view path) : m_inst{inst}, m_name{inst.GetStringTopic(fmt::format("{}/.name", path)).Subscribe("")}, @@ -25,7 +25,7 @@ NTCommandSchedulerModel::NTCommandSchedulerModel(nt::NetworkTableInstance inst, inst.GetIntegerArrayTopic(fmt::format("{}/Ids", path)).Subscribe({})}, m_cancel{ inst.GetIntegerArrayTopic(fmt::format("{}/Cancel", path)).Publish()}, - m_nameValue{wpi::rsplit(path, '/').second} {} + m_nameValue{wpi::util::rsplit(path, '/').second} {} void NTCommandSchedulerModel::CancelCommand(size_t index) { if (index < m_idsValue.size()) { diff --git a/glass/src/libnt/native/cpp/NTCommandSelector.cpp b/glass/src/libnt/native/cpp/NTCommandSelector.cpp index c6b9fa3805..3084e7265e 100644 --- a/glass/src/libnt/native/cpp/NTCommandSelector.cpp +++ b/glass/src/libnt/native/cpp/NTCommandSelector.cpp @@ -10,19 +10,19 @@ #include "wpi/util/StringExtras.hpp" -using namespace glass; +using namespace wpi::glass; NTCommandSelectorModel::NTCommandSelectorModel(std::string_view path) - : NTCommandSelectorModel(nt::NetworkTableInstance::GetDefault(), path) {} + : NTCommandSelectorModel(wpi::nt::NetworkTableInstance::GetDefault(), path) {} -NTCommandSelectorModel::NTCommandSelectorModel(nt::NetworkTableInstance inst, +NTCommandSelectorModel::NTCommandSelectorModel(wpi::nt::NetworkTableInstance inst, std::string_view path) : m_inst{inst}, m_running{inst.GetBooleanTopic(fmt::format("{}/running", path)) .GetEntry(false)}, m_name{inst.GetStringTopic(fmt::format("{}/.name", path)).Subscribe("")}, m_runningData{fmt::format("NTCmd:{}", path)}, - m_nameValue{wpi::rsplit(path, '/').second} {} + m_nameValue{wpi::util::rsplit(path, '/').second} {} void NTCommandSelectorModel::SetRunning(bool run) { m_running.Set(run); diff --git a/glass/src/libnt/native/cpp/NTDifferentialDrive.cpp b/glass/src/libnt/native/cpp/NTDifferentialDrive.cpp index 7959303e9a..2ca21c421f 100644 --- a/glass/src/libnt/native/cpp/NTDifferentialDrive.cpp +++ b/glass/src/libnt/native/cpp/NTDifferentialDrive.cpp @@ -12,13 +12,13 @@ #include "wpi/util/MathExtras.hpp" #include "wpi/util/StringExtras.hpp" -using namespace glass; +using namespace wpi::glass; NTDifferentialDriveModel::NTDifferentialDriveModel(std::string_view path) - : NTDifferentialDriveModel(nt::NetworkTableInstance::GetDefault(), path) {} + : NTDifferentialDriveModel(wpi::nt::NetworkTableInstance::GetDefault(), path) {} NTDifferentialDriveModel::NTDifferentialDriveModel( - nt::NetworkTableInstance inst, std::string_view path) + wpi::nt::NetworkTableInstance inst, std::string_view path) : m_inst{inst}, m_name{inst.GetStringTopic(fmt::format("{}/.name", path)).Subscribe("")}, m_controllable{inst.GetBooleanTopic(fmt::format("{}/.controllable", path)) @@ -27,7 +27,7 @@ NTDifferentialDriveModel::NTDifferentialDriveModel( .GetEntry(0)}, m_rPercent{inst.GetDoubleTopic(fmt::format("{}/Right Motor Speed", path)) .GetEntry(0)}, - m_nameValue{wpi::rsplit(path, '/').second}, + m_nameValue{wpi::util::rsplit(path, '/').second}, m_lPercentData{fmt::format("NTDiffDriveL:{}", path)}, m_rPercentData{fmt::format("NTDiffDriveR:{}", path)} { m_wheels.emplace_back("L % Output", &m_lPercentData, diff --git a/glass/src/libnt/native/cpp/NTDigitalInput.cpp b/glass/src/libnt/native/cpp/NTDigitalInput.cpp index f5de2402a7..67bc8d2938 100644 --- a/glass/src/libnt/native/cpp/NTDigitalInput.cpp +++ b/glass/src/libnt/native/cpp/NTDigitalInput.cpp @@ -10,19 +10,19 @@ #include "wpi/util/StringExtras.hpp" -using namespace glass; +using namespace wpi::glass; NTDigitalInputModel::NTDigitalInputModel(std::string_view path) - : NTDigitalInputModel{nt::NetworkTableInstance::GetDefault(), path} {} + : NTDigitalInputModel{wpi::nt::NetworkTableInstance::GetDefault(), path} {} -NTDigitalInputModel::NTDigitalInputModel(nt::NetworkTableInstance inst, +NTDigitalInputModel::NTDigitalInputModel(wpi::nt::NetworkTableInstance inst, std::string_view path) : m_inst{inst}, m_value{ inst.GetBooleanTopic(fmt::format("{}/Value", path)).Subscribe(false)}, m_name{inst.GetStringTopic(fmt::format("{}/.name", path)).Subscribe("")}, m_valueData{fmt::format("NT_DIn:{}", path)}, - m_nameValue{wpi::rsplit(path, '/').second} {} + m_nameValue{wpi::util::rsplit(path, '/').second} {} void NTDigitalInputModel::Update() { for (auto&& v : m_value.ReadQueue()) { diff --git a/glass/src/libnt/native/cpp/NTDigitalOutput.cpp b/glass/src/libnt/native/cpp/NTDigitalOutput.cpp index 05cdbdddb6..3671d8fbca 100644 --- a/glass/src/libnt/native/cpp/NTDigitalOutput.cpp +++ b/glass/src/libnt/native/cpp/NTDigitalOutput.cpp @@ -8,12 +8,12 @@ #include -using namespace glass; +using namespace wpi::glass; NTDigitalOutputModel::NTDigitalOutputModel(std::string_view path) - : NTDigitalOutputModel{nt::NetworkTableInstance::GetDefault(), path} {} + : NTDigitalOutputModel{wpi::nt::NetworkTableInstance::GetDefault(), path} {} -NTDigitalOutputModel::NTDigitalOutputModel(nt::NetworkTableInstance inst, +NTDigitalOutputModel::NTDigitalOutputModel(wpi::nt::NetworkTableInstance inst, std::string_view path) : m_inst{inst}, m_value{ diff --git a/glass/src/libnt/native/cpp/NTFMS.cpp b/glass/src/libnt/native/cpp/NTFMS.cpp index e534af9f7c..e6c134b61f 100644 --- a/glass/src/libnt/native/cpp/NTFMS.cpp +++ b/glass/src/libnt/native/cpp/NTFMS.cpp @@ -13,12 +13,12 @@ #include "wpi/util/SmallVector.hpp" #include "wpi/util/timestamp.h" -using namespace glass; +using namespace wpi::glass; NTFMSModel::NTFMSModel(std::string_view path) - : NTFMSModel{nt::NetworkTableInstance::GetDefault(), path} {} + : NTFMSModel{wpi::nt::NetworkTableInstance::GetDefault(), path} {} -NTFMSModel::NTFMSModel(nt::NetworkTableInstance inst, std::string_view path) +NTFMSModel::NTFMSModel(wpi::nt::NetworkTableInstance inst, std::string_view path) : m_inst{inst}, m_gameSpecificMessage{ inst.GetStringTopic(fmt::format("{}/GameSpecificMessage", path)) diff --git a/glass/src/libnt/native/cpp/NTField2D.cpp b/glass/src/libnt/native/cpp/NTField2D.cpp index 08a4aca06d..439fc1db48 100644 --- a/glass/src/libnt/native/cpp/NTField2D.cpp +++ b/glass/src/libnt/native/cpp/NTField2D.cpp @@ -20,39 +20,39 @@ #include "wpi/util/SmallVector.hpp" #include "wpi/util/StringExtras.hpp" -using namespace glass; +using namespace wpi::glass; class NTField2DModel::ObjectModel : public FieldObjectModel { public: - ObjectModel(std::string_view name, nt::DoubleArrayTopic topic) + ObjectModel(std::string_view name, wpi::nt::DoubleArrayTopic topic) : m_name{name}, m_topic{topic} {} const char* GetName() const override { return m_name.c_str(); } - nt::DoubleArrayTopic GetTopic() const { return m_topic; } + wpi::nt::DoubleArrayTopic GetTopic() const { return m_topic; } - void NTUpdate(const nt::Value& value); + void NTUpdate(const wpi::nt::Value& value); void Update() override {} bool Exists() override { return m_topic.Exists(); } bool IsReadOnly() override { return false; } - std::span GetPoses() override { return m_poses; } - void SetPoses(std::span poses) override; - void SetPose(size_t i, frc::Pose2d pose) override; - void SetPosition(size_t i, frc::Translation2d pos) override; - void SetRotation(size_t i, frc::Rotation2d rot) override; + std::span GetPoses() override { return m_poses; } + void SetPoses(std::span poses) override; + void SetPose(size_t i, wpi::math::Pose2d pose) override; + void SetPosition(size_t i, wpi::math::Translation2d pos) override; + void SetRotation(size_t i, wpi::math::Rotation2d rot) override; private: void UpdateNT(); std::string m_name; - nt::DoubleArrayTopic m_topic; - nt::DoubleArrayPublisher m_pub; + wpi::nt::DoubleArrayTopic m_topic; + wpi::nt::DoubleArrayPublisher m_pub; - std::vector m_poses; + std::vector m_poses; }; -void NTField2DModel::ObjectModel::NTUpdate(const nt::Value& value) { +void NTField2DModel::ObjectModel::NTUpdate(const wpi::nt::Value& value) { if (value.IsDoubleArray()) { auto arr = value.GetDoubleArray(); auto size = arr.size(); @@ -61,15 +61,15 @@ void NTField2DModel::ObjectModel::NTUpdate(const nt::Value& value) { } m_poses.resize(size / 3); for (size_t i = 0; i < size / 3; ++i) { - m_poses[i] = frc::Pose2d{ - units::meter_t{arr[i * 3 + 0]}, units::meter_t{arr[i * 3 + 1]}, - frc::Rotation2d{units::degree_t{arr[i * 3 + 2]}}}; + m_poses[i] = wpi::math::Pose2d{ + wpi::units::meter_t{arr[i * 3 + 0]}, wpi::units::meter_t{arr[i * 3 + 1]}, + wpi::math::Rotation2d{wpi::units::degree_t{arr[i * 3 + 2]}}}; } } } void NTField2DModel::ObjectModel::UpdateNT() { - wpi::SmallVector arr; + wpi::util::SmallVector arr; for (auto&& pose : m_poses) { auto& translation = pose.Translation(); arr.push_back(translation.X().value()); @@ -82,12 +82,12 @@ void NTField2DModel::ObjectModel::UpdateNT() { m_pub.Set(arr); } -void NTField2DModel::ObjectModel::SetPoses(std::span poses) { +void NTField2DModel::ObjectModel::SetPoses(std::span poses) { m_poses.assign(poses.begin(), poses.end()); UpdateNT(); } -void NTField2DModel::ObjectModel::SetPose(size_t i, frc::Pose2d pose) { +void NTField2DModel::ObjectModel::SetPose(size_t i, wpi::math::Pose2d pose) { if (i < m_poses.size()) { m_poses[i] = pose; UpdateNT(); @@ -95,33 +95,33 @@ void NTField2DModel::ObjectModel::SetPose(size_t i, frc::Pose2d pose) { } void NTField2DModel::ObjectModel::SetPosition(size_t i, - frc::Translation2d pos) { + wpi::math::Translation2d pos) { if (i < m_poses.size()) { - m_poses[i] = frc::Pose2d{pos, m_poses[i].Rotation()}; + m_poses[i] = wpi::math::Pose2d{pos, m_poses[i].Rotation()}; UpdateNT(); } } -void NTField2DModel::ObjectModel::SetRotation(size_t i, frc::Rotation2d rot) { +void NTField2DModel::ObjectModel::SetRotation(size_t i, wpi::math::Rotation2d rot) { if (i < m_poses.size()) { - m_poses[i] = frc::Pose2d{m_poses[i].Translation(), rot}; + m_poses[i] = wpi::math::Pose2d{m_poses[i].Translation(), rot}; UpdateNT(); } } NTField2DModel::NTField2DModel(std::string_view path) - : NTField2DModel{nt::NetworkTableInstance::GetDefault(), path} {} + : NTField2DModel{wpi::nt::NetworkTableInstance::GetDefault(), path} {} -NTField2DModel::NTField2DModel(nt::NetworkTableInstance inst, +NTField2DModel::NTField2DModel(wpi::nt::NetworkTableInstance inst, std::string_view path) : m_path{fmt::format("{}/", path)}, m_inst{inst}, m_tableSub{inst, {{m_path}}, {.periodic = 0.05, .sendAll = true}}, m_nameTopic{inst.GetTopic(fmt::format("{}/.name", path))}, m_poller{inst} { - m_poller.AddListener(m_tableSub, nt::EventFlags::kTopic | - nt::EventFlags::kValueAll | - nt::EventFlags::kImmediate); + m_poller.AddListener(m_tableSub, wpi::nt::EventFlags::kTopic | + wpi::nt::EventFlags::kValueAll | + wpi::nt::EventFlags::kImmediate); } NTField2DModel::~NTField2DModel() = default; @@ -130,21 +130,21 @@ void NTField2DModel::Update() { for (auto&& event : m_poller.ReadQueue()) { if (auto info = event.GetTopicInfo()) { // handle publish/unpublish - auto name = wpi::remove_prefix(info->name, m_path).value_or(""); + auto name = wpi::util::remove_prefix(info->name, m_path).value_or(""); if (name.empty() || name[0] == '.') { continue; } auto [it, match] = Find(info->name); - if (event.flags & nt::EventFlags::kUnpublish) { + if (event.flags & wpi::nt::EventFlags::kUnpublish) { if (match) { m_objects.erase(it); } continue; - } else if (event.flags & nt::EventFlags::kPublish) { + } else if (event.flags & wpi::nt::EventFlags::kPublish) { if (!match) { it = m_objects.emplace( it, std::make_unique( - info->name, nt::DoubleArrayTopic{info->topic})); + info->name, wpi::nt::DoubleArrayTopic{info->topic})); } } else if (!match) { continue; @@ -198,11 +198,11 @@ void NTField2DModel::RemoveFieldObject(std::string_view name) { } void NTField2DModel::ForEachFieldObject( - wpi::function_ref + wpi::util::function_ref func) { for (auto&& obj : m_objects) { if (obj->Exists()) { - if (auto name = wpi::remove_prefix(obj->GetName(), m_path)) { + if (auto name = wpi::util::remove_prefix(obj->GetName(), m_path)) { func(*obj, *name); } } diff --git a/glass/src/libnt/native/cpp/NTGyro.cpp b/glass/src/libnt/native/cpp/NTGyro.cpp index ef26c89e02..c7e07ebfc0 100644 --- a/glass/src/libnt/native/cpp/NTGyro.cpp +++ b/glass/src/libnt/native/cpp/NTGyro.cpp @@ -10,17 +10,17 @@ #include "wpi/util/StringExtras.hpp" -using namespace glass; +using namespace wpi::glass; NTGyroModel::NTGyroModel(std::string_view path) - : NTGyroModel(nt::NetworkTableInstance::GetDefault(), path) {} + : NTGyroModel(wpi::nt::NetworkTableInstance::GetDefault(), path) {} -NTGyroModel::NTGyroModel(nt::NetworkTableInstance inst, std::string_view path) +NTGyroModel::NTGyroModel(wpi::nt::NetworkTableInstance inst, std::string_view path) : m_inst{inst}, m_angle{inst.GetDoubleTopic(fmt::format("{}/Value", path)).Subscribe(0)}, m_name{inst.GetStringTopic(fmt::format("{}/.name", path)).Subscribe({})}, m_angleData{fmt::format("NT_Gyro:{}", path)}, - m_nameValue{wpi::rsplit(path, '/').second} {} + m_nameValue{wpi::util::rsplit(path, '/').second} {} void NTGyroModel::Update() { for (auto&& v : m_name.ReadQueue()) { diff --git a/glass/src/libnt/native/cpp/NTMecanumDrive.cpp b/glass/src/libnt/native/cpp/NTMecanumDrive.cpp index b7f5fd7769..12115da787 100644 --- a/glass/src/libnt/native/cpp/NTMecanumDrive.cpp +++ b/glass/src/libnt/native/cpp/NTMecanumDrive.cpp @@ -12,12 +12,12 @@ #include "wpi/util/MathExtras.hpp" #include "wpi/util/StringExtras.hpp" -using namespace glass; +using namespace wpi::glass; NTMecanumDriveModel::NTMecanumDriveModel(std::string_view path) - : NTMecanumDriveModel(nt::NetworkTableInstance::GetDefault(), path) {} + : NTMecanumDriveModel(wpi::nt::NetworkTableInstance::GetDefault(), path) {} -NTMecanumDriveModel::NTMecanumDriveModel(nt::NetworkTableInstance inst, +NTMecanumDriveModel::NTMecanumDriveModel(wpi::nt::NetworkTableInstance inst, std::string_view path) : m_inst{inst}, m_name{inst.GetStringTopic(fmt::format("{}/.name", path)).Subscribe("")}, @@ -35,7 +35,7 @@ NTMecanumDriveModel::NTMecanumDriveModel(nt::NetworkTableInstance inst, m_rrPercent{ inst.GetDoubleTopic(fmt::format("{}/Rear Right Motor Speed", path)) .GetEntry(0)}, - m_nameValue{wpi::rsplit(path, '/').second}, + m_nameValue{wpi::util::rsplit(path, '/').second}, m_flPercentData{fmt::format("NTMcnmDriveFL:{}", path)}, m_frPercentData{fmt::format("NTMcnmDriveFR:{}", path)}, m_rlPercentData{fmt::format("NTMcnmDriveRL:{}", path)}, diff --git a/glass/src/libnt/native/cpp/NTMechanism2D.cpp b/glass/src/libnt/native/cpp/NTMechanism2D.cpp index 70dd92283f..012d865c33 100644 --- a/glass/src/libnt/native/cpp/NTMechanism2D.cpp +++ b/glass/src/libnt/native/cpp/NTMechanism2D.cpp @@ -17,33 +17,33 @@ #include "wpi/nt/ntcore_cpp.hpp" #include "wpi/util/StringExtras.hpp" -using namespace glass; +using namespace wpi::glass; // Convert "#RRGGBB" hex color to ImU32 color static void ConvertColor(std::string_view in, ImU32* out) { if (in.size() != 7 || in[0] != '#') { return; } - if (auto v = wpi::parse_integer(wpi::drop_front(in), 16)) { + if (auto v = wpi::util::parse_integer(wpi::util::drop_front(in), 16)) { ImU32 val = v.value(); *out = IM_COL32((val >> 16) & 0xff, (val >> 8) & 0xff, val & 0xff, 255); } } void NTMechanism2DModel::NTMechanismGroupImpl::ForEachObject( - wpi::function_ref func) { + wpi::util::function_ref func) { for (auto&& obj : m_objects) { func(*obj); } } -void NTMechanism2DModel::NTMechanismGroupImpl::NTUpdate(const nt::Event& event, +void NTMechanism2DModel::NTMechanismGroupImpl::NTUpdate(const wpi::nt::Event& event, std::string_view name) { if (name.empty()) { return; } std::string_view childName; - std::tie(name, childName) = wpi::split(name, '/'); + std::tie(name, childName) = wpi::util::split(name, '/'); if (childName.empty()) { return; } @@ -54,7 +54,7 @@ void NTMechanism2DModel::NTMechanismGroupImpl::NTUpdate(const nt::Event& event, bool match = it != m_objects.end() && (*it)->GetName() == name; if (event.GetTopicInfo()) { - if (event.flags & nt::EventFlags::kPublish) { + if (event.flags & wpi::nt::EventFlags::kPublish) { if (!match) { it = m_objects.emplace( it, std::make_unique( @@ -76,10 +76,10 @@ void NTMechanism2DModel::NTMechanismGroupImpl::NTUpdate(const nt::Event& event, } bool NTMechanism2DModel::NTMechanismObjectModel::NTUpdate( - const nt::Event& event, std::string_view childName) { + const wpi::nt::Event& event, std::string_view childName) { if (auto info = event.GetTopicInfo()) { if (info->topic == m_typeTopic.GetHandle()) { - if (event.flags & nt::EventFlags::kUnpublish) { + if (event.flags & wpi::nt::EventFlags::kUnpublish) { return true; } } else if (info->topic != m_colorTopic.GetHandle() && @@ -103,11 +103,11 @@ bool NTMechanism2DModel::NTMechanismObjectModel::NTUpdate( } } else if (valueData->topic == m_angleTopic.GetHandle()) { if (valueData->value && valueData->value.IsDouble()) { - m_angleValue = units::degree_t{valueData->value.GetDouble()}; + m_angleValue = wpi::units::degree_t{valueData->value.GetDouble()}; } } else if (valueData->topic == m_lengthTopic.GetHandle()) { if (valueData->value && valueData->value.IsDouble()) { - m_lengthValue = units::meter_t{valueData->value.GetDouble()}; + m_lengthValue = wpi::units::meter_t{valueData->value.GetDouble()}; } } else { m_group.NTUpdate(event, childName); @@ -116,12 +116,12 @@ bool NTMechanism2DModel::NTMechanismObjectModel::NTUpdate( return false; } -bool NTMechanism2DModel::RootModel::NTUpdate(const nt::Event& event, +bool NTMechanism2DModel::RootModel::NTUpdate(const wpi::nt::Event& event, std::string_view childName) { if (auto info = event.GetTopicInfo()) { if (info->topic == m_xTopic.GetHandle() || info->topic == m_yTopic.GetHandle()) { - if (event.flags & nt::EventFlags::kUnpublish) { + if (event.flags & wpi::nt::EventFlags::kUnpublish) { return true; } } else { @@ -130,13 +130,13 @@ bool NTMechanism2DModel::RootModel::NTUpdate(const nt::Event& event, } else if (auto valueData = event.GetValueEventData()) { if (valueData->topic == m_xTopic.GetHandle()) { if (valueData->value && valueData->value.IsDouble()) { - m_pos = frc::Translation2d{units::meter_t{valueData->value.GetDouble()}, + m_pos = wpi::math::Translation2d{wpi::units::meter_t{valueData->value.GetDouble()}, m_pos.Y()}; } } else if (valueData->topic == m_yTopic.GetHandle()) { if (valueData->value && valueData->value.IsDouble()) { - m_pos = frc::Translation2d{ - m_pos.X(), units::meter_t{valueData->value.GetDouble()}}; + m_pos = wpi::math::Translation2d{ + m_pos.X(), wpi::units::meter_t{valueData->value.GetDouble()}}; } } else { m_group.NTUpdate(event, childName); @@ -146,9 +146,9 @@ bool NTMechanism2DModel::RootModel::NTUpdate(const nt::Event& event, } NTMechanism2DModel::NTMechanism2DModel(std::string_view path) - : NTMechanism2DModel{nt::NetworkTableInstance::GetDefault(), path} {} + : NTMechanism2DModel{wpi::nt::NetworkTableInstance::GetDefault(), path} {} -NTMechanism2DModel::NTMechanism2DModel(nt::NetworkTableInstance inst, +NTMechanism2DModel::NTMechanism2DModel(wpi::nt::NetworkTableInstance inst, std::string_view path) : m_inst{inst}, m_path{fmt::format("{}/", path)}, @@ -158,9 +158,9 @@ NTMechanism2DModel::NTMechanism2DModel(nt::NetworkTableInstance inst, m_bgColorTopic{m_inst.GetTopic(fmt::format("{}/backgroundColor", path))}, m_poller{m_inst}, m_dimensionsValue{1_m, 1_m} { - m_poller.AddListener(m_tableSub, nt::EventFlags::kTopic | - nt::EventFlags::kValueAll | - nt::EventFlags::kImmediate); + m_poller.AddListener(m_tableSub, wpi::nt::EventFlags::kTopic | + wpi::nt::EventFlags::kValueAll | + wpi::nt::EventFlags::kImmediate); } NTMechanism2DModel::~NTMechanism2DModel() = default; @@ -168,12 +168,12 @@ NTMechanism2DModel::~NTMechanism2DModel() = default; void NTMechanism2DModel::Update() { for (auto&& event : m_poller.ReadQueue()) { if (auto info = event.GetTopicInfo()) { - auto name = wpi::remove_prefix(info->name, m_path).value_or(""); + auto name = wpi::util::remove_prefix(info->name, m_path).value_or(""); if (name.empty() || name[0] == '.') { continue; } std::string_view childName; - std::tie(name, childName) = wpi::split(name, '/'); + std::tie(name, childName) = wpi::util::split(name, '/'); if (childName.empty()) { continue; } @@ -184,7 +184,7 @@ void NTMechanism2DModel::Update() { }); bool match = it != m_roots.end() && (*it)->GetName() == name; - if (event.flags & nt::EventFlags::kPublish) { + if (event.flags & wpi::nt::EventFlags::kPublish) { if (!match) { it = m_roots.emplace( it, std::make_unique( @@ -208,8 +208,8 @@ void NTMechanism2DModel::Update() { if (valueData->value && valueData->value.IsDoubleArray()) { auto arr = valueData->value.GetDoubleArray(); if (arr.size() == 2) { - m_dimensionsValue = frc::Translation2d{units::meter_t{arr[0]}, - units::meter_t{arr[1]}}; + m_dimensionsValue = wpi::math::Translation2d{wpi::units::meter_t{arr[0]}, + wpi::units::meter_t{arr[1]}}; } } } else if (valueData->topic == m_bgColorTopic.GetHandle()) { @@ -218,13 +218,13 @@ void NTMechanism2DModel::Update() { ConvertColor(valueData->value.GetString(), &m_bgColorValue); } } else { - auto fullName = nt::Topic{valueData->topic}.GetName(); - auto name = wpi::remove_prefix(fullName, m_path).value_or(""); + auto fullName = wpi::nt::Topic{valueData->topic}.GetName(); + auto name = wpi::util::remove_prefix(fullName, m_path).value_or(""); if (name.empty() || name[0] == '.') { continue; } std::string_view childName; - std::tie(name, childName) = wpi::split(name, '/'); + std::tie(name, childName) = wpi::util::split(name, '/'); if (childName.empty()) { continue; } @@ -252,7 +252,7 @@ bool NTMechanism2DModel::IsReadOnly() { } void NTMechanism2DModel::ForEachRoot( - wpi::function_ref func) { + wpi::util::function_ref func) { for (auto&& obj : m_roots) { func(*obj); } diff --git a/glass/src/libnt/native/cpp/NTMotorController.cpp b/glass/src/libnt/native/cpp/NTMotorController.cpp index 6a799639a8..537e2d7b51 100644 --- a/glass/src/libnt/native/cpp/NTMotorController.cpp +++ b/glass/src/libnt/native/cpp/NTMotorController.cpp @@ -10,12 +10,12 @@ #include "wpi/util/StringExtras.hpp" -using namespace glass; +using namespace wpi::glass; NTMotorControllerModel::NTMotorControllerModel(std::string_view path) - : NTMotorControllerModel(nt::NetworkTableInstance::GetDefault(), path) {} + : NTMotorControllerModel(wpi::nt::NetworkTableInstance::GetDefault(), path) {} -NTMotorControllerModel::NTMotorControllerModel(nt::NetworkTableInstance inst, +NTMotorControllerModel::NTMotorControllerModel(wpi::nt::NetworkTableInstance inst, std::string_view path) : m_inst{inst}, m_value{inst.GetDoubleTopic(fmt::format("{}/Value", path)).GetEntry(0)}, @@ -23,7 +23,7 @@ NTMotorControllerModel::NTMotorControllerModel(nt::NetworkTableInstance inst, m_controllable{inst.GetBooleanTopic(fmt::format("{}/.controllable", path)) .Subscribe(false)}, m_valueData{fmt::format("NT_SpdCtrl:{}", path)}, - m_nameValue{wpi::rsplit(path, '/').second} {} + m_nameValue{wpi::util::rsplit(path, '/').second} {} void NTMotorControllerModel::SetPercent(double value) { m_value.Set(value); diff --git a/glass/src/libnt/native/cpp/NTPIDController.cpp b/glass/src/libnt/native/cpp/NTPIDController.cpp index 184374db36..dbd32787c9 100644 --- a/glass/src/libnt/native/cpp/NTPIDController.cpp +++ b/glass/src/libnt/native/cpp/NTPIDController.cpp @@ -10,12 +10,12 @@ #include "wpi/util/StringExtras.hpp" -using namespace glass; +using namespace wpi::glass; NTPIDControllerModel::NTPIDControllerModel(std::string_view path) - : NTPIDControllerModel(nt::NetworkTableInstance::GetDefault(), path) {} + : NTPIDControllerModel(wpi::nt::NetworkTableInstance::GetDefault(), path) {} -NTPIDControllerModel::NTPIDControllerModel(nt::NetworkTableInstance inst, +NTPIDControllerModel::NTPIDControllerModel(wpi::nt::NetworkTableInstance inst, std::string_view path) : m_inst{inst}, m_name{inst.GetStringTopic(fmt::format("{}/.name", path)).Subscribe("")}, @@ -32,7 +32,7 @@ NTPIDControllerModel::NTPIDControllerModel(nt::NetworkTableInstance inst, m_dData{fmt::format("NTPIDCtrlD:{}", path)}, m_setpointData{fmt::format("NTPIDCtrlStpt:{}", path)}, m_iZoneData{fmt::format("NTPIDCtrlIZone:{}", path)}, - m_nameValue{wpi::rsplit(path, '/').second} {} + m_nameValue{wpi::util::rsplit(path, '/').second} {} void NTPIDControllerModel::SetP(double value) { m_p.Set(value); diff --git a/glass/src/libnt/native/cpp/NTProfiledPIDController.cpp b/glass/src/libnt/native/cpp/NTProfiledPIDController.cpp index e521975597..d5184bb38e 100644 --- a/glass/src/libnt/native/cpp/NTProfiledPIDController.cpp +++ b/glass/src/libnt/native/cpp/NTProfiledPIDController.cpp @@ -10,15 +10,15 @@ #include "wpi/util/StringExtras.hpp" -using namespace glass; +using namespace wpi::glass; NTProfiledPIDControllerModel::NTProfiledPIDControllerModel( std::string_view path) - : NTProfiledPIDControllerModel(nt::NetworkTableInstance::GetDefault(), + : NTProfiledPIDControllerModel(wpi::nt::NetworkTableInstance::GetDefault(), path) {} NTProfiledPIDControllerModel::NTProfiledPIDControllerModel( - nt::NetworkTableInstance inst, std::string_view path) + wpi::nt::NetworkTableInstance inst, std::string_view path) : m_inst{inst}, m_name{inst.GetStringTopic(fmt::format("{}/.name", path)).Subscribe("")}, m_controllable{inst.GetBooleanTopic(fmt::format("{}/.controllable", path)) @@ -40,7 +40,7 @@ NTProfiledPIDControllerModel::NTProfiledPIDControllerModel( m_maxVelocityData{fmt::format("NTPIDCtrlMaxVelo:{}", path)}, m_maxAccelerationData{fmt::format("NTPIDCtrlMaxAccel:{}", path)}, m_goalData{fmt::format("NTPIDCtrlGoal:{}", path)}, - m_nameValue{wpi::rsplit(path, '/').second} {} + m_nameValue{wpi::util::rsplit(path, '/').second} {} void NTProfiledPIDControllerModel::SetP(double value) { m_p.Set(value); diff --git a/glass/src/libnt/native/cpp/NTStringChooser.cpp b/glass/src/libnt/native/cpp/NTStringChooser.cpp index 313f5e8888..710a54a769 100644 --- a/glass/src/libnt/native/cpp/NTStringChooser.cpp +++ b/glass/src/libnt/native/cpp/NTStringChooser.cpp @@ -10,12 +10,12 @@ #include "wpi/util/json.hpp" -using namespace glass; +using namespace wpi::glass; NTStringChooserModel::NTStringChooserModel(std::string_view path) - : NTStringChooserModel{nt::NetworkTableInstance::GetDefault(), path} {} + : NTStringChooserModel{wpi::nt::NetworkTableInstance::GetDefault(), path} {} -NTStringChooserModel::NTStringChooserModel(nt::NetworkTableInstance inst, +NTStringChooserModel::NTStringChooserModel(wpi::nt::NetworkTableInstance inst, std::string_view path) : m_inst{inst}, m_default{ @@ -24,7 +24,7 @@ NTStringChooserModel::NTStringChooserModel(nt::NetworkTableInstance inst, .Subscribe("")}, m_selectedPub{ m_inst.GetStringTopic(fmt::format("{}/selected", path)) - .PublishEx(nt::StringTopic::kTypeString, {{"retained", true}})}, + .PublishEx(wpi::nt::StringTopic::kTypeString, {{"retained", true}})}, m_active{ m_inst.GetStringTopic(fmt::format("{}/active", path)).Subscribe("")}, m_options{m_inst.GetStringArrayTopic(fmt::format("{}/options", path)) diff --git a/glass/src/libnt/native/cpp/NTSubsystem.cpp b/glass/src/libnt/native/cpp/NTSubsystem.cpp index 5b07d068e8..4b9d63456a 100644 --- a/glass/src/libnt/native/cpp/NTSubsystem.cpp +++ b/glass/src/libnt/native/cpp/NTSubsystem.cpp @@ -8,12 +8,12 @@ #include -using namespace glass; +using namespace wpi::glass; NTSubsystemModel::NTSubsystemModel(std::string_view path) - : NTSubsystemModel(nt::NetworkTableInstance::GetDefault(), path) {} + : NTSubsystemModel(wpi::nt::NetworkTableInstance::GetDefault(), path) {} -NTSubsystemModel::NTSubsystemModel(nt::NetworkTableInstance inst, +NTSubsystemModel::NTSubsystemModel(wpi::nt::NetworkTableInstance inst, std::string_view path) : m_inst{inst}, m_name{inst.GetStringTopic(fmt::format("{}/.name", path)).Subscribe("")}, diff --git a/glass/src/libnt/native/cpp/NetworkTables.cpp b/glass/src/libnt/native/cpp/NetworkTables.cpp index 6201aef30b..74c5532f04 100644 --- a/glass/src/libnt/native/cpp/NetworkTables.cpp +++ b/glass/src/libnt/native/cpp/NetworkTables.cpp @@ -44,7 +44,7 @@ #include "wpi/util/print.hpp" #include "wpi/util/raw_ostream.hpp" -using namespace glass; +using namespace wpi::glass; using namespace mpack; namespace { @@ -73,7 +73,7 @@ static bool IsVisible(ShowCategory category, bool persistent, bool retained) { static std::string StringArrayToString(std::span in) { std::string rv; - wpi::raw_string_ostream os{rv}; + wpi::util::raw_string_ostream os{rv}; os << '['; bool first = true; for (auto&& v : in) { @@ -90,22 +90,22 @@ static std::string StringArrayToString(std::span in) { } NetworkTablesModel::NetworkTablesModel() - : NetworkTablesModel{nt::NetworkTableInstance::GetDefault()} {} + : NetworkTablesModel{wpi::nt::NetworkTableInstance::GetDefault()} {} -NetworkTablesModel::NetworkTablesModel(nt::NetworkTableInstance inst) +NetworkTablesModel::NetworkTablesModel(wpi::nt::NetworkTableInstance inst) : m_inst{inst}, m_poller{inst} { - m_poller.AddListener({{"", "$"}}, nt::EventFlags::kTopic | - nt::EventFlags::kValueAll | - nt::EventFlags::kImmediate); + m_poller.AddListener({{"", "$"}}, wpi::nt::EventFlags::kTopic | + wpi::nt::EventFlags::kValueAll | + wpi::nt::EventFlags::kImmediate); } NetworkTablesModel::Entry::~Entry() { if (publisher != 0) { - nt::Unpublish(publisher); + wpi::nt::Unpublish(publisher); } } -void NetworkTablesModel::Entry::UpdateInfo(nt::TopicInfo&& info_) { +void NetworkTablesModel::Entry::UpdateInfo(wpi::nt::TopicInfo&& info_) { info = std::move(info_); properties = info.GetProperties(); @@ -133,29 +133,29 @@ static void UpdateMsgpackValueSource(NetworkTablesModel& model, mpack_tag_t tag = mpack_read_tag(&r); switch (mpack_tag_type(&tag)) { case mpack::mpack_type_bool: - out->value = nt::Value::MakeBoolean(mpack_tag_bool_value(&tag), time); + out->value = wpi::nt::Value::MakeBoolean(mpack_tag_bool_value(&tag), time); out->UpdateFromValue(model, name, ""); break; case mpack::mpack_type_int: - out->value = nt::Value::MakeInteger(mpack_tag_int_value(&tag), time); + out->value = wpi::nt::Value::MakeInteger(mpack_tag_int_value(&tag), time); out->UpdateFromValue(model, name, ""); break; case mpack::mpack_type_uint: - out->value = nt::Value::MakeInteger(mpack_tag_uint_value(&tag), time); + out->value = wpi::nt::Value::MakeInteger(mpack_tag_uint_value(&tag), time); out->UpdateFromValue(model, name, ""); break; case mpack::mpack_type_float: - out->value = nt::Value::MakeFloat(mpack_tag_float_value(&tag), time); + out->value = wpi::nt::Value::MakeFloat(mpack_tag_float_value(&tag), time); out->UpdateFromValue(model, name, ""); break; case mpack::mpack_type_double: - out->value = nt::Value::MakeDouble(mpack_tag_double_value(&tag), time); + out->value = wpi::nt::Value::MakeDouble(mpack_tag_double_value(&tag), time); out->UpdateFromValue(model, name, ""); break; case mpack::mpack_type_str: { std::string str; mpack_read_str(&r, &tag, &str); - out->value = nt::Value::MakeString(std::move(str), time); + out->value = wpi::nt::Value::MakeString(std::move(str), time); out->UpdateFromValue(model, name, ""); break; } @@ -188,7 +188,7 @@ static void UpdateMsgpackValueSource(NetworkTablesModel& model, out->valueChildren.clear(); out->valueChildrenMap = true; } - wpi::StringMap elems; + wpi::util::StringMap elems; for (size_t i = 0, size = out->valueChildren.size(); i < size; ++i) { elems[out->valueChildren[i].name] = i; } @@ -233,7 +233,7 @@ static void UpdateMsgpackValueSource(NetworkTablesModel& model, } } -static std::string GetEnumValue(const wpi::StructFieldDescriptor& field, +static std::string GetEnumValue(const wpi::util::StructFieldDescriptor& field, int64_t val) { auto& enumValues = field.GetEnumValues(); for (auto&& ev : enumValues) { @@ -246,7 +246,7 @@ static std::string GetEnumValue(const wpi::StructFieldDescriptor& field, static void UpdateStructValueSource(NetworkTablesModel& model, NetworkTablesModel::ValueSource* out, - const wpi::DynamicStruct& s, + const wpi::util::DynamicStruct& s, std::string_view name, int64_t time) { auto desc = s.GetDescriptor(); out->typeStr = "struct:" + desc->GetName(); @@ -266,31 +266,31 @@ static void UpdateStructValueSource(NetworkTablesModel& model, for (auto&& field : fields) { auto& child = *outIt++; switch (field.GetType()) { - case wpi::StructFieldType::kBool: + case wpi::util::StructFieldType::kBool: if (field.IsArray()) { std::vector v; v.reserve(field.GetArraySize()); for (size_t i = 0; i < field.GetArraySize(); ++i) { v.emplace_back(s.GetBoolField(&field, i)); } - child.value = nt::Value::MakeBooleanArray(std::move(v), time); + child.value = wpi::nt::Value::MakeBooleanArray(std::move(v), time); } else { - child.value = nt::Value::MakeBoolean(s.GetBoolField(&field), time); + child.value = wpi::nt::Value::MakeBoolean(s.GetBoolField(&field), time); } child.UpdateFromValue(model, child.path, ""); break; - case wpi::StructFieldType::kChar: - child.value = nt::Value::MakeString(s.GetStringField(&field), time); + case wpi::util::StructFieldType::kChar: + child.value = wpi::nt::Value::MakeString(s.GetStringField(&field), time); child.UpdateFromValue(model, child.path, ""); break; - case wpi::StructFieldType::kInt8: - case wpi::StructFieldType::kInt16: - case wpi::StructFieldType::kInt32: - case wpi::StructFieldType::kInt64: - case wpi::StructFieldType::kUint8: - case wpi::StructFieldType::kUint16: - case wpi::StructFieldType::kUint32: - case wpi::StructFieldType::kUint64: { + case wpi::util::StructFieldType::kInt8: + case wpi::util::StructFieldType::kInt16: + case wpi::util::StructFieldType::kInt32: + case wpi::util::StructFieldType::kInt64: + case wpi::util::StructFieldType::kUint8: + case wpi::util::StructFieldType::kUint16: + case wpi::util::StructFieldType::kUint32: + case wpi::util::StructFieldType::kUint64: { bool isUint = field.IsUint(); if (field.HasEnum()) { if (field.IsArray()) { @@ -326,44 +326,44 @@ static void UpdateStructValueSource(NetworkTablesModel& model, v.emplace_back(s.GetIntField(&field, i)); } } - child.value = nt::Value::MakeIntegerArray(std::move(v), time); + child.value = wpi::nt::Value::MakeIntegerArray(std::move(v), time); } else { if (isUint) { - child.value = nt::Value::MakeInteger(s.GetUintField(&field), time); + child.value = wpi::nt::Value::MakeInteger(s.GetUintField(&field), time); } else { - child.value = nt::Value::MakeInteger(s.GetIntField(&field), time); + child.value = wpi::nt::Value::MakeInteger(s.GetIntField(&field), time); } } child.UpdateFromValue(model, child.path, ""); break; } - case wpi::StructFieldType::kFloat: + case wpi::util::StructFieldType::kFloat: if (field.IsArray()) { std::vector v; v.reserve(field.GetArraySize()); for (size_t i = 0; i < field.GetArraySize(); ++i) { v.emplace_back(s.GetFloatField(&field, i)); } - child.value = nt::Value::MakeFloatArray(std::move(v), time); + child.value = wpi::nt::Value::MakeFloatArray(std::move(v), time); } else { - child.value = nt::Value::MakeFloat(s.GetFloatField(&field), time); + child.value = wpi::nt::Value::MakeFloat(s.GetFloatField(&field), time); } child.UpdateFromValue(model, child.path, ""); break; - case wpi::StructFieldType::kDouble: + case wpi::util::StructFieldType::kDouble: if (field.IsArray()) { std::vector v; v.reserve(field.GetArraySize()); for (size_t i = 0; i < field.GetArraySize(); ++i) { v.emplace_back(s.GetDoubleField(&field, i)); } - child.value = nt::Value::MakeDoubleArray(std::move(v), time); + child.value = wpi::nt::Value::MakeDoubleArray(std::move(v), time); } else { - child.value = nt::Value::MakeDouble(s.GetDoubleField(&field), time); + child.value = wpi::nt::Value::MakeDouble(s.GetDoubleField(&field), time); } child.UpdateFromValue(model, child.path, ""); break; - case wpi::StructFieldType::kStruct: + case wpi::util::StructFieldType::kStruct: if (field.IsArray()) { if (child.valueChildrenMap) { child.valueChildren.clear(); @@ -441,9 +441,9 @@ static void UpdateProtobufValueSource(NetworkTablesModel& model, for (size_t i = 0; i < size; ++i) { v.emplace_back(upb_Array_Get(arr, i).bool_val); } - child.value = nt::Value::MakeBooleanArray(std::move(v), time); + child.value = wpi::nt::Value::MakeBooleanArray(std::move(v), time); } else { - child.value = nt::Value::MakeBoolean(value.bool_val, time); + child.value = wpi::nt::Value::MakeBoolean(value.bool_val, time); child.UpdateFromValue(model, child.path, ""); } break; @@ -458,10 +458,10 @@ static void UpdateProtobufValueSource(NetworkTablesModel& model, upb_StringView sv = upb_Array_Get(arr, i).str_val; v.emplace_back(sv.data, sv.size); } - child.value = nt::Value::MakeStringArray(std::move(v), time); + child.value = wpi::nt::Value::MakeStringArray(std::move(v), time); } else { upb_StringView sv = value.str_val; - child.value = nt::Value::MakeString({sv.data, sv.size}, time); + child.value = wpi::nt::Value::MakeString({sv.data, sv.size}, time); child.UpdateFromValue(model, child.path, ""); } break; @@ -475,9 +475,9 @@ static void UpdateProtobufValueSource(NetworkTablesModel& model, for (size_t i = 0; i < size; ++i) { v.emplace_back(upb_Array_Get(arr, i).int32_val); } - child.value = nt::Value::MakeIntegerArray(std::move(v), time); + child.value = wpi::nt::Value::MakeIntegerArray(std::move(v), time); } else { - child.value = nt::Value::MakeInteger(value.int32_val, time); + child.value = wpi::nt::Value::MakeInteger(value.int32_val, time); } child.UpdateFromValue(model, child.path, ""); break; @@ -491,9 +491,9 @@ static void UpdateProtobufValueSource(NetworkTablesModel& model, for (size_t i = 0; i < size; ++i) { v.emplace_back(upb_Array_Get(arr, i).int64_val); } - child.value = nt::Value::MakeIntegerArray(std::move(v), time); + child.value = wpi::nt::Value::MakeIntegerArray(std::move(v), time); } else { - child.value = nt::Value::MakeInteger(value.int64_val, time); + child.value = wpi::nt::Value::MakeInteger(value.int64_val, time); } child.UpdateFromValue(model, child.path, ""); break; @@ -507,9 +507,9 @@ static void UpdateProtobufValueSource(NetworkTablesModel& model, for (size_t i = 0; i < size; ++i) { v.emplace_back(upb_Array_Get(arr, i).uint32_val); } - child.value = nt::Value::MakeIntegerArray(std::move(v), time); + child.value = wpi::nt::Value::MakeIntegerArray(std::move(v), time); } else { - child.value = nt::Value::MakeInteger(value.uint32_val, time); + child.value = wpi::nt::Value::MakeInteger(value.uint32_val, time); } child.UpdateFromValue(model, child.path, ""); break; @@ -523,9 +523,9 @@ static void UpdateProtobufValueSource(NetworkTablesModel& model, for (size_t i = 0; i < size; ++i) { v.emplace_back(upb_Array_Get(arr, i).uint64_val); } - child.value = nt::Value::MakeIntegerArray(std::move(v), time); + child.value = wpi::nt::Value::MakeIntegerArray(std::move(v), time); } else { - child.value = nt::Value::MakeInteger(value.uint64_val, time); + child.value = wpi::nt::Value::MakeInteger(value.uint64_val, time); } child.UpdateFromValue(model, child.path, ""); break; @@ -539,9 +539,9 @@ static void UpdateProtobufValueSource(NetworkTablesModel& model, for (size_t i = 0; i < size; ++i) { v.emplace_back(upb_Array_Get(arr, i).float_val); } - child.value = nt::Value::MakeFloatArray(std::move(v), time); + child.value = wpi::nt::Value::MakeFloatArray(std::move(v), time); } else { - child.value = nt::Value::MakeFloat(value.float_val, time); + child.value = wpi::nt::Value::MakeFloat(value.float_val, time); } child.UpdateFromValue(model, child.path, ""); break; @@ -555,9 +555,9 @@ static void UpdateProtobufValueSource(NetworkTablesModel& model, for (size_t i = 0; i < size; ++i) { v.emplace_back(upb_Array_Get(arr, i).double_val); } - child.value = nt::Value::MakeDoubleArray(std::move(v), time); + child.value = wpi::nt::Value::MakeDoubleArray(std::move(v), time); } else { - child.value = nt::Value::MakeDouble(value.double_val, time); + child.value = wpi::nt::Value::MakeDouble(value.double_val, time); } child.UpdateFromValue(model, child.path, ""); break; @@ -630,15 +630,15 @@ static void UpdateProtobufValueSource(NetworkTablesModel& model, static void UpdateJsonValueSource(NetworkTablesModel& model, NetworkTablesModel::ValueSource* out, - const wpi::json& j, std::string_view name, + const wpi::util::json& j, std::string_view name, int64_t time) { switch (j.type()) { - case wpi::json::value_t::object: { + case wpi::util::json::value_t::object: { if (!out->valueChildrenMap) { out->valueChildren.clear(); out->valueChildrenMap = true; } - wpi::StringMap elems; + wpi::util::StringMap elems; for (size_t i = 0, size = out->valueChildren.size(); i < size; ++i) { elems[out->valueChildren[i].name] = i; } @@ -671,7 +671,7 @@ static void UpdateJsonValueSource(NetworkTablesModel& model, } break; } - case wpi::json::value_t::array: { + case wpi::util::json::value_t::array: { if (out->valueChildrenMap) { out->valueChildren.clear(); out->valueChildrenMap = false; @@ -688,24 +688,24 @@ static void UpdateJsonValueSource(NetworkTablesModel& model, } break; } - case wpi::json::value_t::string: - out->value = nt::Value::MakeString(j.get_ref(), time); + case wpi::util::json::value_t::string: + out->value = wpi::nt::Value::MakeString(j.get_ref(), time); out->UpdateFromValue(model, name, ""); break; - case wpi::json::value_t::boolean: - out->value = nt::Value::MakeBoolean(j.get(), time); + case wpi::util::json::value_t::boolean: + out->value = wpi::nt::Value::MakeBoolean(j.get(), time); out->UpdateFromValue(model, name, ""); break; - case wpi::json::value_t::number_integer: - out->value = nt::Value::MakeInteger(j.get(), time); + case wpi::util::json::value_t::number_integer: + out->value = wpi::nt::Value::MakeInteger(j.get(), time); out->UpdateFromValue(model, name, ""); break; - case wpi::json::value_t::number_unsigned: - out->value = nt::Value::MakeInteger(j.get(), time); + case wpi::util::json::value_t::number_unsigned: + out->value = wpi::nt::Value::MakeInteger(j.get(), time); out->UpdateFromValue(model, name, ""); break; - case wpi::json::value_t::number_float: - out->value = nt::Value::MakeDouble(j.get(), time); + case wpi::util::json::value_t::number_float: + out->value = wpi::nt::Value::MakeDouble(j.get(), time); out->UpdateFromValue(model, name, ""); break; default: @@ -718,7 +718,7 @@ void NetworkTablesModel::ValueSource::UpdateFromEnum(std::string_view name, std::string_view v, int64_t time) { valueChildren.clear(); - value = nt::Value::MakeString(v, time); + value = wpi::nt::Value::MakeString(v, time); valueStr = v; auto s = dynamic_cast(source.get()); if (!s) { @@ -743,7 +743,7 @@ void NetworkTablesModel::ValueSource::UpdateFromEnum( } child.UpdateFromEnum(child.path, arr[i++], time); } - value = nt::Value::MakeStringArray(std::move(arr), time); + value = wpi::nt::Value::MakeStringArray(std::move(arr), time); } void NetworkTablesModel::ValueSource::UpdateDiscreteSource( @@ -833,19 +833,19 @@ void NetworkTablesModel::ValueSource::UpdateFromValue( break; case NT_BOOLEAN_ARRAY: UpdateDiscreteArray(name, value.GetBooleanArray(), value.time(), - nt::Value::MakeBoolean); + wpi::nt::Value::MakeBoolean); break; case NT_INTEGER_ARRAY: UpdateDiscreteArray(name, value.GetIntegerArray(), value.time(), - nt::Value::MakeInteger); + wpi::nt::Value::MakeInteger); break; case NT_FLOAT_ARRAY: UpdateDiscreteArray(name, value.GetFloatArray(), value.time(), - nt::Value::MakeFloat); + wpi::nt::Value::MakeFloat); break; case NT_DOUBLE_ARRAY: UpdateDiscreteArray(name, value.GetDoubleArray(), value.time(), - nt::Value::MakeDouble); + wpi::nt::Value::MakeDouble); break; case NT_STRING_ARRAY: { auto arr = value.GetStringArray(); @@ -860,7 +860,7 @@ void NetworkTablesModel::ValueSource::UpdateFromValue( child.name = fmt::format("[{}]", i); child.path = fmt::format("{}{}", name, child.name); } - child.value = nt::Value::MakeString(arr[i++], value.time()); + child.value = wpi::nt::Value::MakeString(arr[i++], value.time()); child.UpdateFromValue(model, child.path, ""); } break; @@ -869,15 +869,15 @@ void NetworkTablesModel::ValueSource::UpdateFromValue( if (typeStr == "json") { try { UpdateJsonValueSource(model, this, - wpi::json::parse(value.GetString()), name, + wpi::util::json::parse(value.GetString()), name, value.last_change()); - } catch (wpi::json::exception&) { + } catch (wpi::util::json::exception&) { // ignore } } else { valueChildren.clear(); valueStr.clear(); - wpi::raw_string_ostream os{valueStr}; + wpi::util::raw_string_ostream os{valueStr}; os << '"'; os.write_escaped(value.GetString()); os << '"'; @@ -896,9 +896,9 @@ void NetworkTablesModel::ValueSource::UpdateFromValue( mpack_reader_init_data(&r, value.GetRaw()); UpdateMsgpackValueSource(model, this, r, name, value.last_change()); mpack_reader_destroy(&r); - } else if (auto structNameOpt = wpi::remove_prefix(typeStr, "struct:")) { + } else if (auto structNameOpt = wpi::util::remove_prefix(typeStr, "struct:")) { auto structName = *structNameOpt; - auto withoutArray = wpi::remove_suffix(structName, "[]"); + auto withoutArray = wpi::util::remove_suffix(structName, "[]"); bool isArray = withoutArray.has_value(); if (isArray) { structName = *withoutArray; @@ -919,20 +919,20 @@ void NetworkTablesModel::ValueSource::UpdateFromValue( child.name = fmt::format("[{}]", i); child.path = fmt::format("{}{}", name, child.name); } - wpi::DynamicStruct s{desc, raw}; + wpi::util::DynamicStruct s{desc, raw}; UpdateStructValueSource(model, &child, s, child.path, value.last_change()); ++i; - raw = wpi::drop_front(raw, desc->GetSize()); + raw = wpi::util::drop_front(raw, desc->GetSize()); } } else { - wpi::DynamicStruct s{desc, value.GetRaw()}; + wpi::util::DynamicStruct s{desc, value.GetRaw()}; UpdateStructValueSource(model, this, s, name, value.last_change()); } } else { valueChildren.clear(); } - } else if (auto filename = wpi::remove_prefix(typeStr, "proto:")) { + } else if (auto filename = wpi::util::remove_prefix(typeStr, "proto:")) { const upb_MessageDef* messageDef = upb_DefPool_FindMessageByName( model.GetProtobufDatabase(), filename->data()); if (messageDef) { @@ -968,16 +968,16 @@ void NetworkTablesModel::Update() { for (auto&& event : m_poller.ReadQueue()) { if (auto info = event.GetTopicInfo()) { auto& entry = m_entries[info->topic]; - if (event.flags & nt::EventFlags::kPublish) { + if (event.flags & wpi::nt::EventFlags::kPublish) { if (!entry) { entry = std::make_unique(); m_sortedEntries.emplace_back(entry.get()); updateTree = true; } } - if (event.flags & nt::EventFlags::kUnpublish) { + if (event.flags & wpi::nt::EventFlags::kUnpublish) { // meta topic handling - if (wpi::starts_with(info->name, '$')) { + if (wpi::util::starts_with(info->name, '$')) { // meta topic handling if (info->name == "$clients") { m_clients.clear(); @@ -986,13 +986,13 @@ void NetworkTablesModel::Update() { } else if (info->name == "$serversub") { m_server.subscribers.clear(); } else if (auto client = - wpi::remove_prefix(info->name, "$clientpub$")) { + wpi::util::remove_prefix(info->name, "$clientpub$")) { auto it = m_clients.find(*client); if (it != m_clients.end()) { it->second.publishers.clear(); } } else if (auto client = - wpi::remove_prefix(info->name, "$clientsub$")) { + wpi::util::remove_prefix(info->name, "$clientsub$")) { auto it = m_clients.find(*client); if (it != m_clients.end()) { it->second.subscribers.clear(); @@ -1009,7 +1009,7 @@ void NetworkTablesModel::Update() { updateTree = true; continue; } - if (event.flags & nt::EventFlags::kProperties) { + if (event.flags & wpi::nt::EventFlags::kProperties) { updateTree = true; } if (entry) { @@ -1020,7 +1020,7 @@ void NetworkTablesModel::Update() { if (entry) { entry->value = std::move(valueData->value); entry->UpdateFromValue(*this); - if (wpi::starts_with(entry->info.name, '$') && entry->value.IsRaw() && + if (wpi::util::starts_with(entry->info.name, '$') && entry->value.IsRaw() && entry->info.type_str == "msgpack") { // meta topic handling if (entry->info.name == "$clients") { @@ -1034,20 +1034,20 @@ void NetworkTablesModel::Update() { } else if (entry->info.name == "$serversub") { m_server.UpdateSubscribers(entry->value.GetRaw()); } else if (auto client = - wpi::remove_prefix(entry->info.name, "$clientpub$")) { + wpi::util::remove_prefix(entry->info.name, "$clientpub$")) { auto it = m_clients.find(*client); if (it != m_clients.end()) { it->second.UpdatePublishers(entry->value.GetRaw()); } } else if (auto client = - wpi::remove_prefix(entry->info.name, "$clientsub$")) { + wpi::util::remove_prefix(entry->info.name, "$clientsub$")) { auto it = m_clients.find(*client); if (it != m_clients.end()) { it->second.UpdateSubscribers(entry->value.GetRaw()); } } } else if (auto typeStr = - wpi::remove_prefix(entry->info.name, "/.schema/struct:"); + wpi::util::remove_prefix(entry->info.name, "/.schema/struct:"); entry->value.IsRaw() && typeStr && entry->info.type_str == "structschema") { // struct schema handling @@ -1057,7 +1057,7 @@ void NetworkTablesModel::Update() { std::string err; auto desc = m_structDb.Add(*typeStr, schema, &err); if (!desc) { - wpi::print("could not decode struct '{}' schema '{}': {}\n", + wpi::util::print("could not decode struct '{}' schema '{}': {}\n", entry->info.name, schema, err); } else if (desc->IsValid()) { // loop over all entries with this type and update @@ -1065,17 +1065,17 @@ void NetworkTablesModel::Update() { if (!entryPair.second) { continue; } - if (auto ts = wpi::remove_prefix(entryPair.second->info.type_str, + if (auto ts = wpi::util::remove_prefix(entryPair.second->info.type_str, "struct:")) { if (*ts == *typeStr || - wpi::remove_suffix(*ts, "[]").value_or(*ts) == *typeStr) { + wpi::util::remove_suffix(*ts, "[]").value_or(*ts) == *typeStr) { entryPair.second->UpdateFromValue(*this); } } } } } else if (auto filename = - wpi::remove_prefix(entry->info.name, "/.schema/proto:"); + wpi::util::remove_prefix(entry->info.name, "/.schema/proto:"); entry->value.IsRaw() && filename && entry->info.type_str == "proto:FileDescriptorProto") { // protobuf descriptor handling @@ -1089,7 +1089,7 @@ void NetworkTablesModel::Update() { descriptor.size(), m_arena), &status); if (!status.ok) { - wpi::print("could not decode protobuf '{}' filename '{}'\n", + wpi::util::print("could not decode protobuf '{}' filename '{}'\n", entry->info.name, *filename); } else { // loop over all protobuf entries and update (conservatively) @@ -1098,7 +1098,7 @@ void NetworkTablesModel::Update() { continue; } std::string_view ts = entryPair.second->info.type_str; - if (wpi::starts_with(ts, "proto:")) { + if (wpi::util::starts_with(ts, "proto:")) { entryPair.second->UpdateFromValue(*this); } } @@ -1134,14 +1134,14 @@ void NetworkTablesModel::RebuildTree() { void NetworkTablesModel::RebuildTreeImpl(std::vector* tree, int category) { tree->clear(); - wpi::SmallVector parts; + wpi::util::SmallVector parts; for (auto& entry : m_sortedEntries) { if (!IsVisible(static_cast(category), entry->persistent, entry->retained)) { continue; } parts.clear(); - wpi::split(entry->info.name, '/', -1, false, + wpi::util::split(entry->info.name, '/', -1, false, [&](auto part) { parts.emplace_back(part); }); // ignore a raw "/" key @@ -1151,7 +1151,7 @@ void NetworkTablesModel::RebuildTreeImpl(std::vector* tree, // get to leaf auto nodes = tree; - for (auto part : wpi::drop_back(std::span{parts.begin(), parts.end()})) { + for (auto part : wpi::util::drop_back(std::span{parts.begin(), parts.end()})) { auto it = std::find_if(nodes->begin(), nodes->end(), [&](const auto& node) { return node.name == part; }); @@ -1198,7 +1198,7 @@ NetworkTablesModel::Entry* NetworkTablesModel::AddEntry(NT_Topic topic) { auto& entry = m_entries[topic]; if (!entry) { entry = std::make_unique(); - entry->info = nt::GetTopicInfo(topic); + entry->info = wpi::nt::GetTopicInfo(topic); entry->properties = entry->info.GetProperties(); m_sortedEntries.emplace_back(entry.get()); } @@ -1207,34 +1207,34 @@ NetworkTablesModel::Entry* NetworkTablesModel::AddEntry(NT_Topic topic) { } NetworkTablesModel::Client::Subscriber::Subscriber( - nt::meta::ClientSubscriber&& oth) + wpi::nt::meta::ClientSubscriber&& oth) : ClientSubscriber{std::move(oth)}, topicsStr{StringArrayToString(topics)} {} void NetworkTablesModel::Client::UpdatePublishers( std::span data) { - if (auto pubs = nt::meta::DecodeClientPublishers(data)) { + if (auto pubs = wpi::nt::meta::DecodeClientPublishers(data)) { publishers = std::move(*pubs); } else { - wpi::print(stderr, "Failed to update publishers\n"); + wpi::util::print(stderr, "Failed to update publishers\n"); } } void NetworkTablesModel::Client::UpdateSubscribers( std::span data) { - if (auto subs = nt::meta::DecodeClientSubscribers(data)) { + if (auto subs = wpi::nt::meta::DecodeClientSubscribers(data)) { subscribers.clear(); subscribers.reserve(subs->size()); for (auto&& sub : *subs) { subscribers.emplace_back(std::move(sub)); } } else { - wpi::print(stderr, "Failed to update subscribers\n"); + wpi::util::print(stderr, "Failed to update subscribers\n"); } } void NetworkTablesModel::UpdateClients(std::span data) { - auto clientsArr = nt::meta::DecodeClients(data); + auto clientsArr = wpi::nt::meta::DecodeClients(data); if (!clientsArr) { return; } @@ -1269,17 +1269,17 @@ void NetworkTablesModel::UpdateClients(std::span data) { } static bool GetHeadingTypeString(std::string_view* ts) { - if (auto withoutProto = wpi::remove_prefix(*ts, "proto:")) { + if (auto withoutProto = wpi::util::remove_prefix(*ts, "proto:")) { *ts = *withoutProto; auto lastdot = ts->rfind('.'); if (lastdot != std::string_view::npos) { - *ts = wpi::substr(*ts, lastdot + 1); + *ts = wpi::util::substr(*ts, lastdot + 1); } - if (auto withoutProtobuf = wpi::remove_prefix(*ts, "Protobuf")) { + if (auto withoutProtobuf = wpi::util::remove_prefix(*ts, "Protobuf")) { *ts = *withoutProtobuf; } return true; - } else if (auto withoutStruct = wpi::remove_prefix(*ts, "struct:")) { + } else if (auto withoutStruct = wpi::util::remove_prefix(*ts, "struct:")) { *ts = *withoutStruct; return true; } @@ -1287,9 +1287,9 @@ static bool GetHeadingTypeString(std::string_view* ts) { } static const char* GetShortTypeString(std::string_view ts) { - if (wpi::starts_with(ts, "proto:")) { + if (wpi::util::starts_with(ts, "proto:")) { return "protobuf"; - } else if (wpi::starts_with(ts, "struct:")) { + } else if (wpi::util::starts_with(ts, "struct:")) { return "struct"; } else { return ts.data(); @@ -1449,7 +1449,7 @@ bool ArrayEditorImpl::Emit() { ImGui::TableNextColumn(); ImGui::PushID(row); char label[16]; - wpi::format_to_n_c_str(label, sizeof(label), "[{}]", row); + wpi::util::format_to_n_c_str(label, sizeof(label), "[{}]", row); if constexpr (NTType == NT_BOOLEAN_ARRAY) { static const char* boolOptions[] = {"false", "true"}; ImGui::Combo(label, &m_arr[row], boolOptions, 2); @@ -1502,38 +1502,38 @@ bool ArrayEditorImpl::Emit() { auto* entry = m_model.GetEntry(m_name); if (!entry) { entry = m_model.AddEntry( - nt::GetTopic(m_model.GetInstance().GetHandle(), m_name)); + wpi::nt::GetTopic(m_model.GetInstance().GetHandle(), m_name)); } if constexpr (NTType == NT_BOOLEAN_ARRAY) { if (entry->publisher == 0) { entry->publisher = - nt::Publish(entry->info.topic, NT_BOOLEAN_ARRAY, "boolean[]"); + wpi::nt::Publish(entry->info.topic, NT_BOOLEAN_ARRAY, "boolean[]"); } - nt::SetBooleanArray(entry->publisher, m_arr); + wpi::nt::SetBooleanArray(entry->publisher, m_arr); } else if constexpr (NTType == NT_FLOAT_ARRAY) { if (entry->publisher == 0) { entry->publisher = - nt::Publish(entry->info.topic, NT_FLOAT_ARRAY, "float[]"); + wpi::nt::Publish(entry->info.topic, NT_FLOAT_ARRAY, "float[]"); } - nt::SetFloatArray(entry->publisher, m_arr); + wpi::nt::SetFloatArray(entry->publisher, m_arr); } else if constexpr (NTType == NT_DOUBLE_ARRAY) { if (entry->publisher == 0) { entry->publisher = - nt::Publish(entry->info.topic, NT_DOUBLE_ARRAY, "double[]"); + wpi::nt::Publish(entry->info.topic, NT_DOUBLE_ARRAY, "double[]"); } - nt::SetDoubleArray(entry->publisher, m_arr); + wpi::nt::SetDoubleArray(entry->publisher, m_arr); } else if constexpr (NTType == NT_INTEGER_ARRAY) { if (entry->publisher == 0) { entry->publisher = - nt::Publish(entry->info.topic, NT_INTEGER_ARRAY, "int[]"); + wpi::nt::Publish(entry->info.topic, NT_INTEGER_ARRAY, "int[]"); } - nt::SetIntegerArray(entry->publisher, m_arr); + wpi::nt::SetIntegerArray(entry->publisher, m_arr); } else if constexpr (NTType == NT_STRING_ARRAY) { if (entry->publisher == 0) { entry->publisher = - nt::Publish(entry->info.topic, NT_STRING_ARRAY, "string[]"); + wpi::nt::Publish(entry->info.topic, NT_STRING_ARRAY, "string[]"); } - nt::SetStringArray(entry->publisher, m_arr); + wpi::nt::SetStringArray(entry->publisher, m_arr); } return true; } @@ -1566,9 +1566,9 @@ static void EmitEntryValueEditable(NetworkTablesModel* model, if (ImGui::Combo(typeStr, &v, boolOptions, 2)) { if (entry.publisher == 0) { entry.publisher = - nt::Publish(entry.info.topic, NT_BOOLEAN, "boolean"); + wpi::nt::Publish(entry.info.topic, NT_BOOLEAN, "boolean"); } - nt::SetBoolean(entry.publisher, v); + wpi::nt::SetBoolean(entry.publisher, v); } break; } @@ -1577,9 +1577,9 @@ static void EmitEntryValueEditable(NetworkTablesModel* model, if (InputExpr(typeStr, &v, "%" PRId64, ImGuiInputTextFlags_EnterReturnsTrue)) { if (entry.publisher == 0) { - entry.publisher = nt::Publish(entry.info.topic, NT_INTEGER, "int"); + entry.publisher = wpi::nt::Publish(entry.info.topic, NT_INTEGER, "int"); } - nt::SetInteger(entry.publisher, v); + wpi::nt::SetInteger(entry.publisher, v); } break; } @@ -1588,9 +1588,9 @@ static void EmitEntryValueEditable(NetworkTablesModel* model, if (InputExpr(typeStr, &v, "%.6f", ImGuiInputTextFlags_EnterReturnsTrue)) { if (entry.publisher == 0) { - entry.publisher = nt::Publish(entry.info.topic, NT_FLOAT, "float"); + entry.publisher = wpi::nt::Publish(entry.info.topic, NT_FLOAT, "float"); } - nt::SetFloat(entry.publisher, v); + wpi::nt::SetFloat(entry.publisher, v); } break; } @@ -1606,9 +1606,9 @@ static void EmitEntryValueEditable(NetworkTablesModel* model, fmt::format("%.{}f", precision).c_str(), ImGuiInputTextFlags_EnterReturnsTrue)) { if (entry.publisher == 0) { - entry.publisher = nt::Publish(entry.info.topic, NT_DOUBLE, "double"); + entry.publisher = wpi::nt::Publish(entry.info.topic, NT_DOUBLE, "double"); } - nt::SetDouble(entry.publisher, v); + wpi::nt::SetDouble(entry.publisher, v); } #ifdef __GNUC__ #pragma GCC diagnostic pop @@ -1623,11 +1623,11 @@ static void EmitEntryValueEditable(NetworkTablesModel* model, if (v[0] == '"') { if (entry.publisher == 0) { entry.publisher = - nt::Publish(entry.info.topic, NT_STRING, "string"); + wpi::nt::Publish(entry.info.topic, NT_STRING, "string"); } - wpi::SmallString<128> buf; - nt::SetString(entry.publisher, - wpi::UnescapeCString(v + 1, buf).first); + wpi::util::SmallString<128> buf; + wpi::nt::SetString(entry.publisher, + wpi::util::UnescapeCString(v + 1, buf).first); } } break; @@ -1722,40 +1722,40 @@ static void CreateTopicMenuItem(NetworkTablesModel* model, const char* typeStr, bool enabled) { if (ImGui::MenuItem(typeStr, nullptr, false, enabled)) { auto entry = - model->AddEntry(nt::GetTopic(model->GetInstance().GetHandle(), path)); + model->AddEntry(wpi::nt::GetTopic(model->GetInstance().GetHandle(), path)); if (entry->publisher == 0) { - entry->publisher = nt::Publish(entry->info.topic, type, typeStr); + entry->publisher = wpi::nt::Publish(entry->info.topic, type, typeStr); // publish a default value so it's editable switch (type) { case NT_BOOLEAN: - nt::SetDefaultBoolean(entry->publisher, false); + wpi::nt::SetDefaultBoolean(entry->publisher, false); break; case NT_INTEGER: - nt::SetDefaultInteger(entry->publisher, 0); + wpi::nt::SetDefaultInteger(entry->publisher, 0); break; case NT_FLOAT: - nt::SetDefaultFloat(entry->publisher, 0.0); + wpi::nt::SetDefaultFloat(entry->publisher, 0.0); break; case NT_DOUBLE: - nt::SetDefaultDouble(entry->publisher, 0.0); + wpi::nt::SetDefaultDouble(entry->publisher, 0.0); break; case NT_STRING: - nt::SetDefaultString(entry->publisher, ""); + wpi::nt::SetDefaultString(entry->publisher, ""); break; case NT_BOOLEAN_ARRAY: - nt::SetDefaultBooleanArray(entry->publisher, {}); + wpi::nt::SetDefaultBooleanArray(entry->publisher, {}); break; case NT_INTEGER_ARRAY: - nt::SetDefaultIntegerArray(entry->publisher, {}); + wpi::nt::SetDefaultIntegerArray(entry->publisher, {}); break; case NT_FLOAT_ARRAY: - nt::SetDefaultFloatArray(entry->publisher, {}); + wpi::nt::SetDefaultFloatArray(entry->publisher, {}); break; case NT_DOUBLE_ARRAY: - nt::SetDefaultDoubleArray(entry->publisher, {}); + wpi::nt::SetDefaultDoubleArray(entry->publisher, {}); break; case NT_STRING_ARRAY: - nt::SetDefaultStringArray(entry->publisher, {}); + wpi::nt::SetDefaultStringArray(entry->publisher, {}); break; default: break; @@ -1764,7 +1764,7 @@ static void CreateTopicMenuItem(NetworkTablesModel* model, } } -void glass::DisplayNetworkTablesAddMenu(NetworkTablesModel* model, +void wpi::glass::DisplayNetworkTablesAddMenu(NetworkTablesModel* model, std::string_view path, NetworkTablesFlags flags) { static char nameBuffer[kTextBufferSize]; @@ -1849,7 +1849,7 @@ static void EmitValueTree( char label[128]; std::string_view ts = child.typeStr; bool havePopup = GetHeadingTypeString(&ts); - wpi::format_to_n_c_str(label, sizeof(label), "{}##v_{}", ts.data(), + wpi::util::format_to_n_c_str(label, sizeof(label), "{}##v_{}", ts.data(), child.name.c_str()); bool valueChildrenOpen = TreeNodeEx(label, ImGuiTreeNodeFlags_SpanFullWidth); @@ -1891,7 +1891,7 @@ static void EmitEntry(NetworkTablesModel* model, char label[128]; std::string_view ts = entry.info.type_str; bool havePopup = GetHeadingTypeString(&ts); - wpi::format_to_n_c_str(label, sizeof(label), "{}##v_{}", ts.data(), + wpi::util::format_to_n_c_str(label, sizeof(label), "{}##v_{}", ts.data(), entry.info.name.c_str()); valueChildrenOpen = TreeNodeEx(label, ImGuiTreeNodeFlags_SpanFullWidth | @@ -1957,13 +1957,13 @@ static void EmitEntry(NetworkTablesModel* model, ImGui::Text("%s", entry.info.properties.c_str()); if (ImGui::BeginPopupContextItem(entry.info.name.c_str())) { if (ImGui::Checkbox("persistent", &entry.persistent)) { - nt::SetTopicPersistent(entry.info.topic, entry.persistent); + wpi::nt::SetTopicPersistent(entry.info.topic, entry.persistent); } if (ImGui::Checkbox("retained", &entry.retained)) { if (entry.retained) { - nt::SetTopicProperty(entry.info.topic, "retained", true); + wpi::nt::SetTopicProperty(entry.info.topic, "retained", true); } else { - nt::DeleteTopicProperty(entry.info.topic, "retained"); + wpi::nt::DeleteTopicProperty(entry.info.topic, "retained"); } } ImGui::EndPopup(); @@ -2005,7 +2005,7 @@ static void EmitTree(NetworkTablesModel* model, bool root) { for (auto&& node : tree) { if (root && (flags & NetworkTablesFlags_ShowSpecial) == 0 && - wpi::starts_with(node.name, '$')) { + wpi::util::starts_with(node.name, '$')) { continue; } if (node.entry) { @@ -2080,7 +2080,7 @@ static void DisplayTable(NetworkTablesModel* model, } else { for (auto entry : model->GetEntries()) { if ((flags & NetworkTablesFlags_ShowSpecial) != 0 || - !wpi::starts_with(entry->info.name, '$')) { + !wpi::util::starts_with(entry->info.name, '$')) { EmitEntry(model, *entry, entry->info.name.c_str(), flags, category); } } @@ -2139,7 +2139,7 @@ static void DisplayClient(const NetworkTablesModel::Client& client) { } } -void glass::DisplayNetworkTablesInfo(NetworkTablesModel* model) { +void wpi::glass::DisplayNetworkTablesInfo(NetworkTablesModel* model) { auto inst = model->GetInstance(); if (CollapsingHeader("Connections")) { @@ -2193,7 +2193,7 @@ void glass::DisplayNetworkTablesInfo(NetworkTablesModel* model) { } } -void glass::DisplayNetworkTables(NetworkTablesModel* model, +void wpi::glass::DisplayNetworkTables(NetworkTablesModel* model, NetworkTablesFlags flags) { gArrayEditorID = ImGui::GetID("Array Editor"); if (ImGui::BeginPopupModal("Array Editor", nullptr, diff --git a/glass/src/libnt/native/cpp/NetworkTablesProvider.cpp b/glass/src/libnt/native/cpp/NetworkTablesProvider.cpp index dd7f6792a5..51cfb678e5 100644 --- a/glass/src/libnt/native/cpp/NetworkTablesProvider.cpp +++ b/glass/src/libnt/native/cpp/NetworkTablesProvider.cpp @@ -16,20 +16,20 @@ #include "wpi/util/SmallString.hpp" #include "wpi/util/StringExtras.hpp" -using namespace glass; +using namespace wpi::glass; NetworkTablesProvider::NetworkTablesProvider(Storage& storage) - : NetworkTablesProvider{storage, nt::NetworkTableInstance::GetDefault()} {} + : NetworkTablesProvider{storage, wpi::nt::NetworkTableInstance::GetDefault()} {} NetworkTablesProvider::NetworkTablesProvider(Storage& storage, - nt::NetworkTableInstance inst) + wpi::nt::NetworkTableInstance inst) : Provider{storage.GetChild("windows")}, m_inst{inst}, m_poller{inst}, m_typeCache{storage.GetChild("types")} { storage.SetCustomApply([this] { m_listener = m_poller.AddListener( - {{""}}, nt::EventFlags::kImmediate | nt::EventFlags::kTopic); + {{""}}, wpi::nt::EventFlags::kImmediate | wpi::nt::EventFlags::kTopic); for (auto&& childIt : m_storage.GetChildren()) { auto id = childIt.key(); auto typePtr = m_typeCache.FindValue(id); @@ -64,11 +64,11 @@ NetworkTablesProvider::NetworkTablesProvider(Storage& storage, } void NetworkTablesProvider::DisplayMenu() { - wpi::SmallVector path; - wpi::SmallString<64> name; + wpi::util::SmallVector path; + wpi::util::SmallString<64> name; for (auto&& entry : m_viewEntries) { path.clear(); - wpi::split(entry->name, '/', -1, false, + wpi::util::split(entry->name, '/', -1, false, [&](auto name) { path.emplace_back(name); }); bool fullDepth = true; @@ -88,7 +88,7 @@ void NetworkTablesProvider::DisplayMenu() { // data is the last item, so is guaranteed to be null-terminated ImGui::MenuItem(path.back().data(), nullptr, &visible, true); // Add type label to smartdashboard sendables - if (wpi::starts_with(entry->name, "/SmartDashboard/")) { + if (wpi::util::starts_with(entry->name, "/SmartDashboard/")) { auto typeEntry = m_typeCache.FindValue(entry->name); if (typeEntry) { ImGui::SameLine(); @@ -119,12 +119,12 @@ void NetworkTablesProvider::Update() { if (auto info = event.GetTopicInfo()) { // add/remove entries from NT changes // look for .type fields - if (!wpi::ends_with(info->name, "/.type") || info->type != NT_STRING || + if (!wpi::util::ends_with(info->name, "/.type") || info->type != NT_STRING || info->type_str != "string") { continue; } - if (event.flags & nt::EventFlags::kUnpublish) { + if (event.flags & wpi::nt::EventFlags::kUnpublish) { auto it = m_topicMap.find(info->topic); if (it != m_topicMap.end()) { m_poller.RemoveListener(it->second.listener); @@ -139,13 +139,13 @@ void NetworkTablesProvider::Update() { if (it2 != m_viewEntries.end()) { m_viewEntries.erase(it2); } - } else if (event.flags & nt::EventFlags::kPublish) { + } else if (event.flags & wpi::nt::EventFlags::kPublish) { // subscribe to it; use a subscriber so we only get string values SubListener sublistener; - sublistener.subscriber = nt::StringTopic{info->topic}.Subscribe(""); + sublistener.subscriber = wpi::nt::StringTopic{info->topic}.Subscribe(""); sublistener.listener = m_poller.AddListener( sublistener.subscriber, - nt::EventFlags::kValueAll | nt::EventFlags::kImmediate); + wpi::nt::EventFlags::kValueAll | wpi::nt::EventFlags::kImmediate); m_topicMap.try_emplace(info->topic, std::move(sublistener)); } } else if (auto valueData = event.GetValueEventData()) { @@ -160,11 +160,11 @@ void NetworkTablesProvider::Update() { continue; } - auto topicName = nt::GetTopicName(valueData->topic); + auto topicName = wpi::nt::GetTopicName(valueData->topic); auto tableName = - wpi::remove_suffix(topicName, "/.type").value_or(topicName); + wpi::util::remove_suffix(topicName, "/.type").value_or(topicName); - GetOrCreateView(builderIt->second, nt::Topic{valueData->topic}, + GetOrCreateView(builderIt->second, wpi::nt::Topic{valueData->topic}, tableName); // cache the type m_typeCache.SetString(tableName, valueData->value.GetString()); @@ -201,7 +201,7 @@ void NetworkTablesProvider::Show(ViewEntry* entry, Window* window) { if (!window) { return; } - if (auto name = wpi::remove_prefix(entry->name, "/SmartDashboard/")) { + if (auto name = wpi::util::remove_prefix(entry->name, "/SmartDashboard/")) { window->SetDefaultName(fmt::format("{} (SmartDashboard)", *name)); } entry->window = window; @@ -218,7 +218,7 @@ void NetworkTablesProvider::Show(ViewEntry* entry, Window* window) { } NetworkTablesProvider::ViewEntry* NetworkTablesProvider::GetOrCreateView( - const Builder& builder, nt::Topic typeTopic, std::string_view name) { + const Builder& builder, wpi::nt::Topic typeTopic, std::string_view name) { // get view entry if it already exists auto viewIt = FindViewEntry(name); if (viewIt != m_viewEntries.end() && (*viewIt)->name == name) { diff --git a/glass/src/libnt/native/cpp/NetworkTablesSettings.cpp b/glass/src/libnt/native/cpp/NetworkTablesSettings.cpp index 62dd13a2e3..f9ccc4be00 100644 --- a/glass/src/libnt/native/cpp/NetworkTablesSettings.cpp +++ b/glass/src/libnt/native/cpp/NetworkTablesSettings.cpp @@ -17,7 +17,7 @@ #include "wpi/nt/ntcore_cpp.hpp" #include "wpi/util/StringExtras.hpp" -using namespace glass; +using namespace wpi::glass; void NetworkTablesSettings::Thread::Main() { while (m_active) { @@ -42,16 +42,16 @@ void NetworkTablesSettings::Thread::Main() { lock.unlock(); // if just changing servers in client mode, no need to stop and restart - unsigned int curMode = nt::GetNetworkMode(m_inst); + unsigned int curMode = wpi::nt::GetNetworkMode(m_inst); if ((mode == 0 || mode == 2) || (mode == 1 && (curMode & NT_NET_MODE_CLIENT) == 0)) { - nt::StopClient(m_inst); - nt::StopServer(m_inst); - nt::StopLocal(m_inst); + wpi::nt::StopClient(m_inst); + wpi::nt::StopServer(m_inst); + wpi::nt::StopLocal(m_inst); } if ((m_mode == 0 || m_mode == 2) || !dsClient) { - nt::StopDSClient(m_inst); + wpi::nt::StopDSClient(m_inst); } lock.lock(); @@ -61,25 +61,25 @@ void NetworkTablesSettings::Thread::Main() { std::string_view serverTeam{m_serverTeam}; std::optional team; if (m_mode == 1) { - nt::StartClient(m_inst, m_clientName); + wpi::nt::StartClient(m_inst, m_clientName); } - if (!wpi::contains(serverTeam, '.') && - (team = wpi::parse_integer(serverTeam, 10))) { - nt::SetServerTeam(m_inst, team.value(), m_port); + if (!wpi::util::contains(serverTeam, '.') && + (team = wpi::util::parse_integer(serverTeam, 10))) { + wpi::nt::SetServerTeam(m_inst, team.value(), m_port); } else { std::vector> servers; - wpi::split(serverTeam, ',', -1, false, [&](auto serverName) { + wpi::util::split(serverTeam, ',', -1, false, [&](auto serverName) { servers.emplace_back(serverName, m_port); }); - nt::SetServer(m_inst, servers); + wpi::nt::SetServer(m_inst, servers); } if (m_dsClient) { - nt::StartDSClient(m_inst, m_port); + wpi::nt::StartDSClient(m_inst, m_port); } } else if (m_mode == 3) { - nt::StartServer(m_inst, m_iniName.c_str(), m_listenAddress.c_str(), + wpi::nt::StartServer(m_inst, m_iniName.c_str(), m_listenAddress.c_str(), m_port); } } diff --git a/glass/src/libnt/native/cpp/StandardNetworkTables.cpp b/glass/src/libnt/native/cpp/StandardNetworkTables.cpp index 695bab053b..1fd1306ed6 100644 --- a/glass/src/libnt/native/cpp/StandardNetworkTables.cpp +++ b/glass/src/libnt/native/cpp/StandardNetworkTables.cpp @@ -22,12 +22,12 @@ #include "wpi/glass/networktables/NTSubsystem.hpp" #include "wpi/glass/networktables/NetworkTablesProvider.hpp" -using namespace glass; +using namespace wpi::glass; -void glass::AddStandardNetworkTablesViews(NetworkTablesProvider& provider) { +void wpi::glass::AddStandardNetworkTablesViews(NetworkTablesProvider& provider) { provider.Register( NTAlertsModel::kType, - [](nt::NetworkTableInstance inst, const char* path) { + [](wpi::nt::NetworkTableInstance inst, const char* path) { return std::make_unique(inst, path); }, [](Window* win, Model* model, const char*) { @@ -37,7 +37,7 @@ void glass::AddStandardNetworkTablesViews(NetworkTablesProvider& provider) { }); provider.Register( NTCommandSchedulerModel::kType, - [](nt::NetworkTableInstance inst, const char* path) { + [](wpi::nt::NetworkTableInstance inst, const char* path) { return std::make_unique(inst, path); }, [](Window* win, Model* model, const char*) { @@ -48,7 +48,7 @@ void glass::AddStandardNetworkTablesViews(NetworkTablesProvider& provider) { }); provider.Register( NTCommandSelectorModel::kType, - [](nt::NetworkTableInstance inst, const char* path) { + [](wpi::nt::NetworkTableInstance inst, const char* path) { return std::make_unique(inst, path); }, [](Window* win, Model* model, const char*) { @@ -59,7 +59,7 @@ void glass::AddStandardNetworkTablesViews(NetworkTablesProvider& provider) { }); provider.Register( NTDifferentialDriveModel::kType, - [](nt::NetworkTableInstance inst, const char* path) { + [](wpi::nt::NetworkTableInstance inst, const char* path) { return std::make_unique(inst, path); }, [](Window* win, Model* model, const char*) { @@ -70,7 +70,7 @@ void glass::AddStandardNetworkTablesViews(NetworkTablesProvider& provider) { }); provider.Register( NTFMSModel::kType, - [](nt::NetworkTableInstance inst, const char* path) { + [](wpi::nt::NetworkTableInstance inst, const char* path) { return std::make_unique(inst, path); }, [](Window* win, Model* model, const char*) { @@ -80,7 +80,7 @@ void glass::AddStandardNetworkTablesViews(NetworkTablesProvider& provider) { }); provider.Register( NTDigitalInputModel::kType, - [](nt::NetworkTableInstance inst, const char* path) { + [](wpi::nt::NetworkTableInstance inst, const char* path) { return std::make_unique(inst, path); }, [](Window* win, Model* model, const char*) { @@ -91,7 +91,7 @@ void glass::AddStandardNetworkTablesViews(NetworkTablesProvider& provider) { }); provider.Register( NTDigitalOutputModel::kType, - [](nt::NetworkTableInstance inst, const char* path) { + [](wpi::nt::NetworkTableInstance inst, const char* path) { return std::make_unique(inst, path); }, [](Window* win, Model* model, const char*) { @@ -102,7 +102,7 @@ void glass::AddStandardNetworkTablesViews(NetworkTablesProvider& provider) { }); provider.Register( NTField2DModel::kType, - [](nt::NetworkTableInstance inst, const char* path) { + [](wpi::nt::NetworkTableInstance inst, const char* path) { return std::make_unique(inst, path); }, [=](Window* win, Model* model, const char* path) { @@ -114,7 +114,7 @@ void glass::AddStandardNetworkTablesViews(NetworkTablesProvider& provider) { }); provider.Register( NTGyroModel::kType, - [](nt::NetworkTableInstance inst, const char* path) { + [](wpi::nt::NetworkTableInstance inst, const char* path) { return std::make_unique(inst, path); }, [](Window* win, Model* model, const char* path) { @@ -124,7 +124,7 @@ void glass::AddStandardNetworkTablesViews(NetworkTablesProvider& provider) { }); provider.Register( NTMecanumDriveModel::kType, - [](nt::NetworkTableInstance inst, const char* path) { + [](wpi::nt::NetworkTableInstance inst, const char* path) { return std::make_unique(inst, path); }, [](Window* win, Model* model, const char*) { @@ -134,7 +134,7 @@ void glass::AddStandardNetworkTablesViews(NetworkTablesProvider& provider) { }); provider.Register( NTMechanism2DModel::kType, - [](nt::NetworkTableInstance inst, const char* path) { + [](wpi::nt::NetworkTableInstance inst, const char* path) { return std::make_unique(inst, path); }, [=](Window* win, Model* model, const char* path) { @@ -146,7 +146,7 @@ void glass::AddStandardNetworkTablesViews(NetworkTablesProvider& provider) { }); provider.Register( NTPIDControllerModel::kType, - [](nt::NetworkTableInstance inst, const char* path) { + [](wpi::nt::NetworkTableInstance inst, const char* path) { return std::make_unique(inst, path); }, [](Window* win, Model* model, const char* path) { @@ -157,7 +157,7 @@ void glass::AddStandardNetworkTablesViews(NetworkTablesProvider& provider) { }); provider.Register( NTProfiledPIDControllerModel::kType, - [](nt::NetworkTableInstance inst, const char* path) { + [](wpi::nt::NetworkTableInstance inst, const char* path) { return std::make_unique(inst, path); }, [](Window* win, Model* model, const char* path) { @@ -169,7 +169,7 @@ void glass::AddStandardNetworkTablesViews(NetworkTablesProvider& provider) { }); provider.Register( NTMotorControllerModel::kType, - [](nt::NetworkTableInstance inst, const char* path) { + [](wpi::nt::NetworkTableInstance inst, const char* path) { return std::make_unique(inst, path); }, [](Window* win, Model* model, const char* path) { @@ -180,7 +180,7 @@ void glass::AddStandardNetworkTablesViews(NetworkTablesProvider& provider) { }); provider.Register( NTStringChooserModel::kType, - [](nt::NetworkTableInstance inst, const char* path) { + [](wpi::nt::NetworkTableInstance inst, const char* path) { return std::make_unique(inst, path); }, [](Window* win, Model* model, const char*) { @@ -191,7 +191,7 @@ void glass::AddStandardNetworkTablesViews(NetworkTablesProvider& provider) { }); provider.Register( NTSubsystemModel::kType, - [](nt::NetworkTableInstance inst, const char* path) { + [](wpi::nt::NetworkTableInstance inst, const char* path) { return std::make_unique(inst, path); }, [](Window* win, Model* model, const char*) { diff --git a/glass/src/libnt/native/include/wpi/glass/networktables/NTAlerts.hpp b/glass/src/libnt/native/include/wpi/glass/networktables/NTAlerts.hpp index f6ad5c0b06..37bfd2a655 100644 --- a/glass/src/libnt/native/include/wpi/glass/networktables/NTAlerts.hpp +++ b/glass/src/libnt/native/include/wpi/glass/networktables/NTAlerts.hpp @@ -12,7 +12,7 @@ #include "wpi/nt/NetworkTableInstance.hpp" #include "wpi/nt/StringArrayTopic.hpp" -namespace glass { +namespace wpi::glass { class NTAlertsModel : public AlertsModel { public: @@ -20,7 +20,7 @@ class NTAlertsModel : public AlertsModel { // path is to the table containing ".type", excluding the trailing / explicit NTAlertsModel(std::string_view path); - NTAlertsModel(nt::NetworkTableInstance inst, std::string_view path); + NTAlertsModel(wpi::nt::NetworkTableInstance inst, std::string_view path); const std::vector& GetInfos() override { return m_infosValue; } @@ -35,14 +35,14 @@ class NTAlertsModel : public AlertsModel { bool IsReadOnly() override { return false; } private: - nt::NetworkTableInstance m_inst; - nt::StringArraySubscriber m_infos; - nt::StringArraySubscriber m_warnings; - nt::StringArraySubscriber m_errors; + wpi::nt::NetworkTableInstance m_inst; + wpi::nt::StringArraySubscriber m_infos; + wpi::nt::StringArraySubscriber m_warnings; + wpi::nt::StringArraySubscriber m_errors; std::vector m_infosValue; std::vector m_warningsValue; std::vector m_errorsValue; }; -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/libnt/native/include/wpi/glass/networktables/NTCommandScheduler.hpp b/glass/src/libnt/native/include/wpi/glass/networktables/NTCommandScheduler.hpp index 2e8a2ae15e..83a8075c28 100644 --- a/glass/src/libnt/native/include/wpi/glass/networktables/NTCommandScheduler.hpp +++ b/glass/src/libnt/native/include/wpi/glass/networktables/NTCommandScheduler.hpp @@ -17,13 +17,13 @@ #include "wpi/nt/StringArrayTopic.hpp" #include "wpi/nt/StringTopic.hpp" -namespace glass { +namespace wpi::glass { class NTCommandSchedulerModel : public CommandSchedulerModel { public: static constexpr const char* kType = "Scheduler"; explicit NTCommandSchedulerModel(std::string_view path); - NTCommandSchedulerModel(nt::NetworkTableInstance inst, std::string_view path); + NTCommandSchedulerModel(wpi::nt::NetworkTableInstance inst, std::string_view path); const char* GetName() const override { return m_nameValue.c_str(); } const std::vector& GetCurrentCommands() override { @@ -37,14 +37,14 @@ class NTCommandSchedulerModel : public CommandSchedulerModel { bool IsReadOnly() override { return false; } private: - nt::NetworkTableInstance m_inst; - nt::StringSubscriber m_name; - nt::StringArraySubscriber m_commands; - nt::IntegerArraySubscriber m_ids; - nt::IntegerArrayPublisher m_cancel; + wpi::nt::NetworkTableInstance m_inst; + wpi::nt::StringSubscriber m_name; + wpi::nt::StringArraySubscriber m_commands; + wpi::nt::IntegerArraySubscriber m_ids; + wpi::nt::IntegerArrayPublisher m_cancel; std::string m_nameValue; std::vector m_commandsValue; std::vector m_idsValue; }; -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/libnt/native/include/wpi/glass/networktables/NTCommandSelector.hpp b/glass/src/libnt/native/include/wpi/glass/networktables/NTCommandSelector.hpp index 86b89c3bfa..3e4782527f 100644 --- a/glass/src/libnt/native/include/wpi/glass/networktables/NTCommandSelector.hpp +++ b/glass/src/libnt/native/include/wpi/glass/networktables/NTCommandSelector.hpp @@ -13,13 +13,13 @@ #include "wpi/nt/NetworkTableInstance.hpp" #include "wpi/nt/StringTopic.hpp" -namespace glass { +namespace wpi::glass { class NTCommandSelectorModel : public CommandSelectorModel { public: static constexpr const char* kType = "Command"; explicit NTCommandSelectorModel(std::string_view path); - NTCommandSelectorModel(nt::NetworkTableInstance inst, std::string_view path); + NTCommandSelectorModel(wpi::nt::NetworkTableInstance inst, std::string_view path); const char* GetName() const override { return m_nameValue.c_str(); } BooleanSource* GetRunningData() override { return &m_runningData; } @@ -30,11 +30,11 @@ class NTCommandSelectorModel : public CommandSelectorModel { bool IsReadOnly() override { return false; } private: - nt::NetworkTableInstance m_inst; - nt::BooleanEntry m_running; - nt::StringSubscriber m_name; + wpi::nt::NetworkTableInstance m_inst; + wpi::nt::BooleanEntry m_running; + wpi::nt::StringSubscriber m_name; BooleanSource m_runningData; std::string m_nameValue; }; -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/libnt/native/include/wpi/glass/networktables/NTDifferentialDrive.hpp b/glass/src/libnt/native/include/wpi/glass/networktables/NTDifferentialDrive.hpp index 8826135a9d..a9acb251f9 100644 --- a/glass/src/libnt/native/include/wpi/glass/networktables/NTDifferentialDrive.hpp +++ b/glass/src/libnt/native/include/wpi/glass/networktables/NTDifferentialDrive.hpp @@ -15,13 +15,13 @@ #include "wpi/nt/NetworkTableInstance.hpp" #include "wpi/nt/StringTopic.hpp" -namespace glass { +namespace wpi::glass { class NTDifferentialDriveModel : public DriveModel { public: static constexpr const char* kType = "DifferentialDrive"; explicit NTDifferentialDriveModel(std::string_view path); - NTDifferentialDriveModel(nt::NetworkTableInstance instance, + NTDifferentialDriveModel(wpi::nt::NetworkTableInstance instance, std::string_view path); const char* GetName() const override { return m_nameValue.c_str(); } @@ -37,11 +37,11 @@ class NTDifferentialDriveModel : public DriveModel { bool IsReadOnly() override { return !m_controllableValue; } private: - nt::NetworkTableInstance m_inst; - nt::StringSubscriber m_name; - nt::BooleanSubscriber m_controllable; - nt::DoubleEntry m_lPercent; - nt::DoubleEntry m_rPercent; + wpi::nt::NetworkTableInstance m_inst; + wpi::nt::StringSubscriber m_name; + wpi::nt::BooleanSubscriber m_controllable; + wpi::nt::DoubleEntry m_lPercent; + wpi::nt::DoubleEntry m_rPercent; std::string m_nameValue; bool m_controllableValue = false; @@ -52,4 +52,4 @@ class NTDifferentialDriveModel : public DriveModel { ImVec2 m_speedVector; double m_rotation; }; -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/libnt/native/include/wpi/glass/networktables/NTDigitalInput.hpp b/glass/src/libnt/native/include/wpi/glass/networktables/NTDigitalInput.hpp index 3847581439..4e96e052e8 100644 --- a/glass/src/libnt/native/include/wpi/glass/networktables/NTDigitalInput.hpp +++ b/glass/src/libnt/native/include/wpi/glass/networktables/NTDigitalInput.hpp @@ -13,7 +13,7 @@ #include "wpi/nt/NetworkTableInstance.hpp" #include "wpi/nt/StringTopic.hpp" -namespace glass { +namespace wpi::glass { class NTDigitalInputModel : public DIOModel { public: @@ -21,7 +21,7 @@ class NTDigitalInputModel : public DIOModel { // path is to the table containing ".type", excluding the trailing / explicit NTDigitalInputModel(std::string_view path); - NTDigitalInputModel(nt::NetworkTableInstance inst, std::string_view path); + NTDigitalInputModel(wpi::nt::NetworkTableInstance inst, std::string_view path); const char* GetName() const override { return m_nameValue.c_str(); } @@ -42,12 +42,12 @@ class NTDigitalInputModel : public DIOModel { bool IsReadOnly() override { return true; } private: - nt::NetworkTableInstance m_inst; - nt::BooleanSubscriber m_value; - nt::StringSubscriber m_name; + wpi::nt::NetworkTableInstance m_inst; + wpi::nt::BooleanSubscriber m_value; + wpi::nt::StringSubscriber m_name; BooleanSource m_valueData; std::string m_nameValue; }; -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/libnt/native/include/wpi/glass/networktables/NTDigitalOutput.hpp b/glass/src/libnt/native/include/wpi/glass/networktables/NTDigitalOutput.hpp index 84bdb6e2f8..768cdb8978 100644 --- a/glass/src/libnt/native/include/wpi/glass/networktables/NTDigitalOutput.hpp +++ b/glass/src/libnt/native/include/wpi/glass/networktables/NTDigitalOutput.hpp @@ -13,7 +13,7 @@ #include "wpi/nt/NetworkTableInstance.hpp" #include "wpi/nt/StringTopic.hpp" -namespace glass { +namespace wpi::glass { class NTDigitalOutputModel : public DIOModel { public: @@ -21,7 +21,7 @@ class NTDigitalOutputModel : public DIOModel { // path is to the table containing ".type", excluding the trailing / explicit NTDigitalOutputModel(std::string_view path); - NTDigitalOutputModel(nt::NetworkTableInstance inst, std::string_view path); + NTDigitalOutputModel(wpi::nt::NetworkTableInstance inst, std::string_view path); const char* GetName() const override { return m_nameValue.c_str(); } @@ -42,14 +42,14 @@ class NTDigitalOutputModel : public DIOModel { bool IsReadOnly() override { return !m_controllableValue; } private: - nt::NetworkTableInstance m_inst; - nt::BooleanEntry m_value; - nt::StringSubscriber m_name; - nt::BooleanSubscriber m_controllable; + wpi::nt::NetworkTableInstance m_inst; + wpi::nt::BooleanEntry m_value; + wpi::nt::StringSubscriber m_name; + wpi::nt::BooleanSubscriber m_controllable; BooleanSource m_valueData; std::string m_nameValue; bool m_controllableValue = false; }; -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/libnt/native/include/wpi/glass/networktables/NTFMS.hpp b/glass/src/libnt/native/include/wpi/glass/networktables/NTFMS.hpp index f519b94544..e0a9d3778e 100644 --- a/glass/src/libnt/native/include/wpi/glass/networktables/NTFMS.hpp +++ b/glass/src/libnt/native/include/wpi/glass/networktables/NTFMS.hpp @@ -13,7 +13,7 @@ #include "wpi/nt/NetworkTableInstance.hpp" #include "wpi/nt/StringTopic.hpp" -namespace glass { +namespace wpi::glass { class NTFMSModel : public FMSModel { public: @@ -21,7 +21,7 @@ class NTFMSModel : public FMSModel { // path is to the table containing ".type", excluding the trailing / explicit NTFMSModel(std::string_view path); - NTFMSModel(nt::NetworkTableInstance inst, std::string_view path); + NTFMSModel(wpi::nt::NetworkTableInstance inst, std::string_view path); BooleanSource* GetFmsAttachedData() override { return &m_fmsAttached; } BooleanSource* GetDsAttachedData() override { return &m_dsAttached; } @@ -54,11 +54,11 @@ class NTFMSModel : public FMSModel { bool IsReadOnly() override { return true; } private: - nt::NetworkTableInstance m_inst; - nt::StringSubscriber m_gameSpecificMessage; - nt::BooleanSubscriber m_alliance; - nt::IntegerSubscriber m_station; - nt::IntegerSubscriber m_controlWord; + wpi::nt::NetworkTableInstance m_inst; + wpi::nt::StringSubscriber m_gameSpecificMessage; + wpi::nt::BooleanSubscriber m_alliance; + wpi::nt::IntegerSubscriber m_station; + wpi::nt::IntegerSubscriber m_controlWord; BooleanSource m_fmsAttached; BooleanSource m_dsAttached; @@ -70,4 +70,4 @@ class NTFMSModel : public FMSModel { StringSource m_gameSpecificMessageData; }; -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/libnt/native/include/wpi/glass/networktables/NTField2D.hpp b/glass/src/libnt/native/include/wpi/glass/networktables/NTField2D.hpp index 8863bebf83..006ba5f783 100644 --- a/glass/src/libnt/native/include/wpi/glass/networktables/NTField2D.hpp +++ b/glass/src/libnt/native/include/wpi/glass/networktables/NTField2D.hpp @@ -17,7 +17,7 @@ #include "wpi/nt/StringTopic.hpp" #include "wpi/nt/ntcore_cpp.hpp" -namespace glass { +namespace wpi::glass { class NTField2DModel : public Field2DModel { public: @@ -25,7 +25,7 @@ class NTField2DModel : public Field2DModel { // path is to the table containing ".type", excluding the trailing / explicit NTField2DModel(std::string_view path); - NTField2DModel(nt::NetworkTableInstance inst, std::string_view path); + NTField2DModel(wpi::nt::NetworkTableInstance inst, std::string_view path); ~NTField2DModel() override; const char* GetPath() const { return m_path.c_str(); } @@ -38,15 +38,15 @@ class NTField2DModel : public Field2DModel { FieldObjectModel* AddFieldObject(std::string_view name) override; void RemoveFieldObject(std::string_view name) override; void ForEachFieldObject( - wpi::function_ref + wpi::util::function_ref func) override; private: std::string m_path; - nt::NetworkTableInstance m_inst; - nt::MultiSubscriber m_tableSub; - nt::StringTopic m_nameTopic; - nt::NetworkTableListenerPoller m_poller; + wpi::nt::NetworkTableInstance m_inst; + wpi::nt::MultiSubscriber m_tableSub; + wpi::nt::StringTopic m_nameTopic; + wpi::nt::NetworkTableListenerPoller m_poller; std::string m_nameValue; class ObjectModel; @@ -56,4 +56,4 @@ class NTField2DModel : public Field2DModel { std::pair Find(std::string_view fullName); }; -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/libnt/native/include/wpi/glass/networktables/NTGyro.hpp b/glass/src/libnt/native/include/wpi/glass/networktables/NTGyro.hpp index 335fdd28ad..c29cce4d45 100644 --- a/glass/src/libnt/native/include/wpi/glass/networktables/NTGyro.hpp +++ b/glass/src/libnt/native/include/wpi/glass/networktables/NTGyro.hpp @@ -13,13 +13,13 @@ #include "wpi/nt/NetworkTableInstance.hpp" #include "wpi/nt/StringTopic.hpp" -namespace glass { +namespace wpi::glass { class NTGyroModel : public GyroModel { public: static constexpr const char* kType = "Gyro"; explicit NTGyroModel(std::string_view path); - NTGyroModel(nt::NetworkTableInstance inst, std::string_view path); + NTGyroModel(wpi::nt::NetworkTableInstance inst, std::string_view path); const char* GetName() const override { return m_nameValue.c_str(); } const char* GetSimDevice() const override { return nullptr; } @@ -32,11 +32,11 @@ class NTGyroModel : public GyroModel { bool IsReadOnly() override { return true; } private: - nt::NetworkTableInstance m_inst; - nt::DoubleSubscriber m_angle; - nt::StringSubscriber m_name; + wpi::nt::NetworkTableInstance m_inst; + wpi::nt::DoubleSubscriber m_angle; + wpi::nt::StringSubscriber m_name; DoubleSource m_angleData; std::string m_nameValue; }; -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/libnt/native/include/wpi/glass/networktables/NTMecanumDrive.hpp b/glass/src/libnt/native/include/wpi/glass/networktables/NTMecanumDrive.hpp index 883c30e9c8..b5d5774e1b 100644 --- a/glass/src/libnt/native/include/wpi/glass/networktables/NTMecanumDrive.hpp +++ b/glass/src/libnt/native/include/wpi/glass/networktables/NTMecanumDrive.hpp @@ -15,13 +15,13 @@ #include "wpi/nt/NetworkTableInstance.hpp" #include "wpi/nt/StringTopic.hpp" -namespace glass { +namespace wpi::glass { class NTMecanumDriveModel : public DriveModel { public: static constexpr const char* kType = "MecanumDrive"; explicit NTMecanumDriveModel(std::string_view path); - NTMecanumDriveModel(nt::NetworkTableInstance inst, std::string_view path); + NTMecanumDriveModel(wpi::nt::NetworkTableInstance inst, std::string_view path); const char* GetName() const override { return m_nameValue.c_str(); } const std::vector& GetWheels() const override { @@ -36,13 +36,13 @@ class NTMecanumDriveModel : public DriveModel { bool IsReadOnly() override { return !m_controllableValue; } private: - nt::NetworkTableInstance m_inst; - nt::StringSubscriber m_name; - nt::BooleanSubscriber m_controllable; - nt::DoubleEntry m_flPercent; - nt::DoubleEntry m_frPercent; - nt::DoubleEntry m_rlPercent; - nt::DoubleEntry m_rrPercent; + wpi::nt::NetworkTableInstance m_inst; + wpi::nt::StringSubscriber m_name; + wpi::nt::BooleanSubscriber m_controllable; + wpi::nt::DoubleEntry m_flPercent; + wpi::nt::DoubleEntry m_frPercent; + wpi::nt::DoubleEntry m_rlPercent; + wpi::nt::DoubleEntry m_rrPercent; std::string m_nameValue; bool m_controllableValue = false; @@ -55,4 +55,4 @@ class NTMecanumDriveModel : public DriveModel { ImVec2 m_speedVector; double m_rotation; }; -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/libnt/native/include/wpi/glass/networktables/NTMechanism2D.hpp b/glass/src/libnt/native/include/wpi/glass/networktables/NTMechanism2D.hpp index 2ab5bf5241..ce2cf958d6 100644 --- a/glass/src/libnt/native/include/wpi/glass/networktables/NTMechanism2D.hpp +++ b/glass/src/libnt/native/include/wpi/glass/networktables/NTMechanism2D.hpp @@ -16,7 +16,7 @@ #include "wpi/nt/NetworkTableInstance.hpp" #include "wpi/nt/NetworkTableListener.hpp" -namespace glass { +namespace wpi::glass { class NTMechanism2DModel : public Mechanism2DModel { public: @@ -24,7 +24,7 @@ class NTMechanism2DModel : public Mechanism2DModel { // path is to the table containing ".type", excluding the trailing / explicit NTMechanism2DModel(std::string_view path); - NTMechanism2DModel(nt::NetworkTableInstance inst, std::string_view path); + NTMechanism2DModel(wpi::nt::NetworkTableInstance inst, std::string_view path); ~NTMechanism2DModel() override; const char* GetPath() const { return m_path.c_str(); } @@ -34,41 +34,41 @@ class NTMechanism2DModel : public Mechanism2DModel { bool Exists() override; bool IsReadOnly() override; - frc::Translation2d GetDimensions() const override { + wpi::math::Translation2d GetDimensions() const override { return m_dimensionsValue; } ImU32 GetBackgroundColor() const override { return m_bgColorValue; } void ForEachRoot( - wpi::function_ref func) override; + wpi::util::function_ref func) override; private: - nt::NetworkTableInstance m_inst; + wpi::nt::NetworkTableInstance m_inst; std::string m_path; - nt::MultiSubscriber m_tableSub; - nt::Topic m_nameTopic; - nt::Topic m_dimensionsTopic; - nt::Topic m_bgColorTopic; - nt::NetworkTableListenerPoller m_poller; + wpi::nt::MultiSubscriber m_tableSub; + wpi::nt::Topic m_nameTopic; + wpi::nt::Topic m_dimensionsTopic; + wpi::nt::Topic m_bgColorTopic; + wpi::nt::NetworkTableListenerPoller m_poller; std::string m_nameValue; - frc::Translation2d m_dimensionsValue; + wpi::math::Translation2d m_dimensionsValue; ImU32 m_bgColorValue = 0; class NTMechanismObjectModel; class NTMechanismGroupImpl final { public: - NTMechanismGroupImpl(nt::NetworkTableInstance inst, std::string_view path, + NTMechanismGroupImpl(wpi::nt::NetworkTableInstance inst, std::string_view path, std::string_view name) : m_inst{inst}, m_path{path}, m_name{name} {} const char* GetName() const { return m_name.c_str(); } void ForEachObject( - wpi::function_ref func); + wpi::util::function_ref func); - void NTUpdate(const nt::Event& event, std::string_view name); + void NTUpdate(const wpi::nt::Event& event, std::string_view name); protected: - nt::NetworkTableInstance m_inst; + wpi::nt::NetworkTableInstance m_inst; std::string m_path; std::string m_name; std::vector> m_objects; @@ -76,7 +76,7 @@ class NTMechanism2DModel : public Mechanism2DModel { class NTMechanismObjectModel final : public MechanismObjectModel { public: - NTMechanismObjectModel(nt::NetworkTableInstance inst, std::string_view path, + NTMechanismObjectModel(wpi::nt::NetworkTableInstance inst, std::string_view path, std::string_view name) : m_group{inst, path, name}, m_typeTopic{inst.GetTopic(fmt::format("{}/.type", path))}, @@ -87,37 +87,37 @@ class NTMechanism2DModel : public Mechanism2DModel { const char* GetName() const final { return m_group.GetName(); } void ForEachObject( - wpi::function_ref func) final { + wpi::util::function_ref func) final { m_group.ForEachObject(func); } const char* GetType() const final { return m_typeValue.c_str(); } ImU32 GetColor() const final { return m_colorValue; } double GetWeight() const final { return m_weightValue; } - frc::Rotation2d GetAngle() const final { return m_angleValue; } - units::meter_t GetLength() const final { return m_lengthValue; } + wpi::math::Rotation2d GetAngle() const final { return m_angleValue; } + wpi::units::meter_t GetLength() const final { return m_lengthValue; } - bool NTUpdate(const nt::Event& event, std::string_view name); + bool NTUpdate(const wpi::nt::Event& event, std::string_view name); private: NTMechanismGroupImpl m_group; - nt::Topic m_typeTopic; - nt::Topic m_colorTopic; - nt::Topic m_weightTopic; - nt::Topic m_angleTopic; - nt::Topic m_lengthTopic; + wpi::nt::Topic m_typeTopic; + wpi::nt::Topic m_colorTopic; + wpi::nt::Topic m_weightTopic; + wpi::nt::Topic m_angleTopic; + wpi::nt::Topic m_lengthTopic; std::string m_typeValue; ImU32 m_colorValue = IM_COL32_WHITE; double m_weightValue = 1.0; - frc::Rotation2d m_angleValue; - units::meter_t m_lengthValue = 0.0_m; + wpi::math::Rotation2d m_angleValue; + wpi::units::meter_t m_lengthValue = 0.0_m; }; class RootModel final : public MechanismRootModel { public: - RootModel(nt::NetworkTableInstance inst, std::string_view path, + RootModel(wpi::nt::NetworkTableInstance inst, std::string_view path, std::string_view name) : m_group{inst, path, name}, m_xTopic{inst.GetTopic(fmt::format("{}/x", path))}, @@ -125,22 +125,22 @@ class NTMechanism2DModel : public Mechanism2DModel { const char* GetName() const final { return m_group.GetName(); } void ForEachObject( - wpi::function_ref func) final { + wpi::util::function_ref func) final { m_group.ForEachObject(func); } - bool NTUpdate(const nt::Event& event, std::string_view childName); + bool NTUpdate(const wpi::nt::Event& event, std::string_view childName); - frc::Translation2d GetPosition() const override { return m_pos; }; + wpi::math::Translation2d GetPosition() const override { return m_pos; }; private: NTMechanismGroupImpl m_group; - nt::Topic m_xTopic; - nt::Topic m_yTopic; - frc::Translation2d m_pos; + wpi::nt::Topic m_xTopic; + wpi::nt::Topic m_yTopic; + wpi::math::Translation2d m_pos; }; std::vector> m_roots; }; -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/libnt/native/include/wpi/glass/networktables/NTMotorController.hpp b/glass/src/libnt/native/include/wpi/glass/networktables/NTMotorController.hpp index 30045fbe5e..e7d7460759 100644 --- a/glass/src/libnt/native/include/wpi/glass/networktables/NTMotorController.hpp +++ b/glass/src/libnt/native/include/wpi/glass/networktables/NTMotorController.hpp @@ -14,13 +14,13 @@ #include "wpi/nt/NetworkTableInstance.hpp" #include "wpi/nt/StringTopic.hpp" -namespace glass { +namespace wpi::glass { class NTMotorControllerModel : public MotorControllerModel { public: static constexpr const char* kType = "Motor Controller"; explicit NTMotorControllerModel(std::string_view path); - NTMotorControllerModel(nt::NetworkTableInstance inst, std::string_view path); + NTMotorControllerModel(wpi::nt::NetworkTableInstance inst, std::string_view path); const char* GetName() const override { return m_nameValue.c_str(); } const char* GetSimDevice() const override { return nullptr; } @@ -33,13 +33,13 @@ class NTMotorControllerModel : public MotorControllerModel { bool IsReadOnly() override { return !m_controllableValue; } private: - nt::NetworkTableInstance m_inst; - nt::DoubleEntry m_value; - nt::StringSubscriber m_name; - nt::BooleanSubscriber m_controllable; + wpi::nt::NetworkTableInstance m_inst; + wpi::nt::DoubleEntry m_value; + wpi::nt::StringSubscriber m_name; + wpi::nt::BooleanSubscriber m_controllable; DoubleSource m_valueData; std::string m_nameValue; bool m_controllableValue = false; }; -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/libnt/native/include/wpi/glass/networktables/NTPIDController.hpp b/glass/src/libnt/native/include/wpi/glass/networktables/NTPIDController.hpp index 9bcd5ce26e..c991751e30 100644 --- a/glass/src/libnt/native/include/wpi/glass/networktables/NTPIDController.hpp +++ b/glass/src/libnt/native/include/wpi/glass/networktables/NTPIDController.hpp @@ -14,13 +14,13 @@ #include "wpi/nt/NetworkTableInstance.hpp" #include "wpi/nt/StringTopic.hpp" -namespace glass { +namespace wpi::glass { class NTPIDControllerModel : public PIDControllerModel { public: static constexpr const char* kType = "PIDController"; explicit NTPIDControllerModel(std::string_view path); - NTPIDControllerModel(nt::NetworkTableInstance inst, std::string_view path); + NTPIDControllerModel(wpi::nt::NetworkTableInstance inst, std::string_view path); const char* GetName() const override { return m_nameValue.c_str(); } @@ -41,14 +41,14 @@ class NTPIDControllerModel : public PIDControllerModel { bool IsReadOnly() override { return !m_controllableValue; } private: - nt::NetworkTableInstance m_inst; - nt::StringSubscriber m_name; - nt::BooleanSubscriber m_controllable; - nt::DoubleEntry m_p; - nt::DoubleEntry m_i; - nt::DoubleEntry m_d; - nt::DoubleEntry m_setpoint; - nt::DoubleEntry m_iZone; + wpi::nt::NetworkTableInstance m_inst; + wpi::nt::StringSubscriber m_name; + wpi::nt::BooleanSubscriber m_controllable; + wpi::nt::DoubleEntry m_p; + wpi::nt::DoubleEntry m_i; + wpi::nt::DoubleEntry m_d; + wpi::nt::DoubleEntry m_setpoint; + wpi::nt::DoubleEntry m_iZone; DoubleSource m_pData; DoubleSource m_iData; @@ -59,4 +59,4 @@ class NTPIDControllerModel : public PIDControllerModel { std::string m_nameValue; bool m_controllableValue = false; }; -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/libnt/native/include/wpi/glass/networktables/NTProfiledPIDController.hpp b/glass/src/libnt/native/include/wpi/glass/networktables/NTProfiledPIDController.hpp index 4e32af616e..4b847c0767 100644 --- a/glass/src/libnt/native/include/wpi/glass/networktables/NTProfiledPIDController.hpp +++ b/glass/src/libnt/native/include/wpi/glass/networktables/NTProfiledPIDController.hpp @@ -14,13 +14,13 @@ #include "wpi/nt/NetworkTableInstance.hpp" #include "wpi/nt/StringTopic.hpp" -namespace glass { +namespace wpi::glass { class NTProfiledPIDControllerModel : public ProfiledPIDControllerModel { public: static constexpr const char* kType = "ProfiledPIDController"; explicit NTProfiledPIDControllerModel(std::string_view path); - NTProfiledPIDControllerModel(nt::NetworkTableInstance inst, + NTProfiledPIDControllerModel(wpi::nt::NetworkTableInstance inst, std::string_view path); const char* GetName() const override { return m_nameValue.c_str(); } @@ -48,16 +48,16 @@ class NTProfiledPIDControllerModel : public ProfiledPIDControllerModel { bool IsReadOnly() override { return !m_controllableValue; } private: - nt::NetworkTableInstance m_inst; - nt::StringSubscriber m_name; - nt::BooleanSubscriber m_controllable; - nt::DoubleEntry m_p; - nt::DoubleEntry m_i; - nt::DoubleEntry m_d; - nt::DoubleEntry m_iZone; - nt::DoubleEntry m_maxVelocity; - nt::DoubleEntry m_maxAcceleration; - nt::DoubleEntry m_goal; + wpi::nt::NetworkTableInstance m_inst; + wpi::nt::StringSubscriber m_name; + wpi::nt::BooleanSubscriber m_controllable; + wpi::nt::DoubleEntry m_p; + wpi::nt::DoubleEntry m_i; + wpi::nt::DoubleEntry m_d; + wpi::nt::DoubleEntry m_iZone; + wpi::nt::DoubleEntry m_maxVelocity; + wpi::nt::DoubleEntry m_maxAcceleration; + wpi::nt::DoubleEntry m_goal; DoubleSource m_pData; DoubleSource m_iData; @@ -70,4 +70,4 @@ class NTProfiledPIDControllerModel : public ProfiledPIDControllerModel { std::string m_nameValue; bool m_controllableValue = false; }; -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/libnt/native/include/wpi/glass/networktables/NTStringChooser.hpp b/glass/src/libnt/native/include/wpi/glass/networktables/NTStringChooser.hpp index 1178415f6d..92702c8a2c 100644 --- a/glass/src/libnt/native/include/wpi/glass/networktables/NTStringChooser.hpp +++ b/glass/src/libnt/native/include/wpi/glass/networktables/NTStringChooser.hpp @@ -12,7 +12,7 @@ #include "wpi/nt/StringArrayTopic.hpp" #include "wpi/nt/StringTopic.hpp" -namespace glass { +namespace wpi::glass { class NTStringChooserModel : public StringChooserModel { public: @@ -20,7 +20,7 @@ class NTStringChooserModel : public StringChooserModel { // path is to the table containing ".type", excluding the trailing / explicit NTStringChooserModel(std::string_view path); - NTStringChooserModel(nt::NetworkTableInstance inst, std::string_view path); + NTStringChooserModel(wpi::nt::NetworkTableInstance inst, std::string_view path); const std::string& GetDefault() override { return m_defaultValue; } const std::string& GetSelected() override { return m_selectedValue; } @@ -36,12 +36,12 @@ class NTStringChooserModel : public StringChooserModel { bool IsReadOnly() override { return false; } private: - nt::NetworkTableInstance m_inst; - nt::StringSubscriber m_default; - nt::StringSubscriber m_selected; - nt::StringPublisher m_selectedPub; - nt::StringSubscriber m_active; - nt::StringArraySubscriber m_options; + wpi::nt::NetworkTableInstance m_inst; + wpi::nt::StringSubscriber m_default; + wpi::nt::StringSubscriber m_selected; + wpi::nt::StringPublisher m_selectedPub; + wpi::nt::StringSubscriber m_active; + wpi::nt::StringArraySubscriber m_options; std::string m_defaultValue; std::string m_selectedValue; @@ -49,4 +49,4 @@ class NTStringChooserModel : public StringChooserModel { std::vector m_optionsValue; }; -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/libnt/native/include/wpi/glass/networktables/NTSubsystem.hpp b/glass/src/libnt/native/include/wpi/glass/networktables/NTSubsystem.hpp index 904dfb9c1d..3f8f094923 100644 --- a/glass/src/libnt/native/include/wpi/glass/networktables/NTSubsystem.hpp +++ b/glass/src/libnt/native/include/wpi/glass/networktables/NTSubsystem.hpp @@ -12,13 +12,13 @@ #include "wpi/nt/NetworkTableInstance.hpp" #include "wpi/nt/StringTopic.hpp" -namespace glass { +namespace wpi::glass { class NTSubsystemModel : public SubsystemModel { public: static constexpr const char* kType = "Subsystem"; explicit NTSubsystemModel(std::string_view path); - NTSubsystemModel(nt::NetworkTableInstance inst, std::string_view path); + NTSubsystemModel(wpi::nt::NetworkTableInstance inst, std::string_view path); const char* GetName() const override { return m_nameValue.c_str(); } const char* GetDefaultCommand() const override { @@ -33,13 +33,13 @@ class NTSubsystemModel : public SubsystemModel { bool IsReadOnly() override { return true; } private: - nt::NetworkTableInstance m_inst; - nt::StringSubscriber m_name; - nt::StringSubscriber m_defaultCommand; - nt::StringSubscriber m_currentCommand; + wpi::nt::NetworkTableInstance m_inst; + wpi::nt::StringSubscriber m_name; + wpi::nt::StringSubscriber m_defaultCommand; + wpi::nt::StringSubscriber m_currentCommand; std::string m_nameValue; std::string m_defaultCommandValue; std::string m_currentCommandValue; }; -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/libnt/native/include/wpi/glass/networktables/NetworkTables.hpp b/glass/src/libnt/native/include/wpi/glass/networktables/NetworkTables.hpp index d63c32d394..29d9a3926d 100644 --- a/glass/src/libnt/native/include/wpi/glass/networktables/NetworkTables.hpp +++ b/glass/src/libnt/native/include/wpi/glass/networktables/NetworkTables.hpp @@ -25,7 +25,7 @@ #include "wpi/util/json.hpp" #include "wpi/util/struct/DynamicStruct.hpp" -namespace glass { +namespace wpi::glass { class DataSource; @@ -43,7 +43,7 @@ class NetworkTablesModel : public Model { int64_t time); /** The latest value. */ - nt::Value value; + wpi::nt::Value value; /** String representation of the value (for arrays / complex values). */ std::string valueStr; @@ -91,18 +91,18 @@ class NetworkTablesModel : public Model { ValueSource::UpdateFromValue(model, info.name, info.type_str); } - void UpdateTopic(nt::Event&& event) { - if (std::holds_alternative(event.data)) { - UpdateInfo(std::get(std::move(event.data))); + void UpdateTopic(wpi::nt::Event&& event) { + if (std::holds_alternative(event.data)) { + UpdateInfo(std::get(std::move(event.data))); } } - void UpdateInfo(nt::TopicInfo&& info_); + void UpdateInfo(wpi::nt::TopicInfo&& info_); /** Topic information. */ - nt::TopicInfo info; + wpi::nt::TopicInfo info; /** JSON representation of the topic properties. */ - wpi::json properties; + wpi::util::json properties; /** Specific common property flags. */ bool persistent{false}; @@ -111,8 +111,8 @@ class NetworkTablesModel : public Model { /** Publisher (created when the value changes). */ NT_Publisher publisher{0}; - std::vector publishers; - std::vector subscribers; + std::vector publishers; + std::vector subscribers; }; struct TreeNode { @@ -134,17 +134,17 @@ class NetworkTablesModel : public Model { std::vector children; }; - struct Client : public nt::meta::Client { + struct Client : public wpi::nt::meta::Client { Client() = default; - /*implicit*/ Client(nt::meta::Client&& oth) // NOLINT - : nt::meta::Client{std::move(oth)} {} + /*implicit*/ Client(wpi::nt::meta::Client&& oth) // NOLINT + : wpi::nt::meta::Client{std::move(oth)} {} - struct Subscriber : public nt::meta::ClientSubscriber { - /*implicit*/ Subscriber(nt::meta::ClientSubscriber&& oth); // NOLINT + struct Subscriber : public wpi::nt::meta::ClientSubscriber { + /*implicit*/ Subscriber(wpi::nt::meta::ClientSubscriber&& oth); // NOLINT std::string topicsStr; }; - std::vector publishers; + std::vector publishers; std::vector subscribers; void UpdatePublishers(std::span data); @@ -152,12 +152,12 @@ class NetworkTablesModel : public Model { }; NetworkTablesModel(); - explicit NetworkTablesModel(nt::NetworkTableInstance inst); + explicit NetworkTablesModel(wpi::nt::NetworkTableInstance inst); void Update() override; bool Exists() override; - nt::NetworkTableInstance GetInstance() { return m_inst; } + wpi::nt::NetworkTableInstance GetInstance() { return m_inst; } const std::vector& GetEntries() const { return m_sortedEntries; } const std::vector& GetTreeRoot() const { return m_root; } const std::vector& GetPersistentTreeRoot() const { @@ -176,7 +176,7 @@ class NetworkTablesModel : public Model { Entry* GetEntry(std::string_view name); Entry* AddEntry(NT_Topic topic); - wpi::StructDescriptorDatabase& GetStructDatabase() { return m_structDb; } + wpi::util::StructDescriptorDatabase& GetStructDatabase() { return m_structDb; } upb_DefPool* GetProtobufDatabase() { return m_protoPool; } upb_Arena* GetProtobufArena() { return m_arena; } @@ -185,9 +185,9 @@ class NetworkTablesModel : public Model { void RebuildTreeImpl(std::vector* tree, int category); void UpdateClients(std::span data); - nt::NetworkTableInstance m_inst; - nt::NetworkTableListenerPoller m_poller; - wpi::DenseMap> m_entries; + wpi::nt::NetworkTableInstance m_inst; + wpi::nt::NetworkTableListenerPoller m_poller; + wpi::util::DenseMap> m_entries; // sorted by name std::vector m_sortedEntries; @@ -200,7 +200,7 @@ class NetworkTablesModel : public Model { std::map> m_clients; Client m_server; - wpi::StructDescriptorDatabase m_structDb; + wpi::util::StructDescriptorDatabase m_structDb; upb_DefPool* m_protoPool = upb_DefPool_New(); upb_Arena* m_arena = upb_Arena_New(); }; @@ -273,4 +273,4 @@ class NetworkTablesView : public View { NetworkTablesFlagsSettings m_flags; }; -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/libnt/native/include/wpi/glass/networktables/NetworkTablesProvider.hpp b/glass/src/libnt/native/include/wpi/glass/networktables/NetworkTablesProvider.hpp index f88e43f6b1..26933c3b43 100644 --- a/glass/src/libnt/native/include/wpi/glass/networktables/NetworkTablesProvider.hpp +++ b/glass/src/libnt/native/include/wpi/glass/networktables/NetworkTablesProvider.hpp @@ -18,16 +18,16 @@ #include "wpi/util/DenseMap.hpp" #include "wpi/util/StringMap.hpp" -namespace glass { +namespace wpi::glass { class Window; namespace detail { struct NTProviderFunctions { using Exists = - std::function; + std::function; using CreateModel = std::function( - nt::NetworkTableInstance inst, const char* path)>; + wpi::nt::NetworkTableInstance inst, const char* path)>; using ViewExists = std::function; using CreateView = std::function(Window*, Model*, const char* path)>; @@ -43,14 +43,14 @@ class NetworkTablesProvider : private Provider { using Provider::CreateViewFunc; explicit NetworkTablesProvider(Storage& storage); - NetworkTablesProvider(Storage& storage, nt::NetworkTableInstance inst); + NetworkTablesProvider(Storage& storage, wpi::nt::NetworkTableInstance inst); /** * Get the NetworkTables instance being used for this provider. * * @return NetworkTables instance */ - nt::NetworkTableInstance GetInstance() const { return m_inst; } + wpi::nt::NetworkTableInstance GetInstance() const { return m_inst; } /** * Perform global initialization. This should be called prior to @@ -76,8 +76,8 @@ class NetworkTablesProvider : private Provider { private: void Update() override; - nt::NetworkTableInstance m_inst; - nt::NetworkTableListenerPoller m_poller; + wpi::nt::NetworkTableInstance m_inst; + wpi::nt::NetworkTableListenerPoller m_poller; NT_Listener m_listener{0}; // cached mapping from table name to type string @@ -89,27 +89,27 @@ class NetworkTablesProvider : private Provider { }; // mapping from .type string to model/view creators - wpi::StringMap m_typeMap; + wpi::util::StringMap m_typeMap; struct SubListener { - nt::StringSubscriber subscriber; + wpi::nt::StringSubscriber subscriber; NT_Listener listener; }; // mapping from .type topic to subscriber/listener - wpi::DenseMap m_topicMap; + wpi::util::DenseMap m_topicMap; struct Entry : public ModelEntry { - Entry(nt::Topic typeTopic, std::string_view name, const Builder& builder) + Entry(wpi::nt::Topic typeTopic, std::string_view name, const Builder& builder) : ModelEntry{name, [](auto, const char*) { return true; }, builder.createModel}, typeTopic{typeTopic} {} - nt::Topic typeTopic; + wpi::nt::Topic typeTopic; }; void Show(ViewEntry* entry, Window* window) override; - ViewEntry* GetOrCreateView(const Builder& builder, nt::Topic typeTopic, + ViewEntry* GetOrCreateView(const Builder& builder, wpi::nt::Topic typeTopic, std::string_view name); }; @@ -120,4 +120,4 @@ class NetworkTablesProvider : private Provider { */ void AddStandardNetworkTablesViews(NetworkTablesProvider& provider); -} // namespace glass +} // namespace wpi::glass diff --git a/glass/src/libnt/native/include/wpi/glass/networktables/NetworkTablesSettings.hpp b/glass/src/libnt/native/include/wpi/glass/networktables/NetworkTablesSettings.hpp index 465a4163ce..8f434d6326 100644 --- a/glass/src/libnt/native/include/wpi/glass/networktables/NetworkTablesSettings.hpp +++ b/glass/src/libnt/native/include/wpi/glass/networktables/NetworkTablesSettings.hpp @@ -10,19 +10,19 @@ #include "wpi/nt/ntcore_cpp.hpp" #include "wpi/util/SafeThread.hpp" -namespace wpi { +namespace wpi::util { template class SmallVectorImpl; } // namespace wpi -namespace glass { +namespace wpi::glass { class Storage; class NetworkTablesSettings { public: explicit NetworkTablesSettings(std::string_view clientName, Storage& storage, - NT_Inst inst = nt::GetDefaultInstance()); + NT_Inst inst = wpi::nt::GetDefaultInstance()); /** * Enables or disables the server option. Default is enabled. @@ -43,7 +43,7 @@ class NetworkTablesSettings { int& m_port; bool& m_dsClient; - class Thread : public wpi::SafeThread { + class Thread : public wpi::util::SafeThread { public: explicit Thread(NT_Inst inst) : m_inst{inst} {} @@ -59,7 +59,7 @@ class NetworkTablesSettings { int m_port; bool m_dsClient; }; - wpi::SafeThreadOwner m_thread; + wpi::util::SafeThreadOwner m_thread; }; -} // namespace glass +} // namespace wpi::glass diff --git a/hal/src/dev/native/cpp/main.cpp b/hal/src/dev/native/cpp/main.cpp index 68974e3429..348a3ef4db 100644 --- a/hal/src/dev/native/cpp/main.cpp +++ b/hal/src/dev/native/cpp/main.cpp @@ -6,6 +6,6 @@ #include "wpi/util/print.hpp" int main() { - wpi::print("Hello World\n"); - wpi::print("{}\n", static_cast(HAL_GetRuntimeType())); + wpi::util::print("Hello World\n"); + wpi::util::print("{}\n", static_cast(HAL_GetRuntimeType())); } diff --git a/hal/src/main/native/cpp/ErrorHandling.cpp b/hal/src/main/native/cpp/ErrorHandling.cpp index ed88a96273..6a0bfd03b9 100644 --- a/hal/src/main/native/cpp/ErrorHandling.cpp +++ b/hal/src/main/native/cpp/ErrorHandling.cpp @@ -11,7 +11,7 @@ namespace { struct LastErrorStorage { int32_t status; - wpi::SmallString<512> message; + wpi::util::SmallString<512> message; }; } // namespace @@ -20,7 +20,7 @@ static LastErrorStorage& GetThreadLastError() { return lastError; } -namespace hal { +namespace wpi::hal { void SetLastError(int32_t* status, std::string_view value) { LastErrorStorage& lastError = GetThreadLastError(); lastError.message = value; @@ -40,13 +40,13 @@ void SetLastErrorIndexOutOfRange(int32_t* status, std::string_view message, void SetLastErrorPreviouslyAllocated(int32_t* status, std::string_view message, int32_t channel, std::string_view previousAllocation) { - hal::SetLastError(status, + wpi::hal::SetLastError(status, fmt::format("{} {} previously allocated.\n" "Location of the previous allocation:\n{}\n" "Location of the current allocation:", message, channel, previousAllocation)); } -} // namespace hal +} // namespace wpi::hal extern "C" { const char* HAL_GetLastError(int32_t* status) { diff --git a/hal/src/main/native/cpp/Main.cpp b/hal/src/main/native/cpp/Main.cpp index 30b3e2b5da..c54e000646 100644 --- a/hal/src/main/native/cpp/Main.cpp +++ b/hal/src/main/native/cpp/Main.cpp @@ -16,8 +16,8 @@ static void (*gMainFunc)(void*) = DefaultMain; static void (*gExitFunc)(void*) = DefaultExit; static bool gExited = false; struct MainObj { - wpi::mutex gExitMutex; - wpi::condition_variable gExitCv; + wpi::util::mutex gExitMutex; + wpi::util::condition_variable gExitCv; }; static MainObj* mainObj; @@ -33,12 +33,12 @@ static void DefaultExit(void*) { mainObj->gExitCv.notify_all(); } -namespace hal::init { +namespace wpi::hal::init { void InitializeMain() { static MainObj mO; mainObj = &mO; } -} // namespace hal::init +} // namespace wpi::hal::init extern "C" { diff --git a/hal/src/main/native/cpp/cpp/fpga_clock.cpp b/hal/src/main/native/cpp/cpp/fpga_clock.cpp index 5dccf4b12e..be2819e4ad 100644 --- a/hal/src/main/native/cpp/cpp/fpga_clock.cpp +++ b/hal/src/main/native/cpp/cpp/fpga_clock.cpp @@ -10,7 +10,7 @@ #include "wpi/hal/HALBase.h" #include "wpi/util/print.hpp" -namespace hal { +namespace wpi::hal { const fpga_clock::time_point fpga_clock::min_time = fpga_clock::time_point(fpga_clock::duration( std::numeric_limits::min())); @@ -19,7 +19,7 @@ fpga_clock::time_point fpga_clock::now() noexcept { int32_t status = 0; uint64_t currentTime = HAL_GetFPGATime(&status); if (status != 0) { - wpi::print( + wpi::util::print( stderr, "Call to HAL_GetFPGATime failed in fpga_clock::now() with status {}. " "Initialization might have failed. Time will not be correct\n", @@ -29,4 +29,4 @@ fpga_clock::time_point fpga_clock::now() noexcept { } return time_point(std::chrono::microseconds(currentTime)); } -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/main/native/cpp/handles/HandlesInternal.cpp b/hal/src/main/native/cpp/handles/HandlesInternal.cpp index 204bb24580..a88f2bfcac 100644 --- a/hal/src/main/native/cpp/handles/HandlesInternal.cpp +++ b/hal/src/main/native/cpp/handles/HandlesInternal.cpp @@ -9,11 +9,11 @@ #include "wpi/util/SmallVector.hpp" #include "wpi/util/mutex.hpp" -namespace hal { -static wpi::SmallVector* globalHandles = nullptr; -static wpi::mutex globalHandleMutex; +namespace wpi::hal { +static wpi::util::SmallVector* globalHandles = nullptr; +static wpi::util::mutex globalHandleMutex; HandleBase::HandleBase() { - static wpi::SmallVector gH; + static wpi::util::SmallVector gH; std::scoped_lock lock(globalHandleMutex); if (!globalHandles) { globalHandles = &gH; @@ -67,4 +67,4 @@ HAL_Handle createHandle(int16_t index, HAL_HandleEnum handleType, handle += index; return handle; } -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/main/native/cpp/jni/AddressableLEDJNI.cpp b/hal/src/main/native/cpp/jni/AddressableLEDJNI.cpp index 5d36ab71c0..fae53ad3dc 100644 --- a/hal/src/main/native/cpp/jni/AddressableLEDJNI.cpp +++ b/hal/src/main/native/cpp/jni/AddressableLEDJNI.cpp @@ -9,8 +9,8 @@ #include "wpi/hal/AddressableLED.h" #include "wpi/util/jni_util.hpp" -using namespace hal; -using namespace wpi::java; +using namespace wpi::hal; +using namespace wpi::util::java; static_assert(sizeof(jbyte) * 3 == sizeof(HAL_AddressableLEDData)); @@ -38,7 +38,7 @@ Java_org_wpilib_hardware_hal_AddressableLEDJNI_initialize (JNIEnv* env, jclass, jint channel) { int32_t status = 0; - auto stack = wpi::java::GetJavaStackTrace(env, "edu.wpi.first"); + auto stack = wpi::util::java::GetJavaStackTrace(env, "edu.wpi.first"); auto ret = HAL_InitializeAddressableLED(channel, stack.c_str(), &status); CheckStatusForceThrow(env, status); return ret; diff --git a/hal/src/main/native/cpp/jni/AnalogJNI.cpp b/hal/src/main/native/cpp/jni/AnalogJNI.cpp index 78ce48cb98..41d93aa8fb 100644 --- a/hal/src/main/native/cpp/jni/AnalogJNI.cpp +++ b/hal/src/main/native/cpp/jni/AnalogJNI.cpp @@ -13,7 +13,7 @@ #include "wpi/hal/handles/HandlesInternal.h" #include "wpi/util/jni_util.hpp" -using namespace hal; +using namespace wpi::hal; extern "C" { @@ -27,7 +27,7 @@ Java_org_wpilib_hardware_hal_AnalogJNI_initializeAnalogInputPort (JNIEnv* env, jclass, jint channel) { int32_t status = 0; - auto stack = wpi::java::GetJavaStackTrace(env, "edu.wpi.first"); + auto stack = wpi::util::java::GetJavaStackTrace(env, "edu.wpi.first"); auto analog = HAL_InitializeAnalogInputPort(channel, stack.c_str(), &status); CheckStatusForceThrow(env, status); return (jint)analog; diff --git a/hal/src/main/native/cpp/jni/CANAPIJNI.cpp b/hal/src/main/native/cpp/jni/CANAPIJNI.cpp index b5d4c4e522..d9a3e604eb 100644 --- a/hal/src/main/native/cpp/jni/CANAPIJNI.cpp +++ b/hal/src/main/native/cpp/jni/CANAPIJNI.cpp @@ -13,8 +13,8 @@ #include "wpi/hal/Errors.h" #include "wpi/util/jni_util.hpp" -using namespace hal; -using namespace wpi::java; +using namespace wpi::hal; +using namespace wpi::util::java; extern "C" { diff --git a/hal/src/main/native/cpp/jni/CANJNI.cpp b/hal/src/main/native/cpp/jni/CANJNI.cpp index 4d1e67afc1..c4d8518802 100644 --- a/hal/src/main/native/cpp/jni/CANJNI.cpp +++ b/hal/src/main/native/cpp/jni/CANJNI.cpp @@ -12,8 +12,8 @@ #include "wpi/hal/Errors.h" #include "wpi/util/jni_util.hpp" -using namespace hal; -using namespace wpi::java; +using namespace wpi::hal; +using namespace wpi::util::java; extern "C" { @@ -180,7 +180,7 @@ Java_org_wpilib_hardware_hal_can_CANJNI_readCANStreamSession uint32_t handle = static_cast(sessionHandle); uint32_t messagesRead = 0; - wpi::SmallVector messageBuffer; + wpi::util::SmallVector messageBuffer; messageBuffer.resize_for_overwrite(messagesToRead); int32_t status = 0; diff --git a/hal/src/main/native/cpp/jni/CTREPCMJNI.cpp b/hal/src/main/native/cpp/jni/CTREPCMJNI.cpp index 1e4940b6a4..bd15963e36 100644 --- a/hal/src/main/native/cpp/jni/CTREPCMJNI.cpp +++ b/hal/src/main/native/cpp/jni/CTREPCMJNI.cpp @@ -11,7 +11,7 @@ #include "wpi/hal/handles/HandlesInternal.h" #include "wpi/util/jni_util.hpp" -using namespace hal; +using namespace wpi::hal; extern "C" { @@ -25,7 +25,7 @@ Java_org_wpilib_hardware_hal_CTREPCMJNI_initialize (JNIEnv* env, jclass, jint busId, jint module) { int32_t status = 0; - auto stack = wpi::java::GetJavaStackTrace(env, "edu.wpi.first"); + auto stack = wpi::util::java::GetJavaStackTrace(env, "edu.wpi.first"); auto handle = HAL_InitializeCTREPCM(busId, module, stack.c_str(), &status); CheckStatusForceThrow(env, status); return handle; diff --git a/hal/src/main/native/cpp/jni/ConstantsJNI.cpp b/hal/src/main/native/cpp/jni/ConstantsJNI.cpp index 38e49dbbdd..d204f02a27 100644 --- a/hal/src/main/native/cpp/jni/ConstantsJNI.cpp +++ b/hal/src/main/native/cpp/jni/ConstantsJNI.cpp @@ -10,7 +10,7 @@ #include "org_wpilib_hardware_hal_ConstantsJNI.h" #include "wpi/hal/Constants.h" -using namespace hal; +using namespace wpi::hal; extern "C" { /* diff --git a/hal/src/main/native/cpp/jni/CounterJNI.cpp b/hal/src/main/native/cpp/jni/CounterJNI.cpp index 4a005e4114..c2c622856c 100644 --- a/hal/src/main/native/cpp/jni/CounterJNI.cpp +++ b/hal/src/main/native/cpp/jni/CounterJNI.cpp @@ -12,7 +12,7 @@ #include "wpi/hal/Errors.h" #include "wpi/util/jni_util.hpp" -using namespace hal; +using namespace wpi::hal; extern "C" { @@ -26,7 +26,7 @@ Java_org_wpilib_hardware_hal_CounterJNI_initializeCounter (JNIEnv* env, jclass, jint channel, jboolean risingEdge) { int32_t status = 0; - auto stack = wpi::java::GetJavaStackTrace(env, "edu.wpi.first"); + auto stack = wpi::util::java::GetJavaStackTrace(env, "edu.wpi.first"); auto counter = HAL_InitializeCounter(channel, risingEdge, stack.c_str(), &status); CheckStatusForceThrow(env, status); diff --git a/hal/src/main/native/cpp/jni/DIOJNI.cpp b/hal/src/main/native/cpp/jni/DIOJNI.cpp index b3f803548a..eba3d05b7e 100644 --- a/hal/src/main/native/cpp/jni/DIOJNI.cpp +++ b/hal/src/main/native/cpp/jni/DIOJNI.cpp @@ -14,7 +14,7 @@ #include "wpi/hal/handles/HandlesInternal.h" #include "wpi/util/jni_util.hpp" -using namespace hal; +using namespace wpi::hal; extern "C" { @@ -28,7 +28,7 @@ Java_org_wpilib_hardware_hal_DIOJNI_initializeDIOPort (JNIEnv* env, jclass, jint channel, jboolean input) { int32_t status = 0; - auto stack = wpi::java::GetJavaStackTrace(env, "edu.wpi.first"); + auto stack = wpi::util::java::GetJavaStackTrace(env, "edu.wpi.first"); auto dio = HAL_InitializeDIOPort(channel, static_cast(input), stack.c_str(), &status); CheckStatusForceThrow(env, status); diff --git a/hal/src/main/native/cpp/jni/DriverStationJNI.cpp b/hal/src/main/native/cpp/jni/DriverStationJNI.cpp index 716dee492c..bd3dac3624 100644 --- a/hal/src/main/native/cpp/jni/DriverStationJNI.cpp +++ b/hal/src/main/native/cpp/jni/DriverStationJNI.cpp @@ -37,8 +37,8 @@ static_assert(org_wpilib_hardware_hal_DriverStationJNI_kMaxJoystickPOVs == static_assert(org_wpilib_hardware_hal_DriverStationJNI_kMaxJoysticks == HAL_kMaxJoysticks); -using namespace hal; -using namespace wpi::java; +using namespace wpi::hal; +using namespace wpi::util::java; extern "C" { @@ -216,7 +216,7 @@ Java_org_wpilib_hardware_hal_DriverStationJNI_getJoystickName { WPI_String joystickName; HAL_GetJoystickName(&joystickName, port); - jstring str = MakeJString(env, wpi::to_string_view(&joystickName)); + jstring str = MakeJString(env, wpi::util::to_string_view(&joystickName)); WPI_FreeString(&joystickName); return str; } diff --git a/hal/src/main/native/cpp/jni/DutyCycleJNI.cpp b/hal/src/main/native/cpp/jni/DutyCycleJNI.cpp index a745244048..f7a1c874dc 100644 --- a/hal/src/main/native/cpp/jni/DutyCycleJNI.cpp +++ b/hal/src/main/native/cpp/jni/DutyCycleJNI.cpp @@ -9,7 +9,7 @@ #include "wpi/hal/DutyCycle.h" #include "wpi/util/jni_util.hpp" -using namespace hal; +using namespace wpi::hal; extern "C" { /* @@ -22,7 +22,7 @@ Java_org_wpilib_hardware_hal_DutyCycleJNI_initialize (JNIEnv* env, jclass, jint channel) { int32_t status = 0; - auto stack = wpi::java::GetJavaStackTrace(env, "edu.wpi.first"); + auto stack = wpi::util::java::GetJavaStackTrace(env, "edu.wpi.first"); auto handle = HAL_InitializeDutyCycle(channel, stack.c_str(), &status); CheckStatus(env, status); return handle; diff --git a/hal/src/main/native/cpp/jni/EncoderJNI.cpp b/hal/src/main/native/cpp/jni/EncoderJNI.cpp index 7c591e4168..313b618734 100644 --- a/hal/src/main/native/cpp/jni/EncoderJNI.cpp +++ b/hal/src/main/native/cpp/jni/EncoderJNI.cpp @@ -11,7 +11,7 @@ #include "wpi/hal/Encoder.h" #include "wpi/hal/Errors.h" -using namespace hal; +using namespace wpi::hal; extern "C" { diff --git a/hal/src/main/native/cpp/jni/HAL.cpp b/hal/src/main/native/cpp/jni/HAL.cpp index 5d0a706cad..cd829796e7 100644 --- a/hal/src/main/native/cpp/jni/HAL.cpp +++ b/hal/src/main/native/cpp/jni/HAL.cpp @@ -21,8 +21,8 @@ #include "wpi/hal/Main.h" #include "wpi/util/jni_util.hpp" -using namespace hal; -using namespace wpi::java; +using namespace wpi::hal; +using namespace wpi::util::java; extern "C" { diff --git a/hal/src/main/native/cpp/jni/HALUtil.cpp b/hal/src/main/native/cpp/jni/HALUtil.cpp index 7f54386c4f..60b3e30b56 100644 --- a/hal/src/main/native/cpp/jni/HALUtil.cpp +++ b/hal/src/main/native/cpp/jni/HALUtil.cpp @@ -21,7 +21,7 @@ #include "wpi/hal/HAL.h" #include "wpi/util/jni_util.hpp" -using namespace wpi::java; +using namespace wpi::util::java; #define kRioStatusOffset -63000 #define kRioStatusSuccess 0 @@ -78,7 +78,7 @@ static const JExceptionInit exceptions[] = { &uncleanStatusExCls}, {"java/lang/NullPointerException", &nullPointerEx}}; -namespace hal { +namespace wpi::hal { void ThrowUncleanStatusException(JNIEnv* env, std::string_view msg, int32_t status) { @@ -312,9 +312,9 @@ jint SimOnLoad(JavaVM* vm, void* reserved); void SimOnUnload(JavaVM* vm, void* reserved); } // namespace sim -} // namespace hal +} // namespace wpi::hal -using namespace hal; +using namespace wpi::hal; extern "C" { @@ -375,7 +375,7 @@ Java_org_wpilib_hardware_hal_HALUtil_getSerialNumber { WPI_String serialNum; HAL_GetSerialNumber(&serialNum); - jstring ret = MakeJString(env, wpi::to_string_view(&serialNum)); + jstring ret = MakeJString(env, wpi::util::to_string_view(&serialNum)); WPI_FreeString(&serialNum); return ret; } @@ -391,7 +391,7 @@ Java_org_wpilib_hardware_hal_HALUtil_getComments { WPI_String comments; HAL_GetComments(&comments); - jstring ret = MakeJString(env, wpi::to_string_view(&comments)); + jstring ret = MakeJString(env, wpi::util::to_string_view(&comments)); WPI_FreeString(&comments); return ret; } diff --git a/hal/src/main/native/cpp/jni/HALUtil.h b/hal/src/main/native/cpp/jni/HALUtil.h index b34a2780cc..88adab4acc 100644 --- a/hal/src/main/native/cpp/jni/HALUtil.h +++ b/hal/src/main/native/cpp/jni/HALUtil.h @@ -13,7 +13,7 @@ struct HAL_MatchInfo; struct HAL_Value; -namespace hal { +namespace wpi::hal { void ReportError(JNIEnv* env, int32_t status, bool doThrow = true); @@ -84,6 +84,6 @@ jobject CreateCANStreamMessage(JNIEnv* env); JavaVM* GetJVM(); -} // namespace hal +} // namespace wpi::hal #endif // HAL_HAL_SRC_MAIN_NATIVE_CPP_JNI_HALUTIL_H_ diff --git a/hal/src/main/native/cpp/jni/I2CJNI.cpp b/hal/src/main/native/cpp/jni/I2CJNI.cpp index 35425d0222..341e5a4270 100644 --- a/hal/src/main/native/cpp/jni/I2CJNI.cpp +++ b/hal/src/main/native/cpp/jni/I2CJNI.cpp @@ -11,8 +11,8 @@ #include "wpi/hal/I2C.h" #include "wpi/util/jni_util.hpp" -using namespace hal; -using namespace wpi::java; +using namespace wpi::hal; +using namespace wpi::util::java; extern "C" { @@ -73,7 +73,7 @@ Java_org_wpilib_hardware_hal_I2CJNI_i2CTransactionB return 0; } - wpi::SmallVector recvBuf; + wpi::util::SmallVector recvBuf; recvBuf.resize(receiveSize); jint returnValue = HAL_TransactionI2C(static_cast(port), address, @@ -156,7 +156,7 @@ Java_org_wpilib_hardware_hal_I2CJNI_i2CReadB return 0; } - wpi::SmallVector recvBuf; + wpi::util::SmallVector recvBuf; recvBuf.resize(receiveSize); jint returnValue = HAL_ReadI2C(static_cast(port), address, recvBuf.data(), receiveSize); diff --git a/hal/src/main/native/cpp/jni/IMUJNI.cpp b/hal/src/main/native/cpp/jni/IMUJNI.cpp index 369cf639e9..a8adfa03a3 100644 --- a/hal/src/main/native/cpp/jni/IMUJNI.cpp +++ b/hal/src/main/native/cpp/jni/IMUJNI.cpp @@ -12,7 +12,7 @@ #include "org_wpilib_hardware_hal_IMUJNI.h" #include "wpi/hal/IMU.h" -using namespace hal; +using namespace wpi::hal; namespace { void assertArraySize(JNIEnv* env, jarray array, int minimumSize, diff --git a/hal/src/main/native/cpp/jni/NotifierJNI.cpp b/hal/src/main/native/cpp/jni/NotifierJNI.cpp index 90702d3a24..32fac3d6f0 100644 --- a/hal/src/main/native/cpp/jni/NotifierJNI.cpp +++ b/hal/src/main/native/cpp/jni/NotifierJNI.cpp @@ -12,7 +12,7 @@ #include "wpi/hal/Notifier.h" #include "wpi/util/jni_util.hpp" -using namespace hal; +using namespace wpi::hal; extern "C" { @@ -59,7 +59,7 @@ Java_org_wpilib_hardware_hal_NotifierJNI_setNotifierName { int32_t status = 0; HAL_SetNotifierName((HAL_NotifierHandle)notifierHandle, - wpi::java::JStringRef{env, name}.c_str(), &status); + wpi::util::java::JStringRef{env, name}.c_str(), &status); CheckStatus(env, status); } diff --git a/hal/src/main/native/cpp/jni/PWMJNI.cpp b/hal/src/main/native/cpp/jni/PWMJNI.cpp index 6297505ce8..e412cfa4e3 100644 --- a/hal/src/main/native/cpp/jni/PWMJNI.cpp +++ b/hal/src/main/native/cpp/jni/PWMJNI.cpp @@ -14,7 +14,7 @@ #include "wpi/hal/handles/HandlesInternal.h" #include "wpi/util/jni_util.hpp" -using namespace hal; +using namespace wpi::hal; extern "C" { @@ -28,7 +28,7 @@ Java_org_wpilib_hardware_hal_PWMJNI_initializePWMPort (JNIEnv* env, jclass, jint channel) { int32_t status = 0; - auto stack = wpi::java::GetJavaStackTrace(env, "edu.wpi.first"); + auto stack = wpi::util::java::GetJavaStackTrace(env, "edu.wpi.first"); auto pwm = HAL_InitializePWMPort(channel, stack.c_str(), &status); CheckStatusForceThrow(env, status); return (jint)pwm; diff --git a/hal/src/main/native/cpp/jni/PortsJNI.cpp b/hal/src/main/native/cpp/jni/PortsJNI.cpp index 60eff1bf62..34030eefa1 100644 --- a/hal/src/main/native/cpp/jni/PortsJNI.cpp +++ b/hal/src/main/native/cpp/jni/PortsJNI.cpp @@ -10,7 +10,7 @@ #include "org_wpilib_hardware_hal_PortsJNI.h" #include "wpi/hal/Ports.h" -using namespace hal; +using namespace wpi::hal; extern "C" { /* diff --git a/hal/src/main/native/cpp/jni/PowerDistributionJNI.cpp b/hal/src/main/native/cpp/jni/PowerDistributionJNI.cpp index 6b6fc185ef..e956a641a1 100644 --- a/hal/src/main/native/cpp/jni/PowerDistributionJNI.cpp +++ b/hal/src/main/native/cpp/jni/PowerDistributionJNI.cpp @@ -10,7 +10,7 @@ #include "wpi/hal/PowerDistribution.h" #include "wpi/util/jni_util.hpp" -using namespace hal; +using namespace wpi::hal; static_assert(org_wpilib_hardware_hal_PowerDistributionJNI_AUTOMATIC_TYPE == HAL_PowerDistributionType::HAL_PowerDistributionType_kAutomatic); @@ -33,7 +33,7 @@ Java_org_wpilib_hardware_hal_PowerDistributionJNI_initialize (JNIEnv* env, jclass, jint busId, jint module, jint type) { int32_t status = 0; - auto stack = wpi::java::GetJavaStackTrace(env, "edu.wpi.first"); + auto stack = wpi::util::java::GetJavaStackTrace(env, "edu.wpi.first"); auto handle = HAL_InitializePowerDistribution( busId, module, static_cast(type), stack.c_str(), &status); @@ -182,7 +182,7 @@ Java_org_wpilib_hardware_hal_PowerDistributionJNI_getAllCurrents { int32_t status = 0; int32_t size = HAL_GetPowerDistributionNumChannels(handle, &status); - wpi::SmallVector storage; + wpi::util::SmallVector storage; storage.resize_for_overwrite(size); HAL_GetPowerDistributionAllChannelCurrents(handle, storage.data(), size, diff --git a/hal/src/main/native/cpp/jni/PowerJNI.cpp b/hal/src/main/native/cpp/jni/PowerJNI.cpp index b4116c7a1e..9499801139 100644 --- a/hal/src/main/native/cpp/jni/PowerJNI.cpp +++ b/hal/src/main/native/cpp/jni/PowerJNI.cpp @@ -8,7 +8,7 @@ #include "org_wpilib_hardware_hal_PowerJNI.h" #include "wpi/hal/Power.h" -using namespace hal; +using namespace wpi::hal; extern "C" { diff --git a/hal/src/main/native/cpp/jni/REVPHJNI.cpp b/hal/src/main/native/cpp/jni/REVPHJNI.cpp index e2b7e1f04a..6797db8870 100644 --- a/hal/src/main/native/cpp/jni/REVPHJNI.cpp +++ b/hal/src/main/native/cpp/jni/REVPHJNI.cpp @@ -24,7 +24,7 @@ static_assert( org_wpilib_hardware_hal_REVPHJNI_COMPRESSOR_CONFIG_TYPE_HYBRID == HAL_REVPHCompressorConfigType::HAL_REVPHCompressorConfigType_kHybrid); -using namespace hal; +using namespace wpi::hal; extern "C" { @@ -38,7 +38,7 @@ Java_org_wpilib_hardware_hal_REVPHJNI_initialize (JNIEnv* env, jclass, jint busId, jint module) { int32_t status = 0; - auto stack = wpi::java::GetJavaStackTrace(env, "edu.wpi.first"); + auto stack = wpi::util::java::GetJavaStackTrace(env, "edu.wpi.first"); auto handle = HAL_InitializeREVPH(busId, module, stack.c_str(), &status); CheckStatusForceThrow(env, status); return handle; diff --git a/hal/src/main/native/cpp/jni/SerialPortJNI.cpp b/hal/src/main/native/cpp/jni/SerialPortJNI.cpp index fa0fb94d6d..cfe760d0d4 100644 --- a/hal/src/main/native/cpp/jni/SerialPortJNI.cpp +++ b/hal/src/main/native/cpp/jni/SerialPortJNI.cpp @@ -11,8 +11,8 @@ #include "wpi/hal/SerialPort.h" #include "wpi/util/jni_util.hpp" -using namespace hal; -using namespace wpi::java; +using namespace wpi::hal; +using namespace wpi::util::java; extern "C" { @@ -239,7 +239,7 @@ JNIEXPORT jint JNICALL Java_org_wpilib_hardware_hal_SerialPortJNI_serialRead (JNIEnv* env, jclass, jint handle, jbyteArray dataReceived, jint size) { - wpi::SmallVector recvBuf; + wpi::util::SmallVector recvBuf; recvBuf.resize(size); int32_t status = 0; jint retVal = HAL_ReadSerial(static_cast(handle), diff --git a/hal/src/main/native/cpp/jni/SimDeviceJNI.cpp b/hal/src/main/native/cpp/jni/SimDeviceJNI.cpp index 07bf750161..7e36d5ce87 100644 --- a/hal/src/main/native/cpp/jni/SimDeviceJNI.cpp +++ b/hal/src/main/native/cpp/jni/SimDeviceJNI.cpp @@ -12,7 +12,7 @@ #include "wpi/hal/SimDevice.h" #include "wpi/util/jni_util.hpp" -using namespace wpi::java; +using namespace wpi::util::java; static HAL_Value ValueFromJava(jint type, jlong value1, jdouble value2) { HAL_Value value; @@ -114,7 +114,7 @@ Java_org_wpilib_hardware_hal_SimDeviceJNI_createSimValueEnum } arr.emplace_back(JStringRef{env, elem}.str()); } - wpi::SmallVector carr; + wpi::util::SmallVector carr; for (auto&& val : arr) { carr.push_back(val.c_str()); } @@ -148,7 +148,7 @@ Java_org_wpilib_hardware_hal_SimDeviceJNI_createSimValueEnumDouble arr.emplace_back(JStringRef{env, elem}.str()); } - wpi::SmallVector carr; + wpi::util::SmallVector carr; for (auto&& val : arr) { carr.push_back(val.c_str()); } @@ -166,7 +166,7 @@ JNIEXPORT jobject JNICALL Java_org_wpilib_hardware_hal_SimDeviceJNI_getSimValue (JNIEnv* env, jclass, jint handle) { - return hal::CreateHALValue(env, HAL_GetSimValue(handle)); + return wpi::hal::CreateHALValue(env, HAL_GetSimValue(handle)); } /* diff --git a/hal/src/main/native/cpp/jni/ThreadsJNI.cpp b/hal/src/main/native/cpp/jni/ThreadsJNI.cpp index 013e277a16..6f611db24f 100644 --- a/hal/src/main/native/cpp/jni/ThreadsJNI.cpp +++ b/hal/src/main/native/cpp/jni/ThreadsJNI.cpp @@ -10,7 +10,7 @@ #include "org_wpilib_hardware_hal_ThreadsJNI.h" #include "wpi/hal/Threads.h" -using namespace hal; +using namespace wpi::hal; extern "C" { /* diff --git a/hal/src/main/native/cpp/jni/UsageReportingJNI.cpp b/hal/src/main/native/cpp/jni/UsageReportingJNI.cpp index c57039b853..5d928e05ce 100644 --- a/hal/src/main/native/cpp/jni/UsageReportingJNI.cpp +++ b/hal/src/main/native/cpp/jni/UsageReportingJNI.cpp @@ -11,7 +11,7 @@ #include "wpi/util/jni_util.hpp" #include "wpi/util/string.h" -using namespace wpi::java; +using namespace wpi::util::java; extern "C" { @@ -26,8 +26,8 @@ Java_org_wpilib_hardware_hal_UsageReportingJNI_report { JStringRef resourceStr{env, resource}; JStringRef dataStr{env, data}; - WPI_String resourceWpiStr = wpi::make_string(resourceStr); - WPI_String dataWpiStr = wpi::make_string(dataStr); + WPI_String resourceWpiStr = wpi::util::make_string(resourceStr); + WPI_String dataWpiStr = wpi::util::make_string(dataStr); return HAL_ReportUsage(&resourceWpiStr, &dataWpiStr); } diff --git a/hal/src/main/native/cpp/jni/simulation/AddressableLEDDataJNI.cpp b/hal/src/main/native/cpp/jni/simulation/AddressableLEDDataJNI.cpp index 9027eba3bf..34961b376a 100644 --- a/hal/src/main/native/cpp/jni/simulation/AddressableLEDDataJNI.cpp +++ b/hal/src/main/native/cpp/jni/simulation/AddressableLEDDataJNI.cpp @@ -13,8 +13,8 @@ static_assert(sizeof(jbyte) * 3 == sizeof(HAL_AddressableLEDData)); -using namespace hal; -using namespace wpi::java; +using namespace wpi::hal; +using namespace wpi::util::java; extern "C" { diff --git a/hal/src/main/native/cpp/jni/simulation/AnalogInDataJNI.cpp b/hal/src/main/native/cpp/jni/simulation/AnalogInDataJNI.cpp index 73861d8ae0..da56034524 100644 --- a/hal/src/main/native/cpp/jni/simulation/AnalogInDataJNI.cpp +++ b/hal/src/main/native/cpp/jni/simulation/AnalogInDataJNI.cpp @@ -8,7 +8,7 @@ #include "org_wpilib_hardware_hal_simulation_AnalogInDataJNI.h" #include "wpi/hal/simulation/AnalogInData.h" -using namespace hal; +using namespace wpi::hal; extern "C" { diff --git a/hal/src/main/native/cpp/jni/simulation/BufferCallbackStore.cpp b/hal/src/main/native/cpp/jni/simulation/BufferCallbackStore.cpp index b12de5eba6..83b7e5bafc 100644 --- a/hal/src/main/native/cpp/jni/simulation/BufferCallbackStore.cpp +++ b/hal/src/main/native/cpp/jni/simulation/BufferCallbackStore.cpp @@ -14,22 +14,22 @@ #include "wpi/hal/handles/UnlimitedHandleResource.h" #include "wpi/util/jni_util.hpp" -using namespace hal; -using namespace hal::sim; -using namespace wpi::java; +using namespace wpi::hal; +using namespace wpi::hal::sim; +using namespace wpi::util::java; -static hal::UnlimitedHandleResource* +static wpi::hal::UnlimitedHandleResource* callbackHandles; -namespace hal::sim { +namespace wpi::hal::sim { void InitializeBufferStore() { - static hal::UnlimitedHandleResource + static wpi::hal::UnlimitedHandleResource cb; callbackHandles = &cb; } -} // namespace hal::sim +} // namespace wpi::hal::sim void BufferCallbackStore::create(JNIEnv* env, jobject obj) { m_call = JGlobal(env, obj); diff --git a/hal/src/main/native/cpp/jni/simulation/BufferCallbackStore.h b/hal/src/main/native/cpp/jni/simulation/BufferCallbackStore.h index 2a681ffbd7..cee5338a95 100644 --- a/hal/src/main/native/cpp/jni/simulation/BufferCallbackStore.h +++ b/hal/src/main/native/cpp/jni/simulation/BufferCallbackStore.h @@ -13,7 +13,7 @@ #include "wpi/hal/simulation/NotifyListener.h" #include "wpi/util/jni_util.hpp" -namespace hal::sim { +namespace wpi::hal::sim { class BufferCallbackStore { public: void create(JNIEnv* env, jobject obj); @@ -23,7 +23,7 @@ class BufferCallbackStore { int32_t getCallbackId() { return callbackId; } private: - wpi::java::JGlobal m_call; + wpi::util::java::JGlobal m_call; int32_t callbackId; }; @@ -38,4 +38,4 @@ SIM_JniHandle AllocateBufferCallback(JNIEnv* env, jint index, jobject callback, RegisterBufferCallbackFunc createCallback); void FreeBufferCallback(JNIEnv* env, SIM_JniHandle handle, jint index, FreeBufferCallbackFunc freeCallback); -} // namespace hal::sim +} // namespace wpi::hal::sim diff --git a/hal/src/main/native/cpp/jni/simulation/CTREPCMDataJNI.cpp b/hal/src/main/native/cpp/jni/simulation/CTREPCMDataJNI.cpp index e58040034e..327d941724 100644 --- a/hal/src/main/native/cpp/jni/simulation/CTREPCMDataJNI.cpp +++ b/hal/src/main/native/cpp/jni/simulation/CTREPCMDataJNI.cpp @@ -8,7 +8,7 @@ #include "org_wpilib_hardware_hal_simulation_CTREPCMDataJNI.h" #include "wpi/hal/simulation/CTREPCMData.h" -using namespace hal; +using namespace wpi::hal; extern "C" { diff --git a/hal/src/main/native/cpp/jni/simulation/CallbackStore.cpp b/hal/src/main/native/cpp/jni/simulation/CallbackStore.cpp index 2156ee892e..be06d97190 100644 --- a/hal/src/main/native/cpp/jni/simulation/CallbackStore.cpp +++ b/hal/src/main/native/cpp/jni/simulation/CallbackStore.cpp @@ -15,22 +15,22 @@ #include "wpi/hal/handles/UnlimitedHandleResource.h" #include "wpi/util/jni_util.hpp" -using namespace hal; -using namespace hal::sim; -using namespace wpi::java; +using namespace wpi::hal; +using namespace wpi::hal::sim; +using namespace wpi::util::java; -static hal::UnlimitedHandleResource* +static wpi::hal::UnlimitedHandleResource* callbackHandles; -namespace hal::sim { +namespace wpi::hal::sim { void InitializeStore() { - static hal::UnlimitedHandleResource + static wpi::hal::UnlimitedHandleResource cb; callbackHandles = &cb; } -} // namespace hal::sim +} // namespace wpi::hal::sim void CallbackStore::create(JNIEnv* env, jobject obj) { m_call = JGlobal(env, obj); diff --git a/hal/src/main/native/cpp/jni/simulation/CallbackStore.h b/hal/src/main/native/cpp/jni/simulation/CallbackStore.h index 079d2e16cd..5e27b8ff02 100644 --- a/hal/src/main/native/cpp/jni/simulation/CallbackStore.h +++ b/hal/src/main/native/cpp/jni/simulation/CallbackStore.h @@ -13,7 +13,7 @@ #include "wpi/hal/simulation/NotifyListener.h" #include "wpi/util/jni_util.hpp" -namespace hal::sim { +namespace wpi::hal::sim { class CallbackStore { public: void create(JNIEnv* env, jobject obj); @@ -23,7 +23,7 @@ class CallbackStore { int32_t getCallbackId() { return callbackId; } private: - wpi::java::JGlobal m_call; + wpi::util::java::JGlobal m_call; int32_t callbackId; }; @@ -59,4 +59,4 @@ void FreeChannelCallback(JNIEnv* env, SIM_JniHandle handle, jint index, jint channel, FreeChannelCallbackFunc freeCallback); void FreeCallbackNoIndex(JNIEnv* env, SIM_JniHandle handle, FreeCallbackNoIndexFunc freeCallback); -} // namespace hal::sim +} // namespace wpi::hal::sim diff --git a/hal/src/main/native/cpp/jni/simulation/ConstBufferCallbackStore.cpp b/hal/src/main/native/cpp/jni/simulation/ConstBufferCallbackStore.cpp index 69a4aeaa45..1376623091 100644 --- a/hal/src/main/native/cpp/jni/simulation/ConstBufferCallbackStore.cpp +++ b/hal/src/main/native/cpp/jni/simulation/ConstBufferCallbackStore.cpp @@ -14,22 +14,22 @@ #include "wpi/hal/handles/UnlimitedHandleResource.h" #include "wpi/util/jni_util.hpp" -using namespace hal; -using namespace hal::sim; -using namespace wpi::java; +using namespace wpi::hal; +using namespace wpi::hal::sim; +using namespace wpi::util::java; -static hal::UnlimitedHandleResource* +static wpi::hal::UnlimitedHandleResource* callbackHandles; -namespace hal::sim { +namespace wpi::hal::sim { void InitializeConstBufferStore() { - static hal::UnlimitedHandleResource + static wpi::hal::UnlimitedHandleResource cb; callbackHandles = &cb; } -} // namespace hal::sim +} // namespace wpi::hal::sim void ConstBufferCallbackStore::create(JNIEnv* env, jobject obj) { m_call = JGlobal(env, obj); diff --git a/hal/src/main/native/cpp/jni/simulation/ConstBufferCallbackStore.h b/hal/src/main/native/cpp/jni/simulation/ConstBufferCallbackStore.h index 97f4b4b8d2..3e6d9e0672 100644 --- a/hal/src/main/native/cpp/jni/simulation/ConstBufferCallbackStore.h +++ b/hal/src/main/native/cpp/jni/simulation/ConstBufferCallbackStore.h @@ -13,7 +13,7 @@ #include "wpi/hal/simulation/NotifyListener.h" #include "wpi/util/jni_util.hpp" -namespace hal::sim { +namespace wpi::hal::sim { class ConstBufferCallbackStore { public: void create(JNIEnv* env, jobject obj); @@ -24,7 +24,7 @@ class ConstBufferCallbackStore { int32_t getCallbackId() { return callbackId; } private: - wpi::java::JGlobal m_call; + wpi::util::java::JGlobal m_call; int32_t callbackId; }; @@ -39,4 +39,4 @@ SIM_JniHandle AllocateConstBufferCallback( RegisterConstBufferCallbackFunc createCallback); void FreeConstBufferCallback(JNIEnv* env, SIM_JniHandle handle, jint index, FreeConstBufferCallbackFunc freeCallback); -} // namespace hal::sim +} // namespace wpi::hal::sim diff --git a/hal/src/main/native/cpp/jni/simulation/DIODataJNI.cpp b/hal/src/main/native/cpp/jni/simulation/DIODataJNI.cpp index 005800e7cd..3e93ff7127 100644 --- a/hal/src/main/native/cpp/jni/simulation/DIODataJNI.cpp +++ b/hal/src/main/native/cpp/jni/simulation/DIODataJNI.cpp @@ -8,7 +8,7 @@ #include "org_wpilib_hardware_hal_simulation_DIODataJNI.h" #include "wpi/hal/simulation/DIOData.h" -using namespace hal; +using namespace wpi::hal; extern "C" { diff --git a/hal/src/main/native/cpp/jni/simulation/DigitalPWMDataJNI.cpp b/hal/src/main/native/cpp/jni/simulation/DigitalPWMDataJNI.cpp index 5ece6ac98f..6346e098e4 100644 --- a/hal/src/main/native/cpp/jni/simulation/DigitalPWMDataJNI.cpp +++ b/hal/src/main/native/cpp/jni/simulation/DigitalPWMDataJNI.cpp @@ -8,7 +8,7 @@ #include "org_wpilib_hardware_hal_simulation_DigitalPWMDataJNI.h" #include "wpi/hal/simulation/DigitalPWMData.h" -using namespace hal; +using namespace wpi::hal; extern "C" { diff --git a/hal/src/main/native/cpp/jni/simulation/DriverStationDataJNI.cpp b/hal/src/main/native/cpp/jni/simulation/DriverStationDataJNI.cpp index 4b4737d7a0..13708735bc 100644 --- a/hal/src/main/native/cpp/jni/simulation/DriverStationDataJNI.cpp +++ b/hal/src/main/native/cpp/jni/simulation/DriverStationDataJNI.cpp @@ -11,8 +11,8 @@ #include "wpi/util/StringExtras.hpp" #include "wpi/util/jni_util.hpp" -using namespace hal; -using namespace wpi::java; +using namespace wpi::hal; +using namespace wpi::util::java; extern "C" { @@ -537,9 +537,9 @@ Java_org_wpilib_hardware_hal_simulation_DriverStationDataJNI_setMatchInfo JStringRef gameSpecificMessageRef{env, gameSpecificMessage}; HAL_MatchInfo halMatchInfo; - wpi::format_to_n_c_str(halMatchInfo.eventName, sizeof(halMatchInfo.eventName), + wpi::util::format_to_n_c_str(halMatchInfo.eventName, sizeof(halMatchInfo.eventName), "{}", eventNameRef.str()); - wpi::format_to_n_c_str( + wpi::util::format_to_n_c_str( reinterpret_cast(halMatchInfo.gameSpecificMessage), sizeof(halMatchInfo.gameSpecificMessage), "{}", gameSpecificMessageRef.str()); @@ -732,7 +732,7 @@ Java_org_wpilib_hardware_hal_simulation_DriverStationDataJNI_setJoystickName (JNIEnv* env, jclass, jint stick, jstring name) { JStringRef nameJString{env, name}; - auto str = wpi::make_string(nameJString); + auto str = wpi::util::make_string(nameJString); HALSIM_SetJoystickName(stick, &str); } @@ -746,7 +746,7 @@ Java_org_wpilib_hardware_hal_simulation_DriverStationDataJNI_setGameSpecificMess (JNIEnv* env, jclass, jstring message) { JStringRef messageJString{env, message}; - auto str = wpi::make_string(messageJString); + auto str = wpi::util::make_string(messageJString); HALSIM_SetGameSpecificMessage(&str); } @@ -760,7 +760,7 @@ Java_org_wpilib_hardware_hal_simulation_DriverStationDataJNI_setEventName (JNIEnv* env, jclass, jstring name) { JStringRef nameJString{env, name}; - auto str = wpi::make_string(nameJString); + auto str = wpi::util::make_string(nameJString); HALSIM_SetEventName(&str); } diff --git a/hal/src/main/native/cpp/jni/simulation/DutyCycleDataJNI.cpp b/hal/src/main/native/cpp/jni/simulation/DutyCycleDataJNI.cpp index 62bb0c8f85..3191adff98 100644 --- a/hal/src/main/native/cpp/jni/simulation/DutyCycleDataJNI.cpp +++ b/hal/src/main/native/cpp/jni/simulation/DutyCycleDataJNI.cpp @@ -8,7 +8,7 @@ #include "org_wpilib_hardware_hal_simulation_DutyCycleDataJNI.h" #include "wpi/hal/simulation/DutyCycleData.h" -using namespace hal; +using namespace wpi::hal; extern "C" { diff --git a/hal/src/main/native/cpp/jni/simulation/EncoderDataJNI.cpp b/hal/src/main/native/cpp/jni/simulation/EncoderDataJNI.cpp index c2fbed5337..86cfdb4dd1 100644 --- a/hal/src/main/native/cpp/jni/simulation/EncoderDataJNI.cpp +++ b/hal/src/main/native/cpp/jni/simulation/EncoderDataJNI.cpp @@ -8,7 +8,7 @@ #include "org_wpilib_hardware_hal_simulation_EncoderDataJNI.h" #include "wpi/hal/simulation/EncoderData.h" -using namespace hal; +using namespace wpi::hal; extern "C" { diff --git a/hal/src/main/native/cpp/jni/simulation/I2CDataJNI.cpp b/hal/src/main/native/cpp/jni/simulation/I2CDataJNI.cpp index be46d43fa3..20aca83cfe 100644 --- a/hal/src/main/native/cpp/jni/simulation/I2CDataJNI.cpp +++ b/hal/src/main/native/cpp/jni/simulation/I2CDataJNI.cpp @@ -10,7 +10,7 @@ #include "org_wpilib_hardware_hal_simulation_I2CDataJNI.h" #include "wpi/hal/simulation/I2CData.h" -using namespace hal; +using namespace wpi::hal; extern "C" { diff --git a/hal/src/main/native/cpp/jni/simulation/PWMDataJNI.cpp b/hal/src/main/native/cpp/jni/simulation/PWMDataJNI.cpp index 177df59e5f..d5de492775 100644 --- a/hal/src/main/native/cpp/jni/simulation/PWMDataJNI.cpp +++ b/hal/src/main/native/cpp/jni/simulation/PWMDataJNI.cpp @@ -8,7 +8,7 @@ #include "org_wpilib_hardware_hal_simulation_PWMDataJNI.h" #include "wpi/hal/simulation/PWMData.h" -using namespace hal; +using namespace wpi::hal; extern "C" { diff --git a/hal/src/main/native/cpp/jni/simulation/PowerDistributionDataJNI.cpp b/hal/src/main/native/cpp/jni/simulation/PowerDistributionDataJNI.cpp index 502d11813a..6fe61be0fe 100644 --- a/hal/src/main/native/cpp/jni/simulation/PowerDistributionDataJNI.cpp +++ b/hal/src/main/native/cpp/jni/simulation/PowerDistributionDataJNI.cpp @@ -8,7 +8,7 @@ #include "org_wpilib_hardware_hal_simulation_PowerDistributionDataJNI.h" #include "wpi/hal/simulation/PowerDistributionData.h" -using namespace hal; +using namespace wpi::hal; extern "C" { diff --git a/hal/src/main/native/cpp/jni/simulation/REVPHDataJNI.cpp b/hal/src/main/native/cpp/jni/simulation/REVPHDataJNI.cpp index 9de41c5039..23a6c5e426 100644 --- a/hal/src/main/native/cpp/jni/simulation/REVPHDataJNI.cpp +++ b/hal/src/main/native/cpp/jni/simulation/REVPHDataJNI.cpp @@ -8,7 +8,7 @@ #include "org_wpilib_hardware_hal_simulation_REVPHDataJNI.h" #include "wpi/hal/simulation/REVPHData.h" -using namespace hal; +using namespace wpi::hal; extern "C" { diff --git a/hal/src/main/native/cpp/jni/simulation/RoboRioDataJNI.cpp b/hal/src/main/native/cpp/jni/simulation/RoboRioDataJNI.cpp index 75485a8870..715b2537ba 100644 --- a/hal/src/main/native/cpp/jni/simulation/RoboRioDataJNI.cpp +++ b/hal/src/main/native/cpp/jni/simulation/RoboRioDataJNI.cpp @@ -9,8 +9,8 @@ #include "wpi/hal/simulation/RoboRioData.h" #include "wpi/util/jni_util.hpp" -using namespace hal; -using namespace wpi::java; +using namespace wpi::hal; +using namespace wpi::util::java; extern "C" { @@ -430,7 +430,7 @@ Java_org_wpilib_hardware_hal_simulation_RoboRioDataJNI_getSerialNumber { WPI_String str; HALSIM_GetRoboRioSerialNumber(&str); - auto jstr = MakeJString(env, wpi::to_string_view(&str)); + auto jstr = MakeJString(env, wpi::util::to_string_view(&str)); WPI_FreeString(&str); return jstr; } @@ -445,7 +445,7 @@ Java_org_wpilib_hardware_hal_simulation_RoboRioDataJNI_setSerialNumber (JNIEnv* env, jclass, jstring serialNumber) { JStringRef serialNumberJString{env, serialNumber}; - auto str = wpi::make_string(serialNumberJString); + auto str = wpi::util::make_string(serialNumberJString); HALSIM_SetRoboRioSerialNumber(&str); } @@ -460,7 +460,7 @@ Java_org_wpilib_hardware_hal_simulation_RoboRioDataJNI_getComments { WPI_String str; HALSIM_GetRoboRioComments(&str); - auto jstr = MakeJString(env, wpi::to_string_view(&str)); + auto jstr = MakeJString(env, wpi::util::to_string_view(&str)); WPI_FreeString(&str); return jstr; } @@ -475,7 +475,7 @@ Java_org_wpilib_hardware_hal_simulation_RoboRioDataJNI_setComments (JNIEnv* env, jclass, jstring comments) { JStringRef commentsJString{env, comments}; - auto str = wpi::make_string(commentsJString); + auto str = wpi::util::make_string(commentsJString); HALSIM_SetRoboRioComments(&str); } diff --git a/hal/src/main/native/cpp/jni/simulation/SimDeviceDataJNI.cpp b/hal/src/main/native/cpp/jni/simulation/SimDeviceDataJNI.cpp index 76457b58c3..722ef1abaf 100644 --- a/hal/src/main/native/cpp/jni/simulation/SimDeviceDataJNI.cpp +++ b/hal/src/main/native/cpp/jni/simulation/SimDeviceDataJNI.cpp @@ -18,8 +18,8 @@ #include "wpi/hal/simulation/SimDeviceData.h" #include "wpi/util/jni_util.hpp" -using namespace hal; -using namespace wpi::java; +using namespace wpi::hal; +using namespace wpi::util::java; static JClass simDeviceInfoCls; static JClass simValueInfoCls; @@ -105,7 +105,7 @@ class DeviceCallbackStore { int32_t getCallbackId() { return callbackId; } private: - wpi::java::JGlobal m_call; + wpi::util::java::JGlobal m_call; int32_t callbackId; }; @@ -119,7 +119,7 @@ class ValueCallbackStore { int32_t getCallbackId() { return m_callbackId; } private: - wpi::java::JGlobal m_call; + wpi::util::java::JGlobal m_call; int32_t m_callbackId; }; @@ -193,8 +193,8 @@ void ValueCallbackStore::performCallback(const char* name, } } -static hal::UnlimitedHandleResource* +static wpi::hal::UnlimitedHandleResource* deviceCallbackHandles; namespace { @@ -250,8 +250,8 @@ static void FreeDeviceCallback(JNIEnv* env, SIM_JniHandle handle, callback->free(env); } -static hal::UnlimitedHandleResource* +static wpi::hal::UnlimitedHandleResource* valueCallbackHandles; namespace { @@ -307,7 +307,7 @@ static void FreeValueCallback(JNIEnv* env, SIM_JniHandle handle, callback->free(env); } -namespace hal::sim { +namespace wpi::hal::sim { bool InitializeSimDeviceDataJNI(JNIEnv* env) { simDeviceInfoCls = JClass( @@ -346,13 +346,13 @@ bool InitializeSimDeviceDataJNI(JNIEnv* env) { return false; } - static hal::UnlimitedHandleResource + static wpi::hal::UnlimitedHandleResource cbDevice; deviceCallbackHandles = &cbDevice; - static hal::UnlimitedHandleResource + static wpi::hal::UnlimitedHandleResource cbValue; valueCallbackHandles = &cbValue; @@ -366,7 +366,7 @@ void FreeSimDeviceDataJNI(JNIEnv* env) { simValueCallbackCls.free(env); } -} // namespace hal::sim +} // namespace wpi::hal::sim extern "C" { diff --git a/hal/src/main/native/cpp/jni/simulation/SimDeviceDataJNI.h b/hal/src/main/native/cpp/jni/simulation/SimDeviceDataJNI.h index 08c47b9ed4..83259c5a39 100644 --- a/hal/src/main/native/cpp/jni/simulation/SimDeviceDataJNI.h +++ b/hal/src/main/native/cpp/jni/simulation/SimDeviceDataJNI.h @@ -6,7 +6,7 @@ #include -namespace hal::sim { +namespace wpi::hal::sim { bool InitializeSimDeviceDataJNI(JNIEnv* env); void FreeSimDeviceDataJNI(JNIEnv* env); -} // namespace hal::sim +} // namespace wpi::hal::sim diff --git a/hal/src/main/native/cpp/jni/simulation/SimulatorJNI.cpp b/hal/src/main/native/cpp/jni/simulation/SimulatorJNI.cpp index f72381052c..a1fef9f40a 100644 --- a/hal/src/main/native/cpp/jni/simulation/SimulatorJNI.cpp +++ b/hal/src/main/native/cpp/jni/simulation/SimulatorJNI.cpp @@ -14,7 +14,7 @@ #include "wpi/hal/simulation/MockHooks.h" #include "wpi/util/jni_util.hpp" -using namespace wpi::java; +using namespace wpi::util::java; static JavaVM* jvm = nullptr; static JClass notifyCallbackCls; @@ -24,7 +24,7 @@ static jmethodID notifyCallbackCallback; static jmethodID bufferCallbackCallback; static jmethodID constBufferCallbackCallback; -namespace hal::sim { +namespace wpi::hal::sim { jint SimOnLoad(JavaVM* vm, void* reserved) { jvm = vm; @@ -108,7 +108,7 @@ jmethodID GetConstBufferCallback() { return constBufferCallbackCallback; } -} // namespace hal::sim +} // namespace wpi::hal::sim extern "C" { /* @@ -240,6 +240,6 @@ JNIEXPORT void JNICALL Java_org_wpilib_hardware_hal_simulation_SimulatorJNI_resetHandles (JNIEnv*, jclass) { - hal::HandleBase::ResetGlobalHandles(); + wpi::hal::HandleBase::ResetGlobalHandles(); } } // extern "C" diff --git a/hal/src/main/native/cpp/jni/simulation/SimulatorJNI.h b/hal/src/main/native/cpp/jni/simulation/SimulatorJNI.h index 2d5181753a..e70a438a69 100644 --- a/hal/src/main/native/cpp/jni/simulation/SimulatorJNI.h +++ b/hal/src/main/native/cpp/jni/simulation/SimulatorJNI.h @@ -9,10 +9,10 @@ using SIM_JniHandle = HAL_Handle; // NOLINT -namespace hal::sim { +namespace wpi::hal::sim { JavaVM* GetJVM(); jmethodID GetNotifyCallback(); jmethodID GetBufferCallback(); jmethodID GetConstBufferCallback(); -} // namespace hal::sim +} // namespace wpi::hal::sim diff --git a/hal/src/main/native/cpp/proto/ControlDataProto.cpp b/hal/src/main/native/cpp/proto/ControlDataProto.cpp index 3bc22fa0c1..e6a245cc8f 100644 --- a/hal/src/main/native/cpp/proto/ControlDataProto.cpp +++ b/hal/src/main/native/cpp/proto/ControlDataProto.cpp @@ -60,9 +60,9 @@ constexpr mrc::ControlFlags ToControlWord(uint32_t Word) { } // namespace -std::optional wpi::Protobuf::Unpack( +std::optional wpi::util::Protobuf::Unpack( InputStream& Stream) { - wpi::UnpackCallback JoystickCb; + wpi::util::UnpackCallback JoystickCb; mrc_proto_ProtobufControlData Msg{ .ControlWord = 0, @@ -91,10 +91,10 @@ std::optional wpi::Protobuf::Unpack( return ControlData; } -bool wpi::Protobuf::Pack(OutputStream& Stream, +bool wpi::util::Protobuf::Pack(OutputStream& Stream, const mrc::ControlData& Value) { std::span Sticks = Value.Joysticks(); - wpi::PackCallback Joysticks{Sticks}; + wpi::util::PackCallback Joysticks{Sticks}; mrc_proto_ProtobufControlData Msg{ .ControlWord = FromControlWord(Value.ControlWord), @@ -106,9 +106,9 @@ bool wpi::Protobuf::Pack(OutputStream& Stream, return Stream.Encode(Msg); } -std::optional wpi::Protobuf::Unpack( +std::optional wpi::util::Protobuf::Unpack( InputStream& Stream) { - wpi::UnpackCallback AxesCb; + wpi::util::UnpackCallback AxesCb; mrc_proto_ProtobufJoystickData Msg{ .AvailableButtons = 0, @@ -148,9 +148,9 @@ std::optional wpi::Protobuf::Unpack( return Joystick; } -bool wpi::Protobuf::Pack(OutputStream& Stream, +bool wpi::util::Protobuf::Pack(OutputStream& Stream, const mrc::Joystick& Value) { - wpi::PackCallback AxesCb{Value.Axes.Axes()}; + wpi::util::PackCallback AxesCb{Value.Axes.Axes()}; uint32_t PovsStore = 0; for (int i = static_cast(Value.Povs.GetCount()) - 1; i >= 0; i--) { diff --git a/hal/src/main/native/cpp/proto/ErrorInfoProto.cpp b/hal/src/main/native/cpp/proto/ErrorInfoProto.cpp index f2f3fa9864..85c55d3769 100644 --- a/hal/src/main/native/cpp/proto/ErrorInfoProto.cpp +++ b/hal/src/main/native/cpp/proto/ErrorInfoProto.cpp @@ -8,11 +8,11 @@ #include "wpi/hal/proto/ErrorInfo.h" #include "wpi/util/protobuf/ProtobufCallbacks.hpp" -std::optional wpi::Protobuf::Unpack( +std::optional wpi::util::Protobuf::Unpack( InputStream& Stream) { - wpi::UnpackCallback DetailsCb; - wpi::UnpackCallback LocationCb; - wpi::UnpackCallback CallStackCb; + wpi::util::UnpackCallback DetailsCb; + wpi::util::UnpackCallback LocationCb; + wpi::util::UnpackCallback CallStackCb; mrc_proto_ProtobufErrorInfo Msg{ .IsError = false, @@ -49,14 +49,14 @@ std::optional wpi::Protobuf::Unpack( return ToRet; } -bool wpi::Protobuf::Pack(OutputStream& Stream, +bool wpi::util::Protobuf::Pack(OutputStream& Stream, const mrc::ErrorInfo& Value) { std::string_view DetailsView = Value.GetDetails(); std::string_view LocationView = Value.GetLocation(); std::string_view CallStackView = Value.GetCallStack(); - wpi::PackCallback DetailsCb{&DetailsView}; - wpi::PackCallback LocationCb{&LocationView}; - wpi::PackCallback CallStackCb{&CallStackView}; + wpi::util::PackCallback DetailsCb{&DetailsView}; + wpi::util::PackCallback LocationCb{&LocationView}; + wpi::util::PackCallback CallStackCb{&CallStackView}; mrc_proto_ProtobufErrorInfo Msg{ .IsError = Value.IsError, diff --git a/hal/src/main/native/cpp/proto/JoystickDescriptorProto.cpp b/hal/src/main/native/cpp/proto/JoystickDescriptorProto.cpp index acf5218724..0d3d08ee5d 100644 --- a/hal/src/main/native/cpp/proto/JoystickDescriptorProto.cpp +++ b/hal/src/main/native/cpp/proto/JoystickDescriptorProto.cpp @@ -9,9 +9,9 @@ #include "wpi/util/protobuf/ProtobufCallbacks.hpp" std::optional -wpi::Protobuf::Unpack(InputStream& Stream) { - wpi::UnpackCallback JoystickNameCb; - wpi::UnpackCallback AxisTypesCb; +wpi::util::Protobuf::Unpack(InputStream& Stream) { + wpi::util::UnpackCallback JoystickNameCb; + wpi::util::UnpackCallback AxisTypesCb; mrc_proto_ProtobufJoystickDescriptor Msg; Msg.JoystickName = JoystickNameCb.Callback(); @@ -47,13 +47,13 @@ wpi::Protobuf::Unpack(InputStream& Stream) { return OutputData; } -bool wpi::Protobuf::Pack( +bool wpi::util::Protobuf::Pack( OutputStream& Stream, const mrc::JoystickDescriptor& Value) { std::string_view JoystickName = Value.GetName(); - wpi::PackCallback JoystickNameCb{&JoystickName}; + wpi::util::PackCallback JoystickNameCb{&JoystickName}; std::span AxisTypes = Value.AxesTypes(); - wpi::PackCallback AxisTypesCb{AxisTypes}; + wpi::util::PackCallback AxisTypesCb{AxisTypes}; mrc_proto_ProtobufJoystickDescriptor Msg{ .JoystickName = JoystickNameCb.Callback(), diff --git a/hal/src/main/native/cpp/proto/JoystickRumbleDataProto.cpp b/hal/src/main/native/cpp/proto/JoystickRumbleDataProto.cpp index ff793f8b0a..6864992536 100644 --- a/hal/src/main/native/cpp/proto/JoystickRumbleDataProto.cpp +++ b/hal/src/main/native/cpp/proto/JoystickRumbleDataProto.cpp @@ -6,8 +6,8 @@ #include "wpi/util/protobuf/ProtobufCallbacks.hpp" std::optional -wpi::Protobuf::Unpack(InputStream& Stream) { - wpi::UnpackCallback RumbleCb; +wpi::util::Protobuf::Unpack(InputStream& Stream) { + wpi::util::UnpackCallback RumbleCb; mrc_proto_ProtobufJoystickRumbleData Msg{ .Value = RumbleCb.Callback(), @@ -29,9 +29,9 @@ wpi::Protobuf::Unpack(InputStream& Stream) { return Rumble; } -bool wpi::Protobuf::Pack( +bool wpi::util::Protobuf::Pack( OutputStream& Stream, const mrc::JoystickRumbleData& Value) { - wpi::PackCallback RumbleCb{Value.Rumbles()}; + wpi::util::PackCallback RumbleCb{Value.Rumbles()}; mrc_proto_ProtobufJoystickRumbleData Msg{ .Value = RumbleCb.Callback(), diff --git a/hal/src/main/native/cpp/proto/MatchInfoProto.cpp b/hal/src/main/native/cpp/proto/MatchInfoProto.cpp index 0f1c6526d6..27dd5d94ef 100644 --- a/hal/src/main/native/cpp/proto/MatchInfoProto.cpp +++ b/hal/src/main/native/cpp/proto/MatchInfoProto.cpp @@ -8,9 +8,9 @@ #include "wpi/hal/proto/MatchInfo.h" #include "wpi/util/protobuf/ProtobufCallbacks.hpp" -std::optional wpi::Protobuf::Unpack( +std::optional wpi::util::Protobuf::Unpack( InputStream& Stream) { - wpi::UnpackCallback NameCb; + wpi::util::UnpackCallback NameCb; mrc_proto_ProtobufMatchInfo Msg; Msg.EventName = NameCb.Callback(); @@ -35,10 +35,10 @@ std::optional wpi::Protobuf::Unpack( return OutputData; } -bool wpi::Protobuf::Pack(OutputStream& Stream, +bool wpi::util::Protobuf::Pack(OutputStream& Stream, const mrc::MatchInfo& Value) { std::string_view EventNameStr = Value.GetEventName(); - wpi::PackCallback EventName{&EventNameStr}; + wpi::util::PackCallback EventName{&EventNameStr}; mrc_proto_ProtobufMatchInfo Msg{ .EventName = EventName.Callback(), diff --git a/hal/src/main/native/cpp/proto/OpModeProto.cpp b/hal/src/main/native/cpp/proto/OpModeProto.cpp index 4f8fe862c9..d7bbedb0bf 100644 --- a/hal/src/main/native/cpp/proto/OpModeProto.cpp +++ b/hal/src/main/native/cpp/proto/OpModeProto.cpp @@ -9,9 +9,9 @@ #include "wpi/hal/proto/OpMode.h" #include "wpi/util/protobuf/ProtobufCallbacks.hpp" -std::optional wpi::Protobuf::Unpack( +std::optional wpi::util::Protobuf::Unpack( InputStream& Stream) { - wpi::UnpackCallback NameCb; + wpi::util::UnpackCallback NameCb; mrc_proto_ProtobufOpMode Msg; Msg.Name = NameCb.Callback(); @@ -34,10 +34,10 @@ std::optional wpi::Protobuf::Unpack( return OutputData; } -bool wpi::Protobuf::Pack(OutputStream& Stream, +bool wpi::util::Protobuf::Pack(OutputStream& Stream, const mrc::OpMode& Value) { std::string_view EventNameStr = Value.GetName(); - wpi::PackCallback EventName{&EventNameStr}; + wpi::util::PackCallback EventName{&EventNameStr}; mrc_proto_ProtobufOpMode Msg{ .Hash = Value.Hash.ToValue(), @@ -48,8 +48,8 @@ bool wpi::Protobuf::Pack(OutputStream& Stream, } std::optional> -wpi::Protobuf>::Unpack(InputStream& Stream) { - wpi::StdVectorUnpackCallback ModesCb; +wpi::util::Protobuf>::Unpack(InputStream& Stream) { + wpi::util::StdVectorUnpackCallback ModesCb; ModesCb.SetLimits(DecodeLimits::Add); mrc_proto_ProtobufAvailableOpModes Msg; @@ -62,10 +62,10 @@ wpi::Protobuf>::Unpack(InputStream& Stream) { return ModesCb.Vec(); } -bool wpi::Protobuf>::Pack( +bool wpi::util::Protobuf>::Pack( OutputStream& Stream, const std::vector& Value) { std::span ModesSpan = Value; - wpi::PackCallback Modes{ModesSpan}; + wpi::util::PackCallback Modes{ModesSpan}; mrc_proto_ProtobufAvailableOpModes Msg{ .Modes = Modes.Callback(), diff --git a/hal/src/main/native/include/wpi/hal/SimDevice.h b/hal/src/main/native/include/wpi/hal/SimDevice.h index 93a24bd60c..2aa20ffdb1 100644 --- a/hal/src/main/native/include/wpi/hal/SimDevice.h +++ b/hal/src/main/native/include/wpi/hal/SimDevice.h @@ -394,7 +394,7 @@ void HAL_ResetSimValue(HAL_SimValueHandle handle); #endif #ifdef __cplusplus -namespace hal { +namespace wpi::hal { /** * C++ wrapper around a HAL simulator value handle. @@ -944,5 +944,5 @@ class SimDevice { HAL_SimDeviceHandle m_handle = HAL_kInvalidHandle; }; -} // namespace hal +} // namespace wpi::hal #endif // __cplusplus diff --git a/hal/src/main/native/include/wpi/hal/Types.h b/hal/src/main/native/include/wpi/hal/Types.h index 2cc2fa3b83..f3c7718ab8 100644 --- a/hal/src/main/native/include/wpi/hal/Types.h +++ b/hal/src/main/native/include/wpi/hal/Types.h @@ -88,7 +88,7 @@ typedef int32_t HAL_Bool; #define HAL_ENUM(name) HAL_ENUM_WITH_UNDERLYING_TYPE(name, int32_t) #ifdef __cplusplus -namespace hal { +namespace wpi::hal { /** * A move-only C++ wrapper around a HAL handle. * Will free the handle if FreeFunction is provided @@ -137,6 +137,6 @@ class Handle { CType m_handle = CInvalid; }; -} // namespace hal +} // namespace wpi::hal #endif /** @} */ diff --git a/hal/src/main/native/include/wpi/hal/UsageReporting.h b/hal/src/main/native/include/wpi/hal/UsageReporting.h index ae007454ae..b9a24c9fb6 100644 --- a/hal/src/main/native/include/wpi/hal/UsageReporting.h +++ b/hal/src/main/native/include/wpi/hal/UsageReporting.h @@ -46,8 +46,8 @@ int32_t HAL_ReportUsage(const struct WPI_String* resource, */ inline int32_t HAL_ReportUsage(std::string_view resource, std::string_view data) { - WPI_String resourceStr = wpi::make_string(resource); - WPI_String dataStr = wpi::make_string(data); + WPI_String resourceStr = wpi::util::make_string(resource); + WPI_String dataStr = wpi::util::make_string(data); return HAL_ReportUsage(&resourceStr, &dataStr); } diff --git a/hal/src/main/native/include/wpi/hal/cpp/fpga_clock.h b/hal/src/main/native/include/wpi/hal/cpp/fpga_clock.h index 0f7bb75c57..42b2ba3bea 100644 --- a/hal/src/main/native/include/wpi/hal/cpp/fpga_clock.h +++ b/hal/src/main/native/include/wpi/hal/cpp/fpga_clock.h @@ -7,7 +7,7 @@ #include /** WPILib Hardware Abstraction Layer (HAL) namespace */ -namespace hal { +namespace wpi::hal { /** * A std::chrono compatible wrapper around the FPGA Timer. @@ -28,4 +28,4 @@ class fpga_clock { static const time_point min_time; }; -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/main/native/include/wpi/hal/handles/DigitalHandleResource.h b/hal/src/main/native/include/wpi/hal/handles/DigitalHandleResource.h index 1c7384f0ad..c5e9d85788 100644 --- a/hal/src/main/native/include/wpi/hal/handles/DigitalHandleResource.h +++ b/hal/src/main/native/include/wpi/hal/handles/DigitalHandleResource.h @@ -14,7 +14,7 @@ #include "wpi/hal/handles/HandlesInternal.h" #include "wpi/util/mutex.hpp" -namespace hal { +namespace wpi::hal { /** * The DigitalHandleResource class is a way to track handles. This version @@ -48,7 +48,7 @@ class DigitalHandleResource : public HandleBase { private: std::array, size> m_structures; - std::array m_handleMutexes; + std::array m_handleMutexes; }; template @@ -70,7 +70,7 @@ DigitalHandleResource::Allocate( } m_structures[index] = std::make_shared(); *handle = - static_cast(hal::createHandle(index, enumValue, m_version)); + static_cast(wpi::hal::createHandle(index, enumValue, m_version)); *status = HAL_SUCCESS; return m_structures[index]; } @@ -110,4 +110,4 @@ void DigitalHandleResource::ResetHandles() { } HandleBase::ResetHandles(); } -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/main/native/include/wpi/hal/handles/HandlesInternal.h b/hal/src/main/native/include/wpi/hal/handles/HandlesInternal.h index 58cc35f3cf..85e5e0c045 100644 --- a/hal/src/main/native/include/wpi/hal/handles/HandlesInternal.h +++ b/hal/src/main/native/include/wpi/hal/handles/HandlesInternal.h @@ -19,7 +19,7 @@ * always reserved for type and error handling. */ -namespace hal { +namespace wpi::hal { /** * Base for all HAL Handles. @@ -44,7 +44,7 @@ constexpr int16_t InvalidHandleIndex = -1; */ enum class HAL_HandleEnum { Undefined = 0, - DIO = wpi::kHandleTypeHALBase, + DIO = wpi::util::kHandleTypeHALBase, Port = 2, Notifier = 3, Interrupt = 4, @@ -165,4 +165,4 @@ inline int16_t getHandleTypedIndex(HAL_Handle handle, HAL_HandleEnum enumType, */ HAL_Handle createHandle(int16_t index, HAL_HandleEnum handleType, int16_t version); -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/main/native/include/wpi/hal/handles/IndexedClassedHandleResource.h b/hal/src/main/native/include/wpi/hal/handles/IndexedClassedHandleResource.h index 0666192e06..588484eca5 100644 --- a/hal/src/main/native/include/wpi/hal/handles/IndexedClassedHandleResource.h +++ b/hal/src/main/native/include/wpi/hal/handles/IndexedClassedHandleResource.h @@ -15,7 +15,7 @@ #include "wpi/hal/handles/HandlesInternal.h" #include "wpi/util/mutex.hpp" -namespace hal { +namespace wpi::hal { /** * The IndexedClassedHandleResource class is a way to track handles. This @@ -52,7 +52,7 @@ class IndexedClassedHandleResource : public HandleBase { private: std::array, size> m_structures; - std::array m_handleMutexes; + std::array m_handleMutexes; }; template ::Allocate( return HAL_kInvalidHandle; } m_structures[index] = toSet; - return static_cast(hal::createHandle(index, enumValue, m_version)); + return static_cast(wpi::hal::createHandle(index, enumValue, m_version)); } template , size> m_structures; - std::array m_handleMutexes; + std::array m_handleMutexes; }; template ::Allocate( } m_structures[index] = std::make_shared(); *handle = - static_cast(hal::createHandle(index, enumValue, m_version)); + static_cast(wpi::hal::createHandle(index, enumValue, m_version)); *status = HAL_SUCCESS; return m_structures[index]; } @@ -115,4 +115,4 @@ void IndexedHandleResource::ResetHandles() { } HandleBase::ResetHandles(); } -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/main/native/include/wpi/hal/handles/LimitedClassedHandleResource.h b/hal/src/main/native/include/wpi/hal/handles/LimitedClassedHandleResource.h index 3f6003243d..77dd4d2034 100644 --- a/hal/src/main/native/include/wpi/hal/handles/LimitedClassedHandleResource.h +++ b/hal/src/main/native/include/wpi/hal/handles/LimitedClassedHandleResource.h @@ -13,7 +13,7 @@ #include "wpi/hal/handles/HandlesInternal.h" #include "wpi/util/mutex.hpp" -namespace hal { +namespace wpi::hal { /** * The LimitedClassedHandleResource class is a way to track handles. This @@ -47,8 +47,8 @@ class LimitedClassedHandleResource : public HandleBase { private: std::array, size> m_structures; - std::array m_handleMutexes; - wpi::mutex m_allocateMutex; + std::array m_handleMutexes; + wpi::util::mutex m_allocateMutex; }; template , size> m_structures; - std::array m_handleMutexes; - wpi::mutex m_allocateMutex; + std::array m_handleMutexes; + wpi::util::mutex m_allocateMutex; }; template ::ResetHandles() { } HandleBase::ResetHandles(); } -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/main/native/include/wpi/hal/handles/UnlimitedHandleResource.h b/hal/src/main/native/include/wpi/hal/handles/UnlimitedHandleResource.h index c94beae210..ec21662bd5 100644 --- a/hal/src/main/native/include/wpi/hal/handles/UnlimitedHandleResource.h +++ b/hal/src/main/native/include/wpi/hal/handles/UnlimitedHandleResource.h @@ -14,7 +14,7 @@ #include "wpi/hal/handles/HandlesInternal.h" #include "wpi/util/mutex.hpp" -namespace hal { +namespace wpi::hal { /** * The UnlimitedHandleResource class is a way to track handles. This version @@ -56,7 +56,7 @@ class UnlimitedHandleResource : public HandleBase { private: std::vector> m_structures; - wpi::mutex m_handleMutex; + wpi::util::mutex m_handleMutex; }; template @@ -126,4 +126,4 @@ void UnlimitedHandleResource::ForEach( } } -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/main/native/include/wpi/hal/proto/ControlData.h b/hal/src/main/native/include/wpi/hal/proto/ControlData.h index 4afd22f2e1..a10e55e458 100644 --- a/hal/src/main/native/include/wpi/hal/proto/ControlData.h +++ b/hal/src/main/native/include/wpi/hal/proto/ControlData.h @@ -11,19 +11,19 @@ #include "wpi/util/protobuf/Protobuf.hpp" template <> -struct wpi::Protobuf { +struct wpi::util::Protobuf { using MessageStruct = mrc_proto_ProtobufControlData; - using InputStream = wpi::ProtoInputStream; - using OutputStream = wpi::ProtoOutputStream; + using InputStream = wpi::util::ProtoInputStream; + using OutputStream = wpi::util::ProtoOutputStream; static std::optional Unpack(InputStream& Stream); static bool Pack(OutputStream& Stream, const mrc::ControlData& Value); }; template <> -struct wpi::Protobuf { +struct wpi::util::Protobuf { using MessageStruct = mrc_proto_ProtobufJoystickData; - using InputStream = wpi::ProtoInputStream; - using OutputStream = wpi::ProtoOutputStream; + using InputStream = wpi::util::ProtoInputStream; + using OutputStream = wpi::util::ProtoOutputStream; static std::optional Unpack(InputStream& Stream); static bool Pack(OutputStream& Stream, const mrc::Joystick& Value); }; diff --git a/hal/src/main/native/include/wpi/hal/proto/ErrorInfo.h b/hal/src/main/native/include/wpi/hal/proto/ErrorInfo.h index 59db959785..b65285e137 100644 --- a/hal/src/main/native/include/wpi/hal/proto/ErrorInfo.h +++ b/hal/src/main/native/include/wpi/hal/proto/ErrorInfo.h @@ -11,10 +11,10 @@ #include "wpi/util/protobuf/Protobuf.hpp" template <> -struct wpi::Protobuf { +struct wpi::util::Protobuf { using MessageStruct = mrc_proto_ProtobufErrorInfo; - using InputStream = wpi::ProtoInputStream; - using OutputStream = wpi::ProtoOutputStream; + using InputStream = wpi::util::ProtoInputStream; + using OutputStream = wpi::util::ProtoOutputStream; static std::optional Unpack(InputStream& Stream); static bool Pack(OutputStream& Stream, const mrc::ErrorInfo& Value); }; diff --git a/hal/src/main/native/include/wpi/hal/proto/JoystickDescriptor.h b/hal/src/main/native/include/wpi/hal/proto/JoystickDescriptor.h index 14fc86f238..5ee881cfdc 100644 --- a/hal/src/main/native/include/wpi/hal/proto/JoystickDescriptor.h +++ b/hal/src/main/native/include/wpi/hal/proto/JoystickDescriptor.h @@ -11,10 +11,10 @@ #include "wpi/util/protobuf/Protobuf.hpp" template <> -struct wpi::Protobuf { +struct wpi::util::Protobuf { using MessageStruct = mrc_proto_ProtobufJoystickDescriptor; - using InputStream = wpi::ProtoInputStream; - using OutputStream = wpi::ProtoOutputStream; + using InputStream = wpi::util::ProtoInputStream; + using OutputStream = wpi::util::ProtoOutputStream; static std::optional Unpack(InputStream& Stream); static bool Pack(OutputStream& Stream, const mrc::JoystickDescriptor& Value); }; diff --git a/hal/src/main/native/include/wpi/hal/proto/JoystickRumbleData.h b/hal/src/main/native/include/wpi/hal/proto/JoystickRumbleData.h index 4a7b9b1ff1..fa81d7824a 100644 --- a/hal/src/main/native/include/wpi/hal/proto/JoystickRumbleData.h +++ b/hal/src/main/native/include/wpi/hal/proto/JoystickRumbleData.h @@ -11,10 +11,10 @@ #include "wpi/util/protobuf/Protobuf.hpp" template <> -struct wpi::Protobuf { +struct wpi::util::Protobuf { using MessageStruct = mrc_proto_ProtobufJoystickRumbleData; - using InputStream = wpi::ProtoInputStream; - using OutputStream = wpi::ProtoOutputStream; + using InputStream = wpi::util::ProtoInputStream; + using OutputStream = wpi::util::ProtoOutputStream; static std::optional Unpack(InputStream& Stream); static bool Pack(OutputStream& Stream, const mrc::JoystickRumbleData& Value); }; diff --git a/hal/src/main/native/include/wpi/hal/proto/MatchInfo.h b/hal/src/main/native/include/wpi/hal/proto/MatchInfo.h index da54907ee0..23c25fd84b 100644 --- a/hal/src/main/native/include/wpi/hal/proto/MatchInfo.h +++ b/hal/src/main/native/include/wpi/hal/proto/MatchInfo.h @@ -11,10 +11,10 @@ #include "wpi/util/protobuf/Protobuf.hpp" template <> -struct wpi::Protobuf { +struct wpi::util::Protobuf { using MessageStruct = mrc_proto_ProtobufMatchInfo; - using InputStream = wpi::ProtoInputStream; - using OutputStream = wpi::ProtoOutputStream; + using InputStream = wpi::util::ProtoInputStream; + using OutputStream = wpi::util::ProtoOutputStream; static std::optional Unpack(InputStream& Stream); static bool Pack(OutputStream& Stream, const mrc::MatchInfo& Value); }; diff --git a/hal/src/main/native/include/wpi/hal/proto/OpMode.h b/hal/src/main/native/include/wpi/hal/proto/OpMode.h index 477af5c73e..b3b0b8be2f 100644 --- a/hal/src/main/native/include/wpi/hal/proto/OpMode.h +++ b/hal/src/main/native/include/wpi/hal/proto/OpMode.h @@ -13,19 +13,19 @@ #include "wpi/util/protobuf/Protobuf.hpp" template <> -struct wpi::Protobuf { +struct wpi::util::Protobuf { using MessageStruct = mrc_proto_ProtobufOpMode; - using InputStream = wpi::ProtoInputStream; - using OutputStream = wpi::ProtoOutputStream; + using InputStream = wpi::util::ProtoInputStream; + using OutputStream = wpi::util::ProtoOutputStream; static std::optional Unpack(InputStream& Stream); static bool Pack(OutputStream& Stream, const mrc::OpMode& Value); }; template <> -struct wpi::Protobuf> { +struct wpi::util::Protobuf> { using MessageStruct = mrc_proto_ProtobufAvailableOpModes; - using InputStream = wpi::ProtoInputStream>; - using OutputStream = wpi::ProtoOutputStream>; + using InputStream = wpi::util::ProtoInputStream>; + using OutputStream = wpi::util::ProtoOutputStream>; static std::optional> Unpack(InputStream& Stream); static bool Pack(OutputStream& Stream, const std::vector& Value); }; diff --git a/hal/src/main/native/include/wpi/hal/proto/VersionInfo.h b/hal/src/main/native/include/wpi/hal/proto/VersionInfo.h index 4072c1c08c..afd45bc731 100644 --- a/hal/src/main/native/include/wpi/hal/proto/VersionInfo.h +++ b/hal/src/main/native/include/wpi/hal/proto/VersionInfo.h @@ -11,10 +11,10 @@ #include "wpi/util/protobuf/Protobuf.hpp" template <> -struct wpi::Protobuf { +struct wpi::util::Protobuf { using MessageStruct = mrc_proto_ProtobufVersionInfo; - using InputStream = wpi::ProtoInputStream; - using OutputStream = wpi::ProtoOutputStream; + using InputStream = wpi::util::ProtoInputStream; + using OutputStream = wpi::util::ProtoOutputStream; static std::optional Unpack(InputStream& Stream); static bool Pack(OutputStream& Stream, const mrc::VersionInfo& Value); }; diff --git a/hal/src/main/native/include/wpi/hal/simulation/NotifyListener.h b/hal/src/main/native/include/wpi/hal/simulation/NotifyListener.h index ca2579234f..a2b3e18ffb 100644 --- a/hal/src/main/native/include/wpi/hal/simulation/NotifyListener.h +++ b/hal/src/main/native/include/wpi/hal/simulation/NotifyListener.h @@ -18,7 +18,7 @@ typedef void (*HAL_ConstBufferCallback)(const char* name, void* param, #ifdef __cplusplus -namespace hal { +namespace wpi::hal { template struct HalCallbackListener { @@ -32,6 +32,6 @@ struct HalCallbackListener { void* param = nullptr; }; -} // namespace hal +} // namespace wpi::hal #endif diff --git a/hal/src/main/native/include/wpi/hal/simulation/SimCallbackRegistry.h b/hal/src/main/native/include/wpi/hal/simulation/SimCallbackRegistry.h index b3d9b00e54..867c7caa2c 100644 --- a/hal/src/main/native/include/wpi/hal/simulation/SimCallbackRegistry.h +++ b/hal/src/main/native/include/wpi/hal/simulation/SimCallbackRegistry.h @@ -12,7 +12,7 @@ #include "wpi/util/UidVector.hpp" #include "wpi/util/spinlock.hpp" -namespace hal { +namespace wpi::hal { namespace impl { @@ -21,7 +21,7 @@ class SimCallbackRegistryBase { using RawFunctor = void (*)(); protected: - using CallbackVector = wpi::UidVector, 4>; + using CallbackVector = wpi::util::UidVector, 4>; public: void Cancel(int32_t uid) { @@ -36,7 +36,7 @@ class SimCallbackRegistryBase { DoReset(); } - wpi::recursive_spinlock& GetMutex() { return m_mutex; } + wpi::util::recursive_spinlock& GetMutex() { return m_mutex; } protected: int32_t DoRegister(RawFunctor callback, void* param) { @@ -56,7 +56,7 @@ class SimCallbackRegistryBase { } } - mutable wpi::recursive_spinlock m_mutex; + mutable wpi::util::recursive_spinlock m_mutex; std::unique_ptr m_callbacks; }; @@ -191,4 +191,4 @@ class SimCallbackRegistry : public impl::SimCallbackRegistryBase { \ void NS##_Cancel##CAPINAME##Callback(int32_t uid) {} -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/main/native/include/wpi/hal/simulation/SimDataValue.h b/hal/src/main/native/include/wpi/hal/simulation/SimDataValue.h index 9d62f03a2a..85daa674fb 100644 --- a/hal/src/main/native/include/wpi/hal/simulation/SimDataValue.h +++ b/hal/src/main/native/include/wpi/hal/simulation/SimDataValue.h @@ -12,7 +12,7 @@ #include "wpi/util/UidVector.hpp" #include "wpi/util/spinlock.hpp" -namespace hal { +namespace wpi::hal { namespace impl { template @@ -35,7 +35,7 @@ class SimDataValueBase : protected SimCallbackRegistryBase { m_value = value; } - wpi::recursive_spinlock& GetMutex() { return m_mutex; } + wpi::util::recursive_spinlock& GetMutex() { return m_mutex; } protected: int32_t DoRegisterCallback(HAL_NotifyCallback callback, void* param, @@ -333,4 +333,4 @@ class SimDataValue final : public impl::SimDataValueBase { \ void NS##_Set##CAPINAME(TYPE) {} -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/main/native/sim/AddressableLED.cpp b/hal/src/main/native/sim/AddressableLED.cpp index 8856e7438b..9173d7f1bc 100644 --- a/hal/src/main/native/sim/AddressableLED.cpp +++ b/hal/src/main/native/sim/AddressableLED.cpp @@ -15,20 +15,20 @@ #include "wpi/hal/handles/HandlesInternal.h" #include "wpi/hal/handles/IndexedHandleResource.h" -using namespace hal; +using namespace wpi::hal; -namespace hal::init { +namespace wpi::hal::init { void InitializeAddressableLED() {} -} // namespace hal::init +} // namespace wpi::hal::init extern "C" { HAL_AddressableLEDHandle HAL_InitializeAddressableLED( int32_t channel, const char* allocationLocation, int32_t* status) { - hal::init::CheckInit(); + wpi::hal::init::CheckInit(); if (channel < 0 || channel >= kNumAddressableLEDs) { *status = RESOURCE_OUT_OF_RANGE; - hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for AddressableLED", + wpi::hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for AddressableLED", 0, kNumAddressableLEDs, channel); return HAL_kInvalidHandle; } @@ -40,10 +40,10 @@ HAL_AddressableLEDHandle HAL_InitializeAddressableLED( if (*status != 0) { if (port) { - hal::SetLastErrorPreviouslyAllocated(status, "PWM or DIO", channel, + wpi::hal::SetLastErrorPreviouslyAllocated(status, "PWM or DIO", channel, port->previousAllocation); } else { - hal::SetLastErrorIndexOutOfRange(status, + wpi::hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for AddressableLED", 0, kNumAddressableLEDs, channel); } @@ -81,7 +81,7 @@ void HAL_SetAddressableLEDStart(HAL_AddressableLEDHandle handle, int32_t start, } if (start > HAL_kAddressableLEDMaxLength || start < 0) { *status = PARAMETER_OUT_OF_RANGE; - hal::SetLastError( + wpi::hal::SetLastError( status, fmt::format( "LED start must be less than or equal to {}. {} was requested", @@ -101,7 +101,7 @@ void HAL_SetAddressableLEDLength(HAL_AddressableLEDHandle handle, } if (length > HAL_kAddressableLEDMaxLength || length < 0) { *status = PARAMETER_OUT_OF_RANGE; - hal::SetLastError( + wpi::hal::SetLastError( status, fmt::format( "LED length must be less than or equal to {}. {} was requested", diff --git a/hal/src/main/native/sim/AnalogInput.cpp b/hal/src/main/native/sim/AnalogInput.cpp index ca4e5ec81d..bb4e4e14f2 100644 --- a/hal/src/main/native/sim/AnalogInput.cpp +++ b/hal/src/main/native/sim/AnalogInput.cpp @@ -11,19 +11,19 @@ #include "mockdata/AnalogInDataInternal.h" #include "wpi/hal/handles/HandlesInternal.h" -using namespace hal; +using namespace wpi::hal; -namespace hal::init { +namespace wpi::hal::init { void InitializeAnalogInput() {} -} // namespace hal::init +} // namespace wpi::hal::init extern "C" { HAL_AnalogInputHandle HAL_InitializeAnalogInputPort( int32_t channel, const char* allocationLocation, int32_t* status) { - hal::init::CheckInit(); + wpi::hal::init::CheckInit(); if (channel < 0 || channel >= kNumAnalogInputs) { *status = RESOURCE_OUT_OF_RANGE; - hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for Analog Input", + wpi::hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for Analog Input", 0, kNumAnalogInputs, channel); return HAL_kInvalidHandle; } @@ -33,10 +33,10 @@ HAL_AnalogInputHandle HAL_InitializeAnalogInputPort( if (*status != 0) { if (analog_port) { - hal::SetLastErrorPreviouslyAllocated(status, "Analog Input", channel, + wpi::hal::SetLastErrorPreviouslyAllocated(status, "Analog Input", channel, analog_port->previousAllocation); } else { - hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for Analog Input", + wpi::hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for Analog Input", 0, kNumAnalogInputs, channel); } return HAL_kInvalidHandle; // failed to allocate. Pass error back. diff --git a/hal/src/main/native/sim/AnalogInternal.cpp b/hal/src/main/native/sim/AnalogInternal.cpp index e8d25b147d..7b692a9db5 100644 --- a/hal/src/main/native/sim/AnalogInternal.cpp +++ b/hal/src/main/native/sim/AnalogInternal.cpp @@ -7,16 +7,16 @@ #include "PortsInternal.h" #include "wpi/hal/handles/IndexedHandleResource.h" -namespace hal { -IndexedHandleResource* analogInputHandles; -} // namespace hal +} // namespace wpi::hal -namespace hal::init { +namespace wpi::hal::init { void InitializeAnalogInternal() { - static IndexedHandleResource aiH; analogInputHandles = &aiH; } -} // namespace hal::init +} // namespace wpi::hal::init diff --git a/hal/src/main/native/sim/AnalogInternal.h b/hal/src/main/native/sim/AnalogInternal.h index ed524bd6e7..e110fb174b 100644 --- a/hal/src/main/native/sim/AnalogInternal.h +++ b/hal/src/main/native/sim/AnalogInternal.h @@ -12,7 +12,7 @@ #include "wpi/hal/handles/HandlesInternal.h" #include "wpi/hal/handles/IndexedHandleResource.h" -namespace hal { +namespace wpi::hal { constexpr int32_t kTimebase = 40000000; ///< 40 MHz clock constexpr int32_t kDefaultOversampleBits = 0; constexpr int32_t kDefaultAverageBits = 7; @@ -25,7 +25,7 @@ struct AnalogPort { std::string previousAllocation; }; -extern IndexedHandleResource* analogInputHandles; -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/main/native/sim/CAN.cpp b/hal/src/main/native/sim/CAN.cpp index 880a4feed3..d7ad4c8e02 100644 --- a/hal/src/main/native/sim/CAN.cpp +++ b/hal/src/main/native/sim/CAN.cpp @@ -6,11 +6,11 @@ #include "mockdata/CanDataInternal.h" -using namespace hal; +using namespace wpi::hal; -namespace hal::init { +namespace wpi::hal::init { void InitializeCAN() {} -} // namespace hal::init +} // namespace wpi::hal::init extern "C" { diff --git a/hal/src/main/native/sim/CANAPI.cpp b/hal/src/main/native/sim/CANAPI.cpp index 901899e5e2..fb861c3a60 100644 --- a/hal/src/main/native/sim/CANAPI.cpp +++ b/hal/src/main/native/sim/CANAPI.cpp @@ -16,7 +16,7 @@ #include "wpi/util/mutex.hpp" #include "wpi/util/timestamp.h" -using namespace hal; +using namespace wpi::hal; namespace { struct CANStorage { @@ -24,17 +24,17 @@ struct CANStorage { HAL_CANDeviceType deviceType; int32_t busId; uint8_t deviceId; - wpi::mutex periodicSendsMutex; - wpi::SmallDenseMap periodicSends; - wpi::mutex receivesMutex; - wpi::SmallDenseMap receives; + wpi::util::mutex periodicSendsMutex; + wpi::util::SmallDenseMap periodicSends; + wpi::util::mutex receivesMutex; + wpi::util::SmallDenseMap receives; }; } // namespace static UnlimitedHandleResource* canHandles; -namespace hal { +namespace wpi::hal { namespace init { void InitializeCANAPI() { static UnlimitedHandleResource @@ -52,7 +52,7 @@ int32_t GetCANModuleFromHandle(HAL_CANHandle handle, int32_t* status) { return can->deviceId; } } // namespace can -} // namespace hal +} // namespace wpi::hal static int32_t CreateCANId(CANStorage* storage, int32_t apiId) { int32_t createdId = 0; @@ -68,9 +68,9 @@ extern "C" { HAL_CANHandle HAL_InitializeCAN(int32_t busId, HAL_CANManufacturer manufacturer, int32_t deviceId, HAL_CANDeviceType deviceType, int32_t* status) { - hal::init::CheckInit(); + wpi::hal::init::CheckInit(); - if (busId < 0 || busId > hal::kNumCanBuses) { + if (busId < 0 || busId > wpi::hal::kNumCanBuses) { *status = PARAMETER_OUT_OF_RANGE; return HAL_kInvalidHandle; } @@ -243,7 +243,7 @@ void HAL_ReadCANPacketTimeout(HAL_CANHandle handle, int32_t apiId, auto i = can->receives.find(messageId); if (i != can->receives.end()) { // Found, check if new enough - uint64_t now = wpi::Now(); + uint64_t now = wpi::util::Now(); if (now - i->second.timeStamp > (static_cast(timeoutMs) * 1000)) { // Timeout, return bad status diff --git a/hal/src/main/native/sim/CANAPIInternal.h b/hal/src/main/native/sim/CANAPIInternal.h index fdd6e6ad0c..3e11fea213 100644 --- a/hal/src/main/native/sim/CANAPIInternal.h +++ b/hal/src/main/native/sim/CANAPIInternal.h @@ -6,6 +6,6 @@ #include "wpi/hal/Types.h" -namespace hal::can { +namespace wpi::hal::can { int32_t GetCANModuleFromHandle(HAL_CANHandle handle, int32_t* status); -} // namespace hal::can +} // namespace wpi::hal::can diff --git a/hal/src/main/native/sim/CTREPCM.cpp b/hal/src/main/native/sim/CTREPCM.cpp index 121fc7ce12..2e56b0de99 100644 --- a/hal/src/main/native/sim/CTREPCM.cpp +++ b/hal/src/main/native/sim/CTREPCM.cpp @@ -13,12 +13,12 @@ #include "wpi/hal/Errors.h" #include "wpi/hal/handles/IndexedHandleResource.h" -using namespace hal; +using namespace wpi::hal; namespace { struct PCM { int32_t module; - wpi::mutex lock; + wpi::util::mutex lock; std::string previousAllocation; }; } // namespace @@ -26,29 +26,29 @@ struct PCM { static IndexedHandleResource* pcmHandles; -namespace hal::init { +namespace wpi::hal::init { void InitializeCTREPCM() { static IndexedHandleResource pH; pcmHandles = &pH; } -} // namespace hal::init +} // namespace wpi::hal::init HAL_CTREPCMHandle HAL_InitializeCTREPCM(int32_t busId, int32_t module, const char* allocationLocation, int32_t* status) { - hal::init::CheckInit(); + wpi::hal::init::CheckInit(); HAL_CTREPCMHandle handle; auto pcm = pcmHandles->Allocate(module, &handle, status); if (*status != 0) { if (pcm) { - hal::SetLastErrorPreviouslyAllocated(status, "CTRE PCM", module, + wpi::hal::SetLastErrorPreviouslyAllocated(status, "CTRE PCM", module, pcm->previousAllocation); } else { - hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for CTRE PCM", 0, + wpi::hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for CTRE PCM", 0, kNumCTREPCMModules - 1, module); } return HAL_kInvalidHandle; // failed to allocate. Pass error back. diff --git a/hal/src/main/native/sim/Constants.cpp b/hal/src/main/native/sim/Constants.cpp index d52692612a..795544e637 100644 --- a/hal/src/main/native/sim/Constants.cpp +++ b/hal/src/main/native/sim/Constants.cpp @@ -6,11 +6,11 @@ #include "ConstantsInternal.h" -using namespace hal; +using namespace wpi::hal; -namespace hal::init { +namespace wpi::hal::init { void InitializeConstants() {} -} // namespace hal::init +} // namespace wpi::hal::init extern "C" { int32_t HAL_GetSystemClockTicksPerMicrosecond(void) { diff --git a/hal/src/main/native/sim/ConstantsInternal.h b/hal/src/main/native/sim/ConstantsInternal.h index f4af049d4f..1afdd66979 100644 --- a/hal/src/main/native/sim/ConstantsInternal.h +++ b/hal/src/main/native/sim/ConstantsInternal.h @@ -6,6 +6,6 @@ #include -namespace hal { +namespace wpi::hal { constexpr int32_t kSystemClockTicksPerMicrosecond = 40; -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/main/native/sim/Counter.cpp b/hal/src/main/native/sim/Counter.cpp index 96760dd1f6..a146e1859a 100644 --- a/hal/src/main/native/sim/Counter.cpp +++ b/hal/src/main/native/sim/Counter.cpp @@ -10,26 +10,26 @@ #include "wpi/hal/handles/HandlesInternal.h" #include "wpi/hal/handles/LimitedHandleResource.h" -namespace hal { +namespace wpi::hal { LimitedHandleResource* counterHandles; -} // namespace hal +} // namespace wpi::hal -namespace hal::init { +namespace wpi::hal::init { void InitializeCounter() { static LimitedHandleResource cH; counterHandles = &cH; } -} // namespace hal::init +} // namespace wpi::hal::init extern "C" { HAL_CounterHandle HAL_InitializeCounter(int channel, HAL_Bool risingEdge, const char* allocationLocation, int32_t* status) { - hal::init::CheckInit(); + wpi::hal::init::CheckInit(); return 0; } void HAL_FreeCounter(HAL_CounterHandle counterHandle) {} diff --git a/hal/src/main/native/sim/CounterInternal.h b/hal/src/main/native/sim/CounterInternal.h index f34bb28c6d..c779483b1f 100644 --- a/hal/src/main/native/sim/CounterInternal.h +++ b/hal/src/main/native/sim/CounterInternal.h @@ -8,7 +8,7 @@ #include "wpi/hal/handles/HandlesInternal.h" #include "wpi/hal/handles/LimitedHandleResource.h" -namespace hal { +namespace wpi::hal { struct Counter { uint8_t index; @@ -17,4 +17,4 @@ struct Counter { extern LimitedHandleResource* counterHandles; -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/main/native/sim/DIO.cpp b/hal/src/main/native/sim/DIO.cpp index 458f629f7a..9321ef9cc2 100644 --- a/hal/src/main/native/sim/DIO.cpp +++ b/hal/src/main/native/sim/DIO.cpp @@ -13,13 +13,13 @@ #include "wpi/hal/handles/HandlesInternal.h" #include "wpi/hal/handles/LimitedHandleResource.h" -using namespace hal; +using namespace wpi::hal; static LimitedHandleResource* digitalPWMHandles; -namespace hal::init { +namespace wpi::hal::init { void InitializeDIO() { static LimitedHandleResource= kNumDigitalChannels) { *status = RESOURCE_OUT_OF_RANGE; - hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for DIO", 0, + wpi::hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for DIO", 0, kNumDigitalChannels, channel); return HAL_kInvalidHandle; } @@ -50,10 +50,10 @@ HAL_DigitalHandle HAL_InitializeDIOPort(int32_t channel, HAL_Bool input, if (*status != 0) { if (port) { - hal::SetLastErrorPreviouslyAllocated(status, "PWM or DIO", channel, + wpi::hal::SetLastErrorPreviouslyAllocated(status, "PWM or DIO", channel, port->previousAllocation); } else { - hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for DIO", 0, + wpi::hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for DIO", 0, kNumDigitalChannels, channel); } return HAL_kInvalidHandle; // failed to allocate. Pass error back. @@ -190,7 +190,7 @@ void HAL_SetDIO(HAL_DigitalHandle dioPortHandle, HAL_Bool value, } if (SimDIOData[port->channel].isInput) { *status = PARAMETER_OUT_OF_RANGE; - hal::SetLastError(status, "Cannot set output of an input channel"); + wpi::hal::SetLastError(status, "Cannot set output of an input channel"); return; } SimDIOData[port->channel].value = value; diff --git a/hal/src/main/native/sim/DigitalInternal.cpp b/hal/src/main/native/sim/DigitalInternal.cpp index 3f9569a679..5fd9c75390 100644 --- a/hal/src/main/native/sim/DigitalInternal.cpp +++ b/hal/src/main/native/sim/DigitalInternal.cpp @@ -9,7 +9,7 @@ #include "wpi/hal/handles/DigitalHandleResource.h" #include "wpi/hal/handles/HandlesInternal.h" -namespace hal { +namespace wpi::hal { DigitalHandleResource* @@ -45,4 +45,4 @@ int32_t GetDigitalInputChannel(HAL_DigitalHandle handle, int32_t* status) { return digital->channel; } -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/main/native/sim/DigitalInternal.h b/hal/src/main/native/sim/DigitalInternal.h index 015f5a5d81..1be867bf96 100644 --- a/hal/src/main/native/sim/DigitalInternal.h +++ b/hal/src/main/native/sim/DigitalInternal.h @@ -11,7 +11,7 @@ #include "PortsInternal.h" #include "wpi/hal/handles/DigitalHandleResource.h" -namespace hal { +namespace wpi::hal { /** * MXP channels when used as digital output PWM are offset from actual value */ @@ -57,4 +57,4 @@ int32_t remapMXPChannel(int32_t channel); int32_t remapMXPPWMChannel(int32_t channel); int32_t GetDigitalInputChannel(HAL_DigitalHandle handle, int32_t* status); -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/main/native/sim/DriverStation.cpp b/hal/src/main/native/sim/DriverStation.cpp index e2011d52e3..40b3a7e231 100644 --- a/hal/src/main/native/sim/DriverStation.cpp +++ b/hal/src/main/native/sim/DriverStation.cpp @@ -25,12 +25,12 @@ #include "wpi/util/condition_variable.hpp" #include "wpi/util/mutex.hpp" -static wpi::mutex msgMutex; +static wpi::util::mutex msgMutex; static std::atomic sendErrorHandler{nullptr}; static std::atomic sendConsoleLineHandler{ nullptr}; -using namespace hal; +using namespace wpi::hal; static constexpr int kJoystickPorts = 6; @@ -53,9 +53,9 @@ static std::atomic_bool gShutdown{false}; struct FRCDriverStation { ~FRCDriverStation() { gShutdown = true; } - wpi::EventVector newDataEvents; - wpi::mutex cacheMutex; - wpi::mutex tcpCacheMutex; + wpi::util::EventVector newDataEvents; + wpi::util::mutex cacheMutex; + wpi::util::mutex tcpCacheMutex; }; } // namespace @@ -116,21 +116,21 @@ void TcpCache::Update() { static ::FRCDriverStation* driverStation; -namespace hal::init { +namespace wpi::hal::init { void InitializeDriverStation() { static FRCDriverStation ds; driverStation = &ds; } -} // namespace hal::init +} // namespace wpi::hal::init -namespace hal { +namespace wpi::hal { static void DefaultPrintErrorImpl(const char* line, size_t size) { std::fwrite(line, size, 1, stderr); } -} // namespace hal +} // namespace wpi::hal static std::atomic gPrintErrorImpl{ - hal::DefaultPrintErrorImpl}; + wpi::hal::DefaultPrintErrorImpl}; extern "C" { @@ -205,7 +205,7 @@ int32_t HAL_SendError(HAL_Bool isError, int32_t errorCode, HAL_Bool isLVCode, } void HAL_SetPrintErrorImpl(void (*func)(const char* line, size_t size)) { - gPrintErrorImpl.store(func ? func : hal::DefaultPrintErrorImpl); + gPrintErrorImpl.store(func ? func : wpi::hal::DefaultPrintErrorImpl); } int32_t HAL_SendConsoleLine(const char* line) { @@ -404,7 +404,7 @@ void HAL_ProvideNewDataEventHandle(WPI_EventHandle handle) { if (gShutdown) { return; } - hal::init::CheckInit(); + wpi::hal::init::CheckInit(); driverStation->newDataEvents.Add(handle); } @@ -425,7 +425,7 @@ HAL_Bool HAL_GetOutputsEnabled(void) { } // extern "C" -namespace hal { +namespace wpi::hal { void NewDriverStationData() { if (gShutdown) { return; @@ -451,4 +451,4 @@ void NewDriverStationData() { void InitializeDriverStation() { SimDriverStationData->ResetData(); } -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/main/native/sim/DutyCycle.cpp b/hal/src/main/native/sim/DutyCycle.cpp index cff3f145cb..f44ee955fa 100644 --- a/hal/src/main/native/sim/DutyCycle.cpp +++ b/hal/src/main/native/sim/DutyCycle.cpp @@ -14,7 +14,7 @@ #include "wpi/hal/handles/HandlesInternal.h" #include "wpi/hal/handles/IndexedHandleResource.h" -using namespace hal; +using namespace wpi::hal; namespace { struct DutyCycle { @@ -27,30 +27,30 @@ struct Empty {}; static IndexedHandleResource* dutyCycleHandles; -namespace hal::init { +namespace wpi::hal::init { void InitializeDutyCycle() { static IndexedHandleResource dcH; dutyCycleHandles = &dcH; } -} // namespace hal::init +} // namespace wpi::hal::init extern "C" { HAL_DutyCycleHandle HAL_InitializeDutyCycle(int32_t channel, const char* allocationLocation, int32_t* status) { - hal::init::CheckInit(); + wpi::hal::init::CheckInit(); HAL_DutyCycleHandle handle = HAL_kInvalidHandle; auto dutyCycle = dutyCycleHandles->Allocate(channel, &handle, status); if (*status != 0) { if (dutyCycle) { - hal::SetLastErrorPreviouslyAllocated(status, "SmartIo", channel, + wpi::hal::SetLastErrorPreviouslyAllocated(status, "SmartIo", channel, dutyCycle->previousAllocation); } else { - hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for Duty Cycle", + wpi::hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for Duty Cycle", 0, kNumDutyCycles, channel); } return HAL_kInvalidHandle; // failed to allocate. Pass error back. diff --git a/hal/src/main/native/sim/Encoder.cpp b/hal/src/main/native/sim/Encoder.cpp index 45a7ad5d40..41f88704df 100644 --- a/hal/src/main/native/sim/Encoder.cpp +++ b/hal/src/main/native/sim/Encoder.cpp @@ -15,7 +15,7 @@ #include "wpi/hal/handles/HandlesInternal.h" #include "wpi/hal/handles/LimitedHandleResource.h" -using namespace hal; +using namespace wpi::hal; namespace { struct Encoder { @@ -36,7 +36,7 @@ static LimitedHandleResource* fpgaEncoderHandles; -namespace hal::init { +namespace wpi::hal::init { void InitializeEncoder() { static LimitedHandleResource @@ -48,9 +48,9 @@ void InitializeEncoder() { eH; encoderHandles = &eH; } -} // namespace hal::init +} // namespace wpi::hal::init -namespace hal { +namespace wpi::hal { bool GetEncoderBaseHandle(HAL_EncoderHandle handle, HAL_FPGAEncoderHandle* fpgaHandle, HAL_CounterHandle* counterHandle) { @@ -63,14 +63,14 @@ bool GetEncoderBaseHandle(HAL_EncoderHandle handle, *counterHandle = encoder->counterHandle; return true; } -} // namespace hal +} // namespace wpi::hal extern "C" { HAL_EncoderHandle HAL_InitializeEncoder(int32_t aChannel, int32_t bChannel, HAL_Bool reverseDirection, HAL_EncoderEncodingType encodingType, int32_t* status) { - hal::init::CheckInit(); + wpi::hal::init::CheckInit(); HAL_Handle nativeHandle = HAL_kInvalidHandle; if (encodingType == HAL_EncoderEncodingType::HAL_Encoder_k4X) { // k4x, allocate encoder @@ -272,7 +272,7 @@ void HAL_SetEncoderMinRate(HAL_EncoderHandle encoderHandle, double minRate, if (minRate == 0.0) { *status = PARAMETER_OUT_OF_RANGE; - hal::SetLastError(status, "minRate must not be 0"); + wpi::hal::SetLastError(status, "minRate must not be 0"); return; } @@ -289,7 +289,7 @@ void HAL_SetEncoderDistancePerPulse(HAL_EncoderHandle encoderHandle, if (distancePerPulse == 0.0) { *status = PARAMETER_OUT_OF_RANGE; - hal::SetLastError(status, "distancePerPulse must not be 0"); + wpi::hal::SetLastError(status, "distancePerPulse must not be 0"); return; } encoder->distancePerPulse = distancePerPulse; diff --git a/hal/src/main/native/sim/Extensions.cpp b/hal/src/main/native/sim/Extensions.cpp index ffb2ef3c86..5500515896 100644 --- a/hal/src/main/native/sim/Extensions.cpp +++ b/hal/src/main/native/sim/Extensions.cpp @@ -38,14 +38,14 @@ #define DLERROR dlerror() #endif -static wpi::recursive_spinlock gExtensionRegistryMutex; +static wpi::util::recursive_spinlock gExtensionRegistryMutex; static std::vector> gExtensionRegistry; static std::vector> gExtensionListeners; -namespace hal::init { +namespace wpi::hal::init { void InitializeExtensions() {} -} // namespace hal::init +} // namespace wpi::hal::init static bool& GetShowNotFoundMessage() { static bool showMsg = true; @@ -56,7 +56,7 @@ extern "C" { int HAL_LoadOneExtension(const char* library) { int rc = 1; // It is expected and reasonable not to find an extra simulation - wpi::print("HAL Extensions: Attempting to load: {}\n", + wpi::util::print("HAL Extensions: Attempting to load: {}\n", fs::path{library}.stem().string()); std::fflush(stdout); HTYPE handle = DLOPEN(library); @@ -67,14 +67,14 @@ int HAL_LoadOneExtension(const char* library) { #else auto libraryName = fmt::format("lib{}.so", library); #endif - wpi::print("HAL Extensions: Load failed: {}\nTrying modified name: {}\n", + wpi::util::print("HAL Extensions: Load failed: {}\nTrying modified name: {}\n", DLERROR, fs::path{libraryName}.stem().string()); std::fflush(stdout); handle = DLOPEN(libraryName.c_str()); } #endif if (!handle) { - wpi::print("HAL Extensions: Failed to load library: {}\n", DLERROR); + wpi::util::print("HAL Extensions: Failed to load library: {}\n", DLERROR); std::fflush(stdout); return rc; } @@ -107,7 +107,7 @@ int HAL_LoadExtensions(void) { } return rc; } - wpi::split(e, DELIM, -1, false, [&](auto library) { + wpi::util::split(e, DELIM, -1, false, [&](auto library) { if (rc >= 0) { rc = HAL_LoadOneExtension(std::string(library).c_str()); } diff --git a/hal/src/main/native/sim/HAL.cpp b/hal/src/main/native/sim/HAL.cpp index 1dd59a3d39..7dde70c872 100644 --- a/hal/src/main/native/sim/HAL.cpp +++ b/hal/src/main/native/sim/HAL.cpp @@ -32,7 +32,7 @@ NtQueryTimerResolution(PULONG MinimumResolution, PULONG MaximumResolution, #include "wpi/util/mutex.hpp" #include "wpi/util/spinlock.hpp" -using namespace hal; +using namespace wpi::hal; namespace { class SimPeriodicCallbackRegistry : public impl::SimCallbackRegistryBase { @@ -54,16 +54,16 @@ class SimPeriodicCallbackRegistry : public impl::SimCallbackRegistryBase { } // namespace static HAL_RuntimeType runtimeType{HAL_Runtime_Simulation}; -static wpi::spinlock gOnShutdownMutex; +static wpi::util::spinlock gOnShutdownMutex; static std::vector> gOnShutdown; static SimPeriodicCallbackRegistry gSimPeriodicBefore; static SimPeriodicCallbackRegistry gSimPeriodicAfter; -namespace hal { +namespace wpi::hal { void InitializeDriverStation(); -} // namespace hal +} // namespace wpi::hal -namespace hal::init { +namespace wpi::hal::init { void InitializeHAL() { InitializeAddressableLEDData(); InitializeAnalogInData(); @@ -107,7 +107,7 @@ void InitializeHAL() { InitializeSimDevice(); InitializeThreads(); } -} // namespace hal::init +} // namespace wpi::hal::init extern "C" { @@ -253,7 +253,7 @@ int32_t HAL_GetTeamNumber(void) { } uint64_t HAL_GetFPGATime(int32_t* status) { - return hal::GetFPGATime(); + return wpi::hal::GetFPGATime(); } uint64_t HAL_ExpandFPGATime(uint32_t unexpandedLower, int32_t* status) { @@ -302,7 +302,7 @@ HAL_Bool HAL_GetSystemTimeValid(int32_t* status) { HAL_Bool HAL_Initialize(int32_t timeout, int32_t mode) { static std::atomic_bool initialized{false}; - static wpi::mutex initializeMutex; + static wpi::util::mutex initializeMutex; // Initial check, as if it's true initialization has finished if (initialized) { return true; @@ -314,12 +314,12 @@ HAL_Bool HAL_Initialize(int32_t timeout, int32_t mode) { return true; } - hal::init::InitializeHAL(); + wpi::hal::init::InitializeHAL(); - hal::init::HAL_IsInitialized.store(true); + wpi::hal::init::HAL_IsInitialized.store(true); - hal::RestartTiming(); - hal::InitializeDriverStation(); + wpi::hal::RestartTiming(); + wpi::hal::InitializeDriverStation(); initialized = true; diff --git a/hal/src/main/native/sim/HALInitializer.cpp b/hal/src/main/native/sim/HALInitializer.cpp index 84ba73e6d4..4312571b81 100644 --- a/hal/src/main/native/sim/HALInitializer.cpp +++ b/hal/src/main/native/sim/HALInitializer.cpp @@ -6,9 +6,9 @@ #include "wpi/hal/HALBase.h" -namespace hal::init { +namespace wpi::hal::init { std::atomic_bool HAL_IsInitialized{false}; void RunInitialize() { HAL_Initialize(500, 0); } -} // namespace hal::init +} // namespace wpi::hal::init diff --git a/hal/src/main/native/sim/HALInitializer.h b/hal/src/main/native/sim/HALInitializer.h index 20779ff0f8..1336500b8d 100644 --- a/hal/src/main/native/sim/HALInitializer.h +++ b/hal/src/main/native/sim/HALInitializer.h @@ -6,7 +6,7 @@ #include -namespace hal::init { +namespace wpi::hal::init { extern std::atomic_bool HAL_IsInitialized; extern void RunInitialize(); inline void CheckInit() { @@ -59,4 +59,4 @@ extern void InitializeSerialPort(); extern void InitializeSimDevice(); extern void InitializeThreads(); -} // namespace hal::init +} // namespace wpi::hal::init diff --git a/hal/src/main/native/sim/HALInternal.h b/hal/src/main/native/sim/HALInternal.h index 7a7863a474..0023442999 100644 --- a/hal/src/main/native/sim/HALInternal.h +++ b/hal/src/main/native/sim/HALInternal.h @@ -8,7 +8,7 @@ #include -namespace hal { +namespace wpi::hal { void SetLastError(int32_t* status, std::string_view value); void SetLastErrorIndexOutOfRange(int32_t* status, std::string_view message, int32_t minimum, int32_t maximum, @@ -16,4 +16,4 @@ void SetLastErrorIndexOutOfRange(int32_t* status, std::string_view message, void SetLastErrorPreviouslyAllocated(int32_t* status, std::string_view message, int32_t channel, std::string_view previousAllocation); -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/main/native/sim/I2C.cpp b/hal/src/main/native/sim/I2C.cpp index 2fe7e2acb5..08e3d8914e 100644 --- a/hal/src/main/native/sim/I2C.cpp +++ b/hal/src/main/native/sim/I2C.cpp @@ -7,15 +7,15 @@ #include "HALInitializer.h" #include "mockdata/I2CDataInternal.h" -using namespace hal; +using namespace wpi::hal; -namespace hal::init { +namespace wpi::hal::init { void InitializeI2C() {} -} // namespace hal::init +} // namespace wpi::hal::init extern "C" { void HAL_InitializeI2C(HAL_I2CPort port, int32_t* status) { - hal::init::CheckInit(); + wpi::hal::init::CheckInit(); SimI2CData[port].initialized = true; } int32_t HAL_TransactionI2C(HAL_I2CPort port, int32_t deviceAddress, diff --git a/hal/src/main/native/sim/MockHooks.cpp b/hal/src/main/native/sim/MockHooks.cpp index 85f24d6347..5637866135 100644 --- a/hal/src/main/native/sim/MockHooks.cpp +++ b/hal/src/main/native/sim/MockHooks.cpp @@ -20,15 +20,15 @@ static std::atomic programStartTime{0}; static std::atomic programPauseTime{0}; static std::atomic programStepTime{0}; -namespace hal::init { +namespace wpi::hal::init { void InitializeMockHooks() { - wpi::SetNowImpl(GetFPGATime); + wpi::util::SetNowImpl(GetFPGATime); } -} // namespace hal::init +} // namespace wpi::hal::init -namespace hal { +namespace wpi::hal { void RestartTiming() { - programStartTime = wpi::NowDefault(); + programStartTime = wpi::util::NowDefault(); programStepTime = 0; if (programPauseTime != 0) { programPauseTime = programStartTime.load(); @@ -37,13 +37,13 @@ void RestartTiming() { void PauseTiming() { if (programPauseTime == 0) { - programPauseTime = wpi::NowDefault(); + programPauseTime = wpi::util::NowDefault(); } } void ResumeTiming() { if (programPauseTime != 0) { - programStartTime += wpi::NowDefault() - programPauseTime; + programStartTime += wpi::util::NowDefault() - programPauseTime; programPauseTime = 0; } } @@ -59,7 +59,7 @@ void StepTiming(uint64_t delta) { uint64_t GetFPGATime() { uint64_t curTime = programPauseTime; if (curTime == 0) { - curTime = wpi::NowDefault(); + curTime = wpi::util::NowDefault(); } return curTime + programStepTime - programStartTime; } @@ -74,16 +74,16 @@ void SetProgramStarted() { bool GetProgramStarted() { return programStarted; } -} // namespace hal +} // namespace wpi::hal -using namespace hal; +using namespace wpi::hal; extern "C" { void HALSIM_WaitForProgramStart(void) { int count = 0; while (!programStarted) { count++; - wpi::print("Waiting for program start signal: {}\n", count); + wpi::util::print("Waiting for program start signal: {}\n", count); std::this_thread::sleep_for(std::chrono::milliseconds(500)); } } diff --git a/hal/src/main/native/sim/MockHooksInternal.h b/hal/src/main/native/sim/MockHooksInternal.h index 101f42df39..fafe25e939 100644 --- a/hal/src/main/native/sim/MockHooksInternal.h +++ b/hal/src/main/native/sim/MockHooksInternal.h @@ -8,7 +8,7 @@ #include "wpi/hal/simulation/MockHooks.h" -namespace hal { +namespace wpi::hal { void RestartTiming(); void PauseTiming(); @@ -24,4 +24,4 @@ uint64_t GetFPGATime(); double GetFPGATimestamp(); void SetProgramStarted(); -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/main/native/sim/Notifier.cpp b/hal/src/main/native/sim/Notifier.cpp index fea0261a6a..6ff60fce8b 100644 --- a/hal/src/main/native/sim/Notifier.cpp +++ b/hal/src/main/native/sim/Notifier.cpp @@ -32,15 +32,15 @@ struct Notifier { bool waitTimeValid = false; // True if waitTime is set and in the future bool waitingForAlarm = false; // True if in HAL_WaitForNotifierAlarm() uint64_t waitCount = 0; // Counts calls to HAL_WaitForNotifierAlarm() - wpi::mutex mutex; - wpi::condition_variable cond; + wpi::util::mutex mutex; + wpi::util::condition_variable cond; }; } // namespace -using namespace hal; +using namespace wpi::hal; -static wpi::mutex notifiersWaiterMutex; -static wpi::condition_variable notifiersWaiterCond; +static wpi::util::mutex notifiersWaiterMutex; +static wpi::util::condition_variable notifiersWaiterCond; class NotifierHandleContainer : public UnlimitedHandleResource notifiersPaused{false}; -namespace hal { +namespace wpi::hal { namespace init { void InitializeNotifier() { static NotifierHandleContainer nH; @@ -87,7 +87,7 @@ void WakeupNotifiers() { void WaitNotifiers() { std::unique_lock ulock(notifiersWaiterMutex); - wpi::SmallVector waiters; + wpi::util::SmallVector waiters; // Wait for all Notifiers to hit HAL_WaitForNotifierAlarm() notifierHandles->ForEach([&](HAL_NotifierHandle handle, Notifier* notifier) { @@ -123,7 +123,7 @@ void WakeupWaitNotifiers() { std::unique_lock ulock(notifiersWaiterMutex); int32_t status = 0; uint64_t curTime = HAL_GetFPGATime(&status); - wpi::SmallVector, 8> waiters; + wpi::util::SmallVector, 8> waiters; // Wake up Notifiers that have expired timeouts notifierHandles->ForEach([&](HAL_NotifierHandle handle, Notifier* notifier) { @@ -161,12 +161,12 @@ void WakeupWaitNotifiers() { notifiersWaiterCond.wait_for(ulock, std::chrono::duration(1)); } } -} // namespace hal +} // namespace wpi::hal extern "C" { HAL_NotifierHandle HAL_InitializeNotifier(int32_t* status) { - hal::init::CheckInit(); + wpi::hal::init::CheckInit(); std::shared_ptr notifier = std::make_shared(); HAL_NotifierHandle handle = notifierHandles->Allocate(notifier); if (handle == HAL_kInvalidHandle) { @@ -318,7 +318,7 @@ int32_t HALSIM_GetNotifierInfo(struct HALSIM_NotifierInfo* arr, int32_t size) { if (num < size) { arr[num].handle = handle; if (notifier->name.empty()) { - wpi::format_to_n_c_str(arr[num].name, sizeof(arr[num].name), + wpi::util::format_to_n_c_str(arr[num].name, sizeof(arr[num].name), "Notifier{}", static_cast(getHandleIndex(handle))); } else { diff --git a/hal/src/main/native/sim/NotifierInternal.h b/hal/src/main/native/sim/NotifierInternal.h index 81d906e1f5..7c02082381 100644 --- a/hal/src/main/native/sim/NotifierInternal.h +++ b/hal/src/main/native/sim/NotifierInternal.h @@ -4,10 +4,10 @@ #pragma once -namespace hal { +namespace wpi::hal { void PauseNotifiers(); void ResumeNotifiers(); void WakeupNotifiers(); void WaitNotifiers(); void WakeupWaitNotifiers(); -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/main/native/sim/PWM.cpp b/hal/src/main/native/sim/PWM.cpp index 09209fd21b..fb15fafbd9 100644 --- a/hal/src/main/native/sim/PWM.cpp +++ b/hal/src/main/native/sim/PWM.cpp @@ -15,22 +15,22 @@ #include "mockdata/PWMDataInternal.h" #include "wpi/hal/handles/HandlesInternal.h" -using namespace hal; +using namespace wpi::hal; -namespace hal::init { +namespace wpi::hal::init { void InitializePWM() {} -} // namespace hal::init +} // namespace wpi::hal::init extern "C" { HAL_DigitalHandle HAL_InitializePWMPort(int32_t channel, const char* allocationLocation, int32_t* status) { - hal::init::CheckInit(); + wpi::hal::init::CheckInit(); if (channel < 0 || channel >= kNumPWMChannels) { *status = RESOURCE_OUT_OF_RANGE; - hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for PWM", 0, + wpi::hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for PWM", 0, kNumPWMChannels, channel); return HAL_kInvalidHandle; } @@ -50,10 +50,10 @@ HAL_DigitalHandle HAL_InitializePWMPort(int32_t channel, if (*status != 0) { if (port) { - hal::SetLastErrorPreviouslyAllocated(status, "PWM or DIO", channel, + wpi::hal::SetLastErrorPreviouslyAllocated(status, "PWM or DIO", channel, port->previousAllocation); } else { - hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for PWM", 0, + wpi::hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for PWM", 0, kNumPWMChannels, channel); } return HAL_kInvalidHandle; // failed to allocate. Pass error back. diff --git a/hal/src/main/native/sim/Ports.cpp b/hal/src/main/native/sim/Ports.cpp index d9f6288287..28eed2bc27 100644 --- a/hal/src/main/native/sim/Ports.cpp +++ b/hal/src/main/native/sim/Ports.cpp @@ -6,11 +6,11 @@ #include "PortsInternal.h" -using namespace hal; +using namespace wpi::hal; -namespace hal::init { +namespace wpi::hal::init { void InitializePorts() {} -} // namespace hal::init +} // namespace wpi::hal::init extern "C" { int32_t HAL_GetNumCanBuses(void) { diff --git a/hal/src/main/native/sim/PortsInternal.h b/hal/src/main/native/sim/PortsInternal.h index 3e1d5668ce..8a339392c3 100644 --- a/hal/src/main/native/sim/PortsInternal.h +++ b/hal/src/main/native/sim/PortsInternal.h @@ -6,7 +6,7 @@ #include -namespace hal { +namespace wpi::hal { constexpr int32_t kNumCanBuses = 5; constexpr int32_t kAccelerometers = 1; constexpr int32_t kNumAccumulators = 2; @@ -38,4 +38,4 @@ constexpr int32_t kNumREVPHChannels = 16; constexpr int32_t kSPIAccelerometers = 5; constexpr int32_t kSPIPorts = 5; -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/main/native/sim/Power.cpp b/hal/src/main/native/sim/Power.cpp index 4f0d2ac330..3434ed6b20 100644 --- a/hal/src/main/native/sim/Power.cpp +++ b/hal/src/main/native/sim/Power.cpp @@ -6,11 +6,11 @@ #include "mockdata/RoboRioDataInternal.h" -using namespace hal; +using namespace wpi::hal; -namespace hal::init { +namespace wpi::hal::init { void InitializePower() {} -} // namespace hal::init +} // namespace wpi::hal::init // TODO: Fix the naming in here extern "C" { diff --git a/hal/src/main/native/sim/PowerDistribution.cpp b/hal/src/main/native/sim/PowerDistribution.cpp index 8afcf6c3fc..7cb82517db 100644 --- a/hal/src/main/native/sim/PowerDistribution.cpp +++ b/hal/src/main/native/sim/PowerDistribution.cpp @@ -14,7 +14,7 @@ #include "wpi/hal/CANAPI.h" #include "wpi/hal/Errors.h" -using namespace hal; +using namespace wpi::hal; static constexpr HAL_CANManufacturer manufacturer = HAL_CANManufacturer::HAL_CAN_Man_kCTRE; @@ -22,9 +22,9 @@ static constexpr HAL_CANManufacturer manufacturer = static constexpr HAL_CANDeviceType deviceType = HAL_CANDeviceType::HAL_CAN_Dev_kPowerDistribution; -namespace hal::init { +namespace wpi::hal::init { void InitializePowerDistribution() {} -} // namespace hal::init +} // namespace wpi::hal::init extern "C" { HAL_PowerDistributionHandle HAL_InitializePowerDistribution( @@ -33,7 +33,7 @@ HAL_PowerDistributionHandle HAL_InitializePowerDistribution( if (type == HAL_PowerDistributionType_kAutomatic) { if (module != HAL_DEFAULT_POWER_DISTRIBUTION_MODULE) { *status = PARAMETER_OUT_OF_RANGE; - hal::SetLastError( + wpi::hal::SetLastError( status, "Automatic PowerDistributionType must have default module"); return HAL_kInvalidHandle; } @@ -46,15 +46,15 @@ HAL_PowerDistributionHandle HAL_InitializePowerDistribution( if (!HAL_CheckPowerDistributionModule(module, type)) { *status = RESOURCE_OUT_OF_RANGE; if (type == HAL_PowerDistributionType::HAL_PowerDistributionType_kCTRE) { - hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for CTRE PDP", 0, + wpi::hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for CTRE PDP", 0, kNumCTREPDPModules - 1, module); } else { - hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for REV PDH", 1, + wpi::hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for REV PDH", 1, kNumREVPDHModules, module); } return HAL_kInvalidHandle; } - hal::init::CheckInit(); + wpi::hal::init::CheckInit(); SimPowerDistributionData[module].initialized = true; auto handle = HAL_InitializeCAN(busId, manufacturer, module, deviceType, status); @@ -69,7 +69,7 @@ HAL_PowerDistributionHandle HAL_InitializePowerDistribution( int32_t HAL_GetPowerDistributionModuleNumber(HAL_PowerDistributionHandle handle, int32_t* status) { - auto module = hal::can::GetCANModuleFromHandle(handle, status); + auto module = wpi::hal::can::GetCANModuleFromHandle(handle, status); if (*status != 0) { return 0; } @@ -116,7 +116,7 @@ void HAL_CleanPowerDistribution(HAL_PowerDistributionHandle handle) { double HAL_GetPowerDistributionTemperature(HAL_PowerDistributionHandle handle, int32_t* status) { - auto module = hal::can::GetCANModuleFromHandle(handle, status); + auto module = wpi::hal::can::GetCANModuleFromHandle(handle, status); if (*status != 0) { return 0.0; } @@ -124,7 +124,7 @@ double HAL_GetPowerDistributionTemperature(HAL_PowerDistributionHandle handle, } double HAL_GetPowerDistributionVoltage(HAL_PowerDistributionHandle handle, int32_t* status) { - auto module = hal::can::GetCANModuleFromHandle(handle, status); + auto module = wpi::hal::can::GetCANModuleFromHandle(handle, status); if (*status != 0) { return 0.0; } @@ -132,7 +132,7 @@ double HAL_GetPowerDistributionVoltage(HAL_PowerDistributionHandle handle, } double HAL_GetPowerDistributionChannelCurrent( HAL_PowerDistributionHandle handle, int32_t channel, int32_t* status) { - auto module = hal::can::GetCANModuleFromHandle(handle, status); + auto module = wpi::hal::can::GetCANModuleFromHandle(handle, status); if (*status != 0) { return 0.0; } @@ -141,7 +141,7 @@ double HAL_GetPowerDistributionChannelCurrent( void HAL_GetPowerDistributionAllChannelCurrents( HAL_PowerDistributionHandle handle, double* currents, int32_t currentsLength, int32_t* status) { - auto module = hal::can::GetCANModuleFromHandle(handle, status); + auto module = wpi::hal::can::GetCANModuleFromHandle(handle, status); if (*status != 0) { return; } @@ -154,7 +154,7 @@ void HAL_GetPowerDistributionAllChannelCurrents( } double HAL_GetPowerDistributionTotalCurrent(HAL_PowerDistributionHandle handle, int32_t* status) { - auto module = hal::can::GetCANModuleFromHandle(handle, status); + auto module = wpi::hal::can::GetCANModuleFromHandle(handle, status); if (*status != 0) { return 0.0; } diff --git a/hal/src/main/native/sim/REVPH.cpp b/hal/src/main/native/sim/REVPH.cpp index 56967c84ea..c2f010d4e8 100644 --- a/hal/src/main/native/sim/REVPH.cpp +++ b/hal/src/main/native/sim/REVPH.cpp @@ -13,12 +13,12 @@ #include "wpi/hal/Errors.h" #include "wpi/hal/handles/IndexedHandleResource.h" -using namespace hal; +using namespace wpi::hal; namespace { struct PCM { int32_t module; - wpi::mutex lock; + wpi::util::mutex lock; std::string previousAllocation; }; } // namespace @@ -26,23 +26,23 @@ struct PCM { static IndexedHandleResource* pcmHandles; -namespace hal::init { +namespace wpi::hal::init { void InitializeREVPH() { static IndexedHandleResource pH; pcmHandles = &pH; } -} // namespace hal::init +} // namespace wpi::hal::init HAL_REVPHHandle HAL_InitializeREVPH(int32_t busId, int32_t module, const char* allocationLocation, int32_t* status) { - hal::init::CheckInit(); + wpi::hal::init::CheckInit(); if (!HAL_CheckREVPHModuleNumber(module)) { *status = RESOURCE_OUT_OF_RANGE; - hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for REV PH", 1, + wpi::hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for REV PH", 1, kNumREVPHModules, module); return HAL_kInvalidHandle; } @@ -53,10 +53,10 @@ HAL_REVPHHandle HAL_InitializeREVPH(int32_t busId, int32_t module, if (*status != 0) { if (pcm) { - hal::SetLastErrorPreviouslyAllocated(status, "REV PH", module, + wpi::hal::SetLastErrorPreviouslyAllocated(status, "REV PH", module, pcm->previousAllocation); } else { - hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for REV PH", 1, + wpi::hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for REV PH", 1, kNumREVPHModules, module); } return HAL_kInvalidHandle; // failed to allocate. Pass error back. diff --git a/hal/src/main/native/sim/SerialPort.cpp b/hal/src/main/native/sim/SerialPort.cpp index 4f160fb3de..03cfed6c96 100644 --- a/hal/src/main/native/sim/SerialPort.cpp +++ b/hal/src/main/native/sim/SerialPort.cpp @@ -6,21 +6,21 @@ #include "HALInitializer.h" -namespace hal::init { +namespace wpi::hal::init { void InitializeSerialPort() {} -} // namespace hal::init +} // namespace wpi::hal::init extern "C" { HAL_SerialPortHandle HAL_InitializeSerialPort(HAL_SerialPort port, int32_t* status) { - hal::init::CheckInit(); + wpi::hal::init::CheckInit(); return HAL_kInvalidHandle; } HAL_SerialPortHandle HAL_InitializeSerialPortDirect(HAL_SerialPort port, const char* portName, int32_t* status) { - hal::init::CheckInit(); + wpi::hal::init::CheckInit(); return HAL_kInvalidHandle; } diff --git a/hal/src/main/native/sim/SimDevice.cpp b/hal/src/main/native/sim/SimDevice.cpp index 2015aef602..9e646abea6 100644 --- a/hal/src/main/native/sim/SimDevice.cpp +++ b/hal/src/main/native/sim/SimDevice.cpp @@ -9,16 +9,16 @@ #include "HALInitializer.h" #include "mockdata/SimDeviceDataInternal.h" -using namespace hal; +using namespace wpi::hal; -namespace hal::init { +namespace wpi::hal::init { void InitializeSimDevice() {} -} // namespace hal::init +} // namespace wpi::hal::init extern "C" { HAL_SimDeviceHandle HAL_CreateSimDevice(const char* name) { - hal::init::CheckInit(); + wpi::hal::init::CheckInit(); return SimSimDeviceData->CreateDevice(name); } @@ -68,11 +68,11 @@ void HAL_ResetSimValue(HAL_SimValueHandle handle) { SimSimDeviceData->ResetValue(handle); } -hal::SimDevice::SimDevice(const char* name, int index) { +wpi::hal::SimDevice::SimDevice(const char* name, int index) { m_handle = HAL_CreateSimDevice(fmt::format("{}[{}]", name, index).c_str()); } -hal::SimDevice::SimDevice(const char* name, int index, int channel) { +wpi::hal::SimDevice::SimDevice(const char* name, int index, int channel) { m_handle = HAL_CreateSimDevice( fmt::format("{}[{},{}]", name, index, channel).c_str()); } diff --git a/hal/src/main/native/sim/Threads.cpp b/hal/src/main/native/sim/Threads.cpp index ce2db84690..bd982bdec6 100644 --- a/hal/src/main/native/sim/Threads.cpp +++ b/hal/src/main/native/sim/Threads.cpp @@ -4,9 +4,9 @@ #include "wpi/hal/Threads.h" -namespace hal::init { +namespace wpi::hal::init { void InitializeThreads() {} -} // namespace hal::init +} // namespace wpi::hal::init int32_t HAL_GetThreadPriority(NativeThreadHandle handle, HAL_Bool* isRealTime, int32_t* status) { diff --git a/hal/src/main/native/sim/mockdata/AddressableLEDData.cpp b/hal/src/main/native/sim/mockdata/AddressableLEDData.cpp index 2cd3bef3e7..2c080bf9c3 100644 --- a/hal/src/main/native/sim/mockdata/AddressableLEDData.cpp +++ b/hal/src/main/native/sim/mockdata/AddressableLEDData.cpp @@ -8,19 +8,19 @@ #include "../PortsInternal.h" #include "AddressableLEDDataInternal.h" -using namespace hal; +using namespace wpi::hal; -namespace hal::init { +namespace wpi::hal::init { void InitializeAddressableLEDData() { static AddressableLEDData sad[kNumAddressableLEDs]; - ::hal::SimAddressableLEDData = sad; + ::wpi::hal::SimAddressableLEDData = sad; static AddressableLEDDataBuffer buf; - ::hal::SimAddressableLEDDataBuffer = &buf; + ::wpi::hal::SimAddressableLEDDataBuffer = &buf; } -} // namespace hal::init +} // namespace wpi::hal::init -AddressableLEDData* hal::SimAddressableLEDData; -AddressableLEDDataBuffer* hal::SimAddressableLEDDataBuffer; +AddressableLEDData* wpi::hal::SimAddressableLEDData; +AddressableLEDDataBuffer* wpi::hal::SimAddressableLEDDataBuffer; void AddressableLEDData::ResetData() { initialized.Reset(false); diff --git a/hal/src/main/native/sim/mockdata/AddressableLEDDataInternal.h b/hal/src/main/native/sim/mockdata/AddressableLEDDataInternal.h index 2b217a1eca..b5ce234e52 100644 --- a/hal/src/main/native/sim/mockdata/AddressableLEDDataInternal.h +++ b/hal/src/main/native/sim/mockdata/AddressableLEDDataInternal.h @@ -11,7 +11,7 @@ #include "wpi/hal/simulation/SimDataValue.h" #include "wpi/util/spinlock.hpp" -namespace hal { +namespace wpi::hal { class AddressableLEDData { HAL_SIMDATAVALUE_DEFINE_NAME(Initialized) HAL_SIMDATAVALUE_DEFINE_NAME(Start) @@ -30,7 +30,7 @@ extern AddressableLEDData* SimAddressableLEDData; class AddressableLEDDataBuffer { HAL_SIMDATAVALUE_DEFINE_NAME(Data) - wpi::recursive_spinlock m_dataMutex; + wpi::util::recursive_spinlock m_dataMutex; HAL_AddressableLEDData m_data[HAL_kAddressableLEDMaxLength]; public: @@ -39,4 +39,4 @@ class AddressableLEDDataBuffer { SimCallbackRegistry data; }; extern AddressableLEDDataBuffer* SimAddressableLEDDataBuffer; -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/main/native/sim/mockdata/AnalogInData.cpp b/hal/src/main/native/sim/mockdata/AnalogInData.cpp index ebe22757c6..a703c03211 100644 --- a/hal/src/main/native/sim/mockdata/AnalogInData.cpp +++ b/hal/src/main/native/sim/mockdata/AnalogInData.cpp @@ -5,16 +5,16 @@ #include "../PortsInternal.h" #include "AnalogInDataInternal.h" -using namespace hal; +using namespace wpi::hal; -namespace hal::init { +namespace wpi::hal::init { void InitializeAnalogInData() { static AnalogInData sind[kNumAnalogInputs]; - ::hal::SimAnalogInData = sind; + ::wpi::hal::SimAnalogInData = sind; } -} // namespace hal::init +} // namespace wpi::hal::init -AnalogInData* hal::SimAnalogInData; +AnalogInData* wpi::hal::SimAnalogInData; void AnalogInData::ResetData() { initialized.Reset(false); simDevice = 0; diff --git a/hal/src/main/native/sim/mockdata/AnalogInDataInternal.h b/hal/src/main/native/sim/mockdata/AnalogInDataInternal.h index a93df355de..8a5ef935a9 100644 --- a/hal/src/main/native/sim/mockdata/AnalogInDataInternal.h +++ b/hal/src/main/native/sim/mockdata/AnalogInDataInternal.h @@ -7,7 +7,7 @@ #include "wpi/hal/simulation/AnalogInData.h" #include "wpi/hal/simulation/SimDataValue.h" -namespace hal { +namespace wpi::hal { class AnalogInData { HAL_SIMDATAVALUE_DEFINE_NAME(Initialized) HAL_SIMDATAVALUE_DEFINE_NAME(AverageBits) @@ -25,4 +25,4 @@ class AnalogInData { virtual void ResetData(); }; extern AnalogInData* SimAnalogInData; -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/main/native/sim/mockdata/CTREPCMData.cpp b/hal/src/main/native/sim/mockdata/CTREPCMData.cpp index bfc0b61796..5096d6538e 100644 --- a/hal/src/main/native/sim/mockdata/CTREPCMData.cpp +++ b/hal/src/main/native/sim/mockdata/CTREPCMData.cpp @@ -5,16 +5,16 @@ #include "../PortsInternal.h" #include "CTREPCMDataInternal.h" -using namespace hal; +using namespace wpi::hal; -namespace hal::init { +namespace wpi::hal::init { void InitializeCTREPCMData() { static CTREPCMData spd[kNumCTREPCMModules]; - ::hal::SimCTREPCMData = spd; + ::wpi::hal::SimCTREPCMData = spd; } -} // namespace hal::init +} // namespace wpi::hal::init -CTREPCMData* hal::SimCTREPCMData; +CTREPCMData* wpi::hal::SimCTREPCMData; void CTREPCMData::ResetData() { for (int i = 0; i < kNumCTRESolenoidChannels; i++) { solenoidOutput[i].Reset(false); diff --git a/hal/src/main/native/sim/mockdata/CTREPCMDataInternal.h b/hal/src/main/native/sim/mockdata/CTREPCMDataInternal.h index d721179983..44352e8fc5 100644 --- a/hal/src/main/native/sim/mockdata/CTREPCMDataInternal.h +++ b/hal/src/main/native/sim/mockdata/CTREPCMDataInternal.h @@ -8,7 +8,7 @@ #include "wpi/hal/simulation/CTREPCMData.h" #include "wpi/hal/simulation/SimDataValue.h" -namespace hal { +namespace wpi::hal { class CTREPCMData { HAL_SIMDATAVALUE_DEFINE_NAME(Initialized) HAL_SIMDATAVALUE_DEFINE_NAME(SolenoidOutput) @@ -40,4 +40,4 @@ class CTREPCMData { virtual void ResetData(); }; extern CTREPCMData* SimCTREPCMData; -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/main/native/sim/mockdata/CanDataInternal.cpp b/hal/src/main/native/sim/mockdata/CanDataInternal.cpp index 0ace401415..e03c261d37 100644 --- a/hal/src/main/native/sim/mockdata/CanDataInternal.cpp +++ b/hal/src/main/native/sim/mockdata/CanDataInternal.cpp @@ -4,16 +4,16 @@ #include "CanDataInternal.h" -using namespace hal; +using namespace wpi::hal; -namespace hal::init { +namespace wpi::hal::init { void InitializeCanData() { static CanData scd; - ::hal::SimCanData = &scd; + ::wpi::hal::SimCanData = &scd; } -} // namespace hal::init +} // namespace wpi::hal::init -CanData* hal::SimCanData; +CanData* wpi::hal::SimCanData; void CanData::ResetData() { sendMessage.Reset(); diff --git a/hal/src/main/native/sim/mockdata/CanDataInternal.h b/hal/src/main/native/sim/mockdata/CanDataInternal.h index 813a8ced29..3b555363b1 100644 --- a/hal/src/main/native/sim/mockdata/CanDataInternal.h +++ b/hal/src/main/native/sim/mockdata/CanDataInternal.h @@ -7,7 +7,7 @@ #include "wpi/hal/simulation/CanData.h" #include "wpi/hal/simulation/SimCallbackRegistry.h" -namespace hal { +namespace wpi::hal { class CanData { HAL_SIMCALLBACKREGISTRY_DEFINE_NAME(SendMessage) @@ -36,4 +36,4 @@ class CanData { extern CanData* SimCanData; -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/main/native/sim/mockdata/DIOData.cpp b/hal/src/main/native/sim/mockdata/DIOData.cpp index cdca84bf9d..1f80eedf92 100644 --- a/hal/src/main/native/sim/mockdata/DIOData.cpp +++ b/hal/src/main/native/sim/mockdata/DIOData.cpp @@ -5,16 +5,16 @@ #include "../PortsInternal.h" #include "DIODataInternal.h" -using namespace hal; +using namespace wpi::hal; -namespace hal::init { +namespace wpi::hal::init { void InitializeDIOData() { static DIOData sdd[kNumDigitalChannels]; - ::hal::SimDIOData = sdd; + ::wpi::hal::SimDIOData = sdd; } -} // namespace hal::init +} // namespace wpi::hal::init -DIOData* hal::SimDIOData; +DIOData* wpi::hal::SimDIOData; void DIOData::ResetData() { initialized.Reset(false); simDevice = 0; diff --git a/hal/src/main/native/sim/mockdata/DIODataInternal.h b/hal/src/main/native/sim/mockdata/DIODataInternal.h index b43296cf0a..1d205e5dcb 100644 --- a/hal/src/main/native/sim/mockdata/DIODataInternal.h +++ b/hal/src/main/native/sim/mockdata/DIODataInternal.h @@ -7,7 +7,7 @@ #include "wpi/hal/simulation/DIOData.h" #include "wpi/hal/simulation/SimDataValue.h" -namespace hal { +namespace wpi::hal { class DIOData { HAL_SIMDATAVALUE_DEFINE_NAME(Initialized) HAL_SIMDATAVALUE_DEFINE_NAME(Value) @@ -27,4 +27,4 @@ class DIOData { virtual void ResetData(); }; extern DIOData* SimDIOData; -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/main/native/sim/mockdata/DigitalPWMData.cpp b/hal/src/main/native/sim/mockdata/DigitalPWMData.cpp index da4236a50d..9afbcd6247 100644 --- a/hal/src/main/native/sim/mockdata/DigitalPWMData.cpp +++ b/hal/src/main/native/sim/mockdata/DigitalPWMData.cpp @@ -5,16 +5,16 @@ #include "../PortsInternal.h" #include "DigitalPWMDataInternal.h" -using namespace hal; +using namespace wpi::hal; -namespace hal::init { +namespace wpi::hal::init { void InitializeDigitalPWMData() { static DigitalPWMData sdpd[kNumDigitalPWMOutputs]; - ::hal::SimDigitalPWMData = sdpd; + ::wpi::hal::SimDigitalPWMData = sdpd; } -} // namespace hal::init +} // namespace wpi::hal::init -DigitalPWMData* hal::SimDigitalPWMData; +DigitalPWMData* wpi::hal::SimDigitalPWMData; void DigitalPWMData::ResetData() { initialized.Reset(false); dutyCycle.Reset(0.0); diff --git a/hal/src/main/native/sim/mockdata/DigitalPWMDataInternal.h b/hal/src/main/native/sim/mockdata/DigitalPWMDataInternal.h index a9f5926cf8..c5e8b1e0be 100644 --- a/hal/src/main/native/sim/mockdata/DigitalPWMDataInternal.h +++ b/hal/src/main/native/sim/mockdata/DigitalPWMDataInternal.h @@ -7,7 +7,7 @@ #include "wpi/hal/simulation/DigitalPWMData.h" #include "wpi/hal/simulation/SimDataValue.h" -namespace hal { +namespace wpi::hal { class DigitalPWMData { HAL_SIMDATAVALUE_DEFINE_NAME(Initialized) HAL_SIMDATAVALUE_DEFINE_NAME(DutyCycle) @@ -22,4 +22,4 @@ class DigitalPWMData { virtual void ResetData(); }; extern DigitalPWMData* SimDigitalPWMData; -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/main/native/sim/mockdata/DriverStationData.cpp b/hal/src/main/native/sim/mockdata/DriverStationData.cpp index e508d05f51..2388775dc7 100644 --- a/hal/src/main/native/sim/mockdata/DriverStationData.cpp +++ b/hal/src/main/native/sim/mockdata/DriverStationData.cpp @@ -6,16 +6,16 @@ #include "DriverStationDataInternal.h" -using namespace hal; +using namespace wpi::hal; -namespace hal::init { +namespace wpi::hal::init { void InitializeDriverStationData() { static DriverStationData dsd; - ::hal::SimDriverStationData = &dsd; + ::wpi::hal::SimDriverStationData = &dsd; } -} // namespace hal::init +} // namespace wpi::hal::init -DriverStationData* hal::SimDriverStationData; +DriverStationData* wpi::hal::SimDriverStationData; DriverStationData::DriverStationData() { ResetData(); @@ -215,12 +215,12 @@ void DriverStationData::CallNewDataCallbacks() { m_newDataCallbacks(&empty); } -namespace hal { +namespace wpi::hal { void NewDriverStationData(); -} // namespace hal +} // namespace wpi::hal void DriverStationData::NotifyNewData() { - hal::NewDriverStationData(); + wpi::hal::NewDriverStationData(); } void DriverStationData::SetJoystickButton(int32_t stick, int32_t button, @@ -528,15 +528,15 @@ void HALSIM_SetJoystickType(int32_t stick, int32_t type) { } void HALSIM_SetJoystickName(int32_t stick, const WPI_String* name) { - SimDriverStationData->SetJoystickName(stick, wpi::to_string_view(name)); + SimDriverStationData->SetJoystickName(stick, wpi::util::to_string_view(name)); } void HALSIM_SetGameSpecificMessage(const WPI_String* message) { - SimDriverStationData->SetGameSpecificMessage(wpi::to_string_view(message)); + SimDriverStationData->SetGameSpecificMessage(wpi::util::to_string_view(message)); } void HALSIM_SetEventName(const WPI_String* name) { - SimDriverStationData->SetEventName(wpi::to_string_view(name)); + SimDriverStationData->SetEventName(wpi::util::to_string_view(name)); } void HALSIM_SetMatchType(HAL_MatchType type) { diff --git a/hal/src/main/native/sim/mockdata/DriverStationDataInternal.h b/hal/src/main/native/sim/mockdata/DriverStationDataInternal.h index 1f007e9ebe..da20ba6c54 100644 --- a/hal/src/main/native/sim/mockdata/DriverStationDataInternal.h +++ b/hal/src/main/native/sim/mockdata/DriverStationDataInternal.h @@ -11,7 +11,7 @@ #include "wpi/hal/simulation/SimDataValue.h" #include "wpi/util/spinlock.hpp" -namespace hal { +namespace wpi::hal { class DriverStationData { HAL_SIMDATAVALUE_DEFINE_NAME(Enabled) @@ -157,11 +157,11 @@ class DriverStationData { }; static constexpr int kNumJoysticks = 6; - wpi::spinlock m_joystickDataMutex; + wpi::util::spinlock m_joystickDataMutex; JoystickData m_joystickData[kNumJoysticks]; - wpi::spinlock m_matchInfoMutex; + wpi::util::spinlock m_matchInfoMutex; HAL_MatchInfo m_matchInfo; }; extern DriverStationData* SimDriverStationData; -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/main/native/sim/mockdata/DutyCycleData.cpp b/hal/src/main/native/sim/mockdata/DutyCycleData.cpp index b76044d135..557c7dbd1d 100644 --- a/hal/src/main/native/sim/mockdata/DutyCycleData.cpp +++ b/hal/src/main/native/sim/mockdata/DutyCycleData.cpp @@ -5,16 +5,16 @@ #include "../PortsInternal.h" #include "DutyCycleDataInternal.h" -using namespace hal; +using namespace wpi::hal; -namespace hal::init { +namespace wpi::hal::init { void InitializeDutyCycleData() { static DutyCycleData sed[kNumDutyCycles]; - ::hal::SimDutyCycleData = sed; + ::wpi::hal::SimDutyCycleData = sed; } -} // namespace hal::init +} // namespace wpi::hal::init -DutyCycleData* hal::SimDutyCycleData; +DutyCycleData* wpi::hal::SimDutyCycleData; void DutyCycleData::ResetData() { initialized.Reset(false); diff --git a/hal/src/main/native/sim/mockdata/DutyCycleDataInternal.h b/hal/src/main/native/sim/mockdata/DutyCycleDataInternal.h index 4e8791cd24..78b2a4b5ec 100644 --- a/hal/src/main/native/sim/mockdata/DutyCycleDataInternal.h +++ b/hal/src/main/native/sim/mockdata/DutyCycleDataInternal.h @@ -10,7 +10,7 @@ #include "wpi/hal/simulation/DutyCycleData.h" #include "wpi/hal/simulation/SimDataValue.h" -namespace hal { +namespace wpi::hal { class DutyCycleData { HAL_SIMDATAVALUE_DEFINE_NAME(Initialized) HAL_SIMDATAVALUE_DEFINE_NAME(Output) @@ -26,4 +26,4 @@ class DutyCycleData { virtual void ResetData(); }; extern DutyCycleData* SimDutyCycleData; -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/main/native/sim/mockdata/EncoderData.cpp b/hal/src/main/native/sim/mockdata/EncoderData.cpp index 8b012ed9d0..2def1a58a1 100644 --- a/hal/src/main/native/sim/mockdata/EncoderData.cpp +++ b/hal/src/main/native/sim/mockdata/EncoderData.cpp @@ -7,16 +7,16 @@ #include "../PortsInternal.h" #include "EncoderDataInternal.h" -using namespace hal; +using namespace wpi::hal; -namespace hal::init { +namespace wpi::hal::init { void InitializeEncoderData() { static EncoderData sed[kNumEncoders]; - ::hal::SimEncoderData = sed; + ::wpi::hal::SimEncoderData = sed; } -} // namespace hal::init +} // namespace wpi::hal::init -EncoderData* hal::SimEncoderData; +EncoderData* wpi::hal::SimEncoderData; void EncoderData::ResetData() { digitalChannelA = 0; digitalChannelB = 0; diff --git a/hal/src/main/native/sim/mockdata/EncoderDataInternal.h b/hal/src/main/native/sim/mockdata/EncoderDataInternal.h index 2b78dadc90..bdd3620605 100644 --- a/hal/src/main/native/sim/mockdata/EncoderDataInternal.h +++ b/hal/src/main/native/sim/mockdata/EncoderDataInternal.h @@ -10,7 +10,7 @@ #include "wpi/hal/simulation/EncoderData.h" #include "wpi/hal/simulation/SimDataValue.h" -namespace hal { +namespace wpi::hal { class EncoderData { HAL_SIMDATAVALUE_DEFINE_NAME(Initialized) HAL_SIMDATAVALUE_DEFINE_NAME(Count) @@ -44,4 +44,4 @@ class EncoderData { virtual void ResetData(); }; extern EncoderData* SimEncoderData; -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/main/native/sim/mockdata/I2CData.cpp b/hal/src/main/native/sim/mockdata/I2CData.cpp index d3b7db61cd..5009c76879 100644 --- a/hal/src/main/native/sim/mockdata/I2CData.cpp +++ b/hal/src/main/native/sim/mockdata/I2CData.cpp @@ -5,16 +5,16 @@ #include "../PortsInternal.h" #include "I2CDataInternal.h" -using namespace hal; +using namespace wpi::hal; -namespace hal::init { +namespace wpi::hal::init { void InitializeI2CData() { static I2CData sid[kI2CPorts]; - ::hal::SimI2CData = sid; + ::wpi::hal::SimI2CData = sid; } -} // namespace hal::init +} // namespace wpi::hal::init -I2CData* hal::SimI2CData; +I2CData* wpi::hal::SimI2CData; void I2CData::ResetData() { initialized.Reset(false); diff --git a/hal/src/main/native/sim/mockdata/I2CDataInternal.h b/hal/src/main/native/sim/mockdata/I2CDataInternal.h index ba447f14b6..e5cc4e48f5 100644 --- a/hal/src/main/native/sim/mockdata/I2CDataInternal.h +++ b/hal/src/main/native/sim/mockdata/I2CDataInternal.h @@ -8,7 +8,7 @@ #include "wpi/hal/simulation/SimCallbackRegistry.h" #include "wpi/hal/simulation/SimDataValue.h" -namespace hal { +namespace wpi::hal { class I2CData { HAL_SIMDATAVALUE_DEFINE_NAME(Initialized) HAL_SIMCALLBACKREGISTRY_DEFINE_NAME(Read) @@ -27,4 +27,4 @@ class I2CData { void ResetData(); }; extern I2CData* SimI2CData; -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/main/native/sim/mockdata/PWMData.cpp b/hal/src/main/native/sim/mockdata/PWMData.cpp index 576c38b305..456334e30c 100644 --- a/hal/src/main/native/sim/mockdata/PWMData.cpp +++ b/hal/src/main/native/sim/mockdata/PWMData.cpp @@ -5,16 +5,16 @@ #include "../PortsInternal.h" #include "PWMDataInternal.h" -using namespace hal; +using namespace wpi::hal; -namespace hal::init { +namespace wpi::hal::init { void InitializePWMData() { static PWMData spd[kNumPWMChannels]; - ::hal::SimPWMData = spd; + ::wpi::hal::SimPWMData = spd; } -} // namespace hal::init +} // namespace wpi::hal::init -PWMData* hal::SimPWMData; +PWMData* wpi::hal::SimPWMData; void PWMData::ResetData() { initialized.Reset(false); simDevice = 0; diff --git a/hal/src/main/native/sim/mockdata/PWMDataInternal.h b/hal/src/main/native/sim/mockdata/PWMDataInternal.h index e3294faab0..f1877f4d11 100644 --- a/hal/src/main/native/sim/mockdata/PWMDataInternal.h +++ b/hal/src/main/native/sim/mockdata/PWMDataInternal.h @@ -7,7 +7,7 @@ #include "wpi/hal/simulation/PWMData.h" #include "wpi/hal/simulation/SimDataValue.h" -namespace hal { +namespace wpi::hal { class PWMData { HAL_SIMDATAVALUE_DEFINE_NAME(Initialized) HAL_SIMDATAVALUE_DEFINE_NAME(PulseMicrosecond) @@ -24,4 +24,4 @@ class PWMData { virtual void ResetData(); }; extern PWMData* SimPWMData; -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/main/native/sim/mockdata/PowerDistributionData.cpp b/hal/src/main/native/sim/mockdata/PowerDistributionData.cpp index 9c5b82644c..d8456fa669 100644 --- a/hal/src/main/native/sim/mockdata/PowerDistributionData.cpp +++ b/hal/src/main/native/sim/mockdata/PowerDistributionData.cpp @@ -5,16 +5,16 @@ #include "../PortsInternal.h" #include "PowerDistributionDataInternal.h" -using namespace hal; +using namespace wpi::hal; -namespace hal::init { +namespace wpi::hal::init { void InitializePowerDistributionData() { static PowerDistributionData spd[kNumPDSimModules]; - ::hal::SimPowerDistributionData = spd; + ::wpi::hal::SimPowerDistributionData = spd; } -} // namespace hal::init +} // namespace wpi::hal::init -PowerDistributionData* hal::SimPowerDistributionData; +PowerDistributionData* wpi::hal::SimPowerDistributionData; void PowerDistributionData::ResetData() { initialized.Reset(false); temperature.Reset(0.0); diff --git a/hal/src/main/native/sim/mockdata/PowerDistributionDataInternal.h b/hal/src/main/native/sim/mockdata/PowerDistributionDataInternal.h index 10c684f72b..77fb40af8c 100644 --- a/hal/src/main/native/sim/mockdata/PowerDistributionDataInternal.h +++ b/hal/src/main/native/sim/mockdata/PowerDistributionDataInternal.h @@ -8,7 +8,7 @@ #include "wpi/hal/simulation/PowerDistributionData.h" #include "wpi/hal/simulation/SimDataValue.h" -namespace hal { +namespace wpi::hal { class PowerDistributionData { HAL_SIMDATAVALUE_DEFINE_NAME(Initialized) @@ -31,4 +31,4 @@ class PowerDistributionData { virtual void ResetData(); }; extern PowerDistributionData* SimPowerDistributionData; -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/main/native/sim/mockdata/REVPHData.cpp b/hal/src/main/native/sim/mockdata/REVPHData.cpp index cb1a3a883e..51cf274c25 100644 --- a/hal/src/main/native/sim/mockdata/REVPHData.cpp +++ b/hal/src/main/native/sim/mockdata/REVPHData.cpp @@ -5,16 +5,16 @@ #include "../PortsInternal.h" #include "REVPHDataInternal.h" -using namespace hal; +using namespace wpi::hal; -namespace hal::init { +namespace wpi::hal::init { void InitializeREVPHData() { static REVPHData spd[kNumREVPHModules]; - ::hal::SimREVPHData = spd; + ::wpi::hal::SimREVPHData = spd; } -} // namespace hal::init +} // namespace wpi::hal::init -REVPHData* hal::SimREVPHData; +REVPHData* wpi::hal::SimREVPHData; void REVPHData::ResetData() { for (int i = 0; i < kNumREVPHChannels; i++) { solenoidOutput[i].Reset(false); diff --git a/hal/src/main/native/sim/mockdata/REVPHDataInternal.h b/hal/src/main/native/sim/mockdata/REVPHDataInternal.h index 7dc268d0af..028c2cf126 100644 --- a/hal/src/main/native/sim/mockdata/REVPHDataInternal.h +++ b/hal/src/main/native/sim/mockdata/REVPHDataInternal.h @@ -8,7 +8,7 @@ #include "wpi/hal/simulation/REVPHData.h" #include "wpi/hal/simulation/SimDataValue.h" -namespace hal { +namespace wpi::hal { class REVPHData { HAL_SIMDATAVALUE_DEFINE_NAME(Initialized) HAL_SIMDATAVALUE_DEFINE_NAME(SolenoidOutput) @@ -47,4 +47,4 @@ class REVPHData { virtual void ResetData(); }; extern REVPHData* SimREVPHData; -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/main/native/sim/mockdata/Reset.cpp b/hal/src/main/native/sim/mockdata/Reset.cpp index c3c5f44c77..bb2449f54d 100644 --- a/hal/src/main/native/sim/mockdata/Reset.cpp +++ b/hal/src/main/native/sim/mockdata/Reset.cpp @@ -20,51 +20,51 @@ #include "wpi/hal/simulation/SimDeviceData.h" extern "C" void HALSIM_ResetAllSimData(void) { - for (int32_t i = 0; i < hal::kNumAddressableLEDs; i++) { + for (int32_t i = 0; i < wpi::hal::kNumAddressableLEDs; i++) { HALSIM_ResetAddressableLEDData(i); } - for (int32_t i = 0; i < hal::kNumAnalogInputs; i++) { + for (int32_t i = 0; i < wpi::hal::kNumAnalogInputs; i++) { HALSIM_ResetAnalogInData(i); } HALSIM_ResetCanData(); - for (int32_t i = 0; i < hal::kNumCTREPCMModules; i++) { + for (int32_t i = 0; i < wpi::hal::kNumCTREPCMModules; i++) { HALSIM_ResetCTREPCMData(i); } - for (int32_t i = 0; i < hal::kNumDigitalPWMOutputs; i++) { + for (int32_t i = 0; i < wpi::hal::kNumDigitalPWMOutputs; i++) { HALSIM_ResetDigitalPWMData(i); } - for (int32_t i = 0; i < hal::kNumDigitalChannels; i++) { + for (int32_t i = 0; i < wpi::hal::kNumDigitalChannels; i++) { HALSIM_ResetDIOData(i); } HALSIM_ResetDriverStationData(); - for (int32_t i = 0; i < hal::kNumDutyCycles; i++) { + for (int32_t i = 0; i < wpi::hal::kNumDutyCycles; i++) { HALSIM_ResetDutyCycleData(i); } - for (int32_t i = 0; i < hal::kNumEncoders; i++) { + for (int32_t i = 0; i < wpi::hal::kNumEncoders; i++) { HALSIM_ResetEncoderData(i); } - for (int32_t i = 0; i < hal::kI2CPorts; i++) { + for (int32_t i = 0; i < wpi::hal::kI2CPorts; i++) { HALSIM_ResetI2CData(i); } - for (int32_t i = 0; i < hal::kNumPDSimModules; i++) { + for (int32_t i = 0; i < wpi::hal::kNumPDSimModules; i++) { HALSIM_ResetPowerDistributionData(i); } - for (int32_t i = 0; i < hal::kNumPWMChannels; i++) { + for (int32_t i = 0; i < wpi::hal::kNumPWMChannels; i++) { HALSIM_ResetPWMData(i); } - for (int32_t i = 0; i < hal::kNumREVPHModules; i++) { + for (int32_t i = 0; i < wpi::hal::kNumREVPHModules; i++) { HALSIM_ResetREVPHData(i); } diff --git a/hal/src/main/native/sim/mockdata/RoboRioData.cpp b/hal/src/main/native/sim/mockdata/RoboRioData.cpp index ba772a8add..852410f673 100644 --- a/hal/src/main/native/sim/mockdata/RoboRioData.cpp +++ b/hal/src/main/native/sim/mockdata/RoboRioData.cpp @@ -6,16 +6,16 @@ #include "RoboRioDataInternal.h" -using namespace hal; +using namespace wpi::hal; -namespace hal::init { +namespace wpi::hal::init { void InitializeRoboRioData() { static RoboRioData srrd; - ::hal::SimRoboRioData = &srrd; + ::wpi::hal::SimRoboRioData = &srrd; } -} // namespace hal::init +} // namespace wpi::hal::init -RoboRioData* hal::SimRoboRioData; +RoboRioData* wpi::hal::SimRoboRioData; void RoboRioData::ResetData() { vInVoltage.Reset(12.0); userVoltage3V3.Reset(3.3); @@ -121,7 +121,7 @@ void HALSIM_GetRoboRioSerialNumber(struct WPI_String* serialNumber) { SimRoboRioData->GetSerialNumber(serialNumber); } void HALSIM_SetRoboRioSerialNumber(const struct WPI_String* serialNumber) { - SimRoboRioData->SetSerialNumber(wpi::to_string_view(serialNumber)); + SimRoboRioData->SetSerialNumber(wpi::util::to_string_view(serialNumber)); } int32_t HALSIM_RegisterRoboRioCommentsCallback( @@ -136,7 +136,7 @@ void HALSIM_GetRoboRioComments(struct WPI_String* comments) { SimRoboRioData->GetComments(comments); } void HALSIM_SetRoboRioComments(const struct WPI_String* comments) { - SimRoboRioData->SetComments(wpi::to_string_view(comments)); + SimRoboRioData->SetComments(wpi::util::to_string_view(comments)); } void HALSIM_RegisterRoboRioAllCallbacks(HAL_NotifyCallback callback, diff --git a/hal/src/main/native/sim/mockdata/RoboRioDataInternal.h b/hal/src/main/native/sim/mockdata/RoboRioDataInternal.h index 5c9c0ca63f..7fc276569b 100644 --- a/hal/src/main/native/sim/mockdata/RoboRioDataInternal.h +++ b/hal/src/main/native/sim/mockdata/RoboRioDataInternal.h @@ -11,7 +11,7 @@ #include "wpi/hal/simulation/SimDataValue.h" #include "wpi/util/spinlock.hpp" -namespace hal { +namespace wpi::hal { class RoboRioData { HAL_SIMDATAVALUE_DEFINE_NAME(VInVoltage) HAL_SIMDATAVALUE_DEFINE_NAME(UserVoltage3V3) @@ -54,10 +54,10 @@ class RoboRioData { virtual void ResetData(); private: - wpi::spinlock m_serialNumberMutex; + wpi::util::spinlock m_serialNumberMutex; std::string m_serialNumber; - wpi::spinlock m_commentsMutex; + wpi::util::spinlock m_commentsMutex; std::string m_comments; SimCallbackRegistry @@ -67,4 +67,4 @@ class RoboRioData { m_commentsCallbacks; }; extern RoboRioData* SimRoboRioData; -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/main/native/sim/mockdata/SimDeviceData.cpp b/hal/src/main/native/sim/mockdata/SimDeviceData.cpp index 045692eada..55aac569f3 100644 --- a/hal/src/main/native/sim/mockdata/SimDeviceData.cpp +++ b/hal/src/main/native/sim/mockdata/SimDeviceData.cpp @@ -11,16 +11,16 @@ #include "SimDeviceDataInternal.h" #include "wpi/util/StringExtras.hpp" -using namespace hal; +using namespace wpi::hal; -namespace hal::init { +namespace wpi::hal::init { void InitializeSimDeviceData() { static SimDeviceData sdd; - ::hal::SimSimDeviceData = &sdd; + ::wpi::hal::SimSimDeviceData = &sdd; } -} // namespace hal::init +} // namespace wpi::hal::init -SimDeviceData* hal::SimSimDeviceData; +SimDeviceData* wpi::hal::SimSimDeviceData; SimDeviceData::Device* SimDeviceData::LookupDevice(HAL_SimDeviceHandle handle) { if (handle <= 0) { @@ -74,7 +74,7 @@ void SimDeviceData::SetDeviceEnabled(const char* prefix, bool enabled) { bool SimDeviceData::IsDeviceEnabled(const char* name) { std::scoped_lock lock(m_mutex); for (const auto& elem : m_prefixEnabled) { - if (wpi::starts_with(name, elem.first)) { + if (wpi::util::starts_with(name, elem.first)) { return elem.second; } } @@ -86,7 +86,7 @@ HAL_SimDeviceHandle SimDeviceData::CreateDevice(const char* name) { // don't create if disabled for (const auto& elem : m_prefixEnabled) { - if (wpi::starts_with(name, elem.first)) { + if (wpi::util::starts_with(name, elem.first)) { if (elem.second) { break; // enabled } @@ -275,7 +275,7 @@ int32_t SimDeviceData::RegisterDeviceCreatedCallback( // initial notifications if (initialNotify) { for (auto&& device : m_devices) { - if (wpi::starts_with(device->name, prefix)) { + if (wpi::util::starts_with(device->name, prefix)) { auto name = device->name; auto handle = device->handle; lock.unlock(); @@ -339,7 +339,7 @@ void SimDeviceData::EnumerateDevices(const char* prefix, void* param, HALSIM_SimDeviceCallback callback) { std::scoped_lock lock(m_mutex); for (auto&& device : m_devices) { - if (wpi::starts_with(device->name, prefix)) { + if (wpi::util::starts_with(device->name, prefix)) { callback(device->name.c_str(), param, device->handle); } } diff --git a/hal/src/main/native/sim/mockdata/SimDeviceDataInternal.h b/hal/src/main/native/sim/mockdata/SimDeviceDataInternal.h index 6f8839139c..1e386e9af9 100644 --- a/hal/src/main/native/sim/mockdata/SimDeviceDataInternal.h +++ b/hal/src/main/native/sim/mockdata/SimDeviceDataInternal.h @@ -19,7 +19,7 @@ #include "wpi/util/UidVector.hpp" #include "wpi/util/spinlock.hpp" -namespace hal { +namespace wpi::hal { namespace impl { @@ -29,7 +29,7 @@ class SimUnnamedCallbackRegistry { using RawFunctor = void (*)(); protected: - using CallbackVector = wpi::UidVector, 4>; + using CallbackVector = wpi::util::UidVector, 4>; public: void Cancel(int32_t uid) { @@ -95,7 +95,7 @@ class SimPrefixCallbackRegistry { explicit operator bool() const { return callback != nullptr; } }; - using CallbackVector = wpi::UidVector; + using CallbackVector = wpi::util::UidVector; public: void Cancel(int32_t uid) { @@ -126,7 +126,7 @@ class SimPrefixCallbackRegistry { if (m_callbacks) { for (size_t i = 0; i < m_callbacks->size(); ++i) { auto& cb = (*m_callbacks)[i]; - if (cb.callback && wpi::starts_with(name, cb.prefix)) { + if (cb.callback && wpi::util::starts_with(name, cb.prefix)) { auto callback = cb.callback; auto param = cb.param; lock.unlock(); @@ -170,16 +170,16 @@ class SimDeviceData { HAL_SimDeviceHandle handle{0}; std::string name; - wpi::UidVector, 16> values; - wpi::StringMap valueMap; + wpi::util::UidVector, 16> values; + wpi::util::StringMap valueMap; impl::SimUnnamedCallbackRegistry valueCreated; }; - wpi::UidVector, 4> m_devices; - wpi::StringMap> m_deviceMap; + wpi::util::UidVector, 4> m_devices; + wpi::util::StringMap> m_deviceMap; std::vector> m_prefixEnabled; - wpi::recursive_spinlock m_mutex; + wpi::util::recursive_spinlock m_mutex; impl::SimPrefixCallbackRegistry m_deviceCreated; impl::SimPrefixCallbackRegistry m_deviceFreed; @@ -253,4 +253,4 @@ class SimDeviceData { void ResetData(); }; extern SimDeviceData* SimSimDeviceData; -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/main/native/systemcore/AddressableLED.cpp b/hal/src/main/native/systemcore/AddressableLED.cpp index f193276c6a..1110ca81cc 100644 --- a/hal/src/main/native/systemcore/AddressableLED.cpp +++ b/hal/src/main/native/systemcore/AddressableLED.cpp @@ -25,7 +25,7 @@ #include "wpi/nt/NetworkTableInstance.hpp" #include "wpi/nt/RawTopic.hpp" -using namespace hal; +using namespace wpi::hal; #define IO_PREFIX "/io/" @@ -34,11 +34,11 @@ namespace { constexpr const char* kLedsKey = IO_PREFIX "leds"; struct AddressableLEDs { - explicit AddressableLEDs(nt::NetworkTableInstance inst) + explicit AddressableLEDs(wpi::nt::NetworkTableInstance inst) : rawPub{inst.GetRawTopic(kLedsKey).Publish( "raw", {.periodic = 0.005, .sendAll = true})} {} - nt::RawPublisher rawPub; + wpi::nt::RawPublisher rawPub; uint8_t s_buffer[HAL_kAddressableLEDMaxLength * 3]; }; @@ -46,7 +46,7 @@ static AddressableLEDs* leds; void ConvertAndCopyLEDData(void* dst, const struct HAL_AddressableLEDData* src, int32_t len, HAL_AddressableLEDColorOrder order) { - using namespace hal::detail; + using namespace wpi::hal::detail; switch (order) { case HAL_ALED_RGB: std::memcpy(dst, src, len * sizeof(HAL_AddressableLEDData)); @@ -75,22 +75,22 @@ void ConvertAndCopyLEDData(void* dst, const struct HAL_AddressableLEDData* src, } } // namespace -namespace hal::init { +namespace wpi::hal::init { void InitializeAddressableLED() { - static AddressableLEDs leds_static{hal::GetSystemServer()}; + static AddressableLEDs leds_static{wpi::hal::GetSystemServer()}; leds = &leds_static; } -} // namespace hal::init +} // namespace wpi::hal::init extern "C" { HAL_AddressableLEDHandle HAL_InitializeAddressableLED( int32_t channel, const char* allocationLocation, int32_t* status) { - hal::init::CheckInit(); + wpi::hal::init::CheckInit(); if (channel < 0 || channel >= kNumSmartIo) { *status = RESOURCE_OUT_OF_RANGE; - hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for AddressableLED", + wpi::hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for AddressableLED", 0, kNumSmartIo, channel); return HAL_kInvalidHandle; } @@ -102,10 +102,10 @@ HAL_AddressableLEDHandle HAL_InitializeAddressableLED( if (*status != 0) { if (port) { - hal::SetLastErrorPreviouslyAllocated(status, "SmartIo", channel, + wpi::hal::SetLastErrorPreviouslyAllocated(status, "SmartIo", channel, port->previousAllocation); } else { - hal::SetLastErrorIndexOutOfRange( + wpi::hal::SetLastErrorIndexOutOfRange( status, "Invalid Index for AddressableLED", 0, kNumSmartIo, channel); } return HAL_kInvalidHandle; // failed to allocate. Pass error back. @@ -133,9 +133,9 @@ void HAL_FreeAddressableLED(HAL_AddressableLEDHandle handle) { smartIoHandles->Free(handle, HAL_HandleEnum::AddressableLED); // Wait for no other object to hold this handle. - auto start = hal::fpga_clock::now(); + auto start = wpi::hal::fpga_clock::now(); while (port.use_count() != 1) { - auto current = hal::fpga_clock::now(); + auto current = wpi::hal::fpga_clock::now(); if (start + std::chrono::seconds(1) < current) { std::puts("AddressableLED handle free timeout"); std::fflush(stdout); diff --git a/hal/src/main/native/systemcore/AddressableLEDSimd.h b/hal/src/main/native/systemcore/AddressableLEDSimd.h index eddda08892..d25ab5aadc 100644 --- a/hal/src/main/native/systemcore/AddressableLEDSimd.h +++ b/hal/src/main/native/systemcore/AddressableLEDSimd.h @@ -8,7 +8,7 @@ #include "simd/simd.h" #include "wpi/hal/AddressableLEDTypes.h" -namespace hal::detail { +namespace wpi::hal::detail { constexpr size_t kPixelSize = 3; static_assert(sizeof(HAL_AddressableLEDData) == kPixelSize); @@ -221,4 +221,4 @@ void ConvertPixels(const uint8_t* src, uint8_t* dst, size_t len) { } } } -} // namespace hal::detail +} // namespace wpi::hal::detail diff --git a/hal/src/main/native/systemcore/AnalogInput.cpp b/hal/src/main/native/systemcore/AnalogInput.cpp index e471f7b37e..5c3c1be014 100644 --- a/hal/src/main/native/systemcore/AnalogInput.cpp +++ b/hal/src/main/native/systemcore/AnalogInput.cpp @@ -16,21 +16,21 @@ #include "wpi/hal/handles/HandlesInternal.h" #include "wpi/util/mutex.hpp" -namespace hal::init { +namespace wpi::hal::init { void InitializeAnalogInput() {} -} // namespace hal::init +} // namespace wpi::hal::init -using namespace hal; +using namespace wpi::hal; extern "C" { HAL_AnalogInputHandle HAL_InitializeAnalogInputPort( int32_t channel, const char* allocationLocation, int32_t* status) { - hal::init::CheckInit(); + wpi::hal::init::CheckInit(); if (channel < 0 || channel >= kNumSmartIo) { *status = RESOURCE_OUT_OF_RANGE; - hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for Analog", 0, + wpi::hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for Analog", 0, kNumSmartIo, channel); return HAL_kInvalidHandle; } @@ -42,10 +42,10 @@ HAL_AnalogInputHandle HAL_InitializeAnalogInputPort( if (*status != 0) { if (port) { - hal::SetLastErrorPreviouslyAllocated(status, "SmartIo", channel, + wpi::hal::SetLastErrorPreviouslyAllocated(status, "SmartIo", channel, port->previousAllocation); } else { - hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for Analog", 0, + wpi::hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for Analog", 0, kNumSmartIo, channel); } return HAL_kInvalidHandle; // failed to allocate. Pass error back. @@ -74,9 +74,9 @@ void HAL_FreeAnalogInputPort(HAL_AnalogInputHandle analogPortHandle) { smartIoHandles->Free(analogPortHandle, HAL_HandleEnum::AnalogInput); // Wait for no other object to hold this handle. - auto start = hal::fpga_clock::now(); + auto start = wpi::hal::fpga_clock::now(); while (port.use_count() != 1) { - auto current = hal::fpga_clock::now(); + auto current = wpi::hal::fpga_clock::now(); if (start + std::chrono::seconds(1) < current) { std::puts("DIO handle free timeout"); std::fflush(stdout); diff --git a/hal/src/main/native/systemcore/CAN.cpp b/hal/src/main/native/systemcore/CAN.cpp index a76066b1be..6fd591e36c 100644 --- a/hal/src/main/native/systemcore/CAN.cpp +++ b/hal/src/main/native/systemcore/CAN.cpp @@ -30,7 +30,7 @@ #include "wpi/util/print.hpp" #include "wpi/util/timestamp.h" -using namespace hal; +using namespace wpi::hal; namespace { @@ -72,7 +72,7 @@ struct CANStreamStorage { canMask{mask}, canFilter{filter} {} - wpi::circular_buffer receivedMessages; + wpi::util::circular_buffer receivedMessages; bool didOverflow{false}; uint32_t allowedMessages; uint8_t canBusId; @@ -83,31 +83,31 @@ struct CANStreamStorage { }; struct SocketCanState { - wpi::EventLoopRunner readLoopRunner; - wpi::EventLoopRunner writeLoopRunner; - wpi::mutex writeMutex[hal::kNumCanBuses]; - int socketHandle[hal::kNumCanBuses]; + wpi::net::EventLoopRunner readLoopRunner; + wpi::net::EventLoopRunner writeLoopRunner; + wpi::util::mutex writeMutex[wpi::hal::kNumCanBuses]; + int socketHandle[wpi::hal::kNumCanBuses]; // ms to count/timer map - wpi::DenseMap>> + wpi::util::DenseMap>> timers; // ms to bus mask/packet - wpi::DenseMap, hal::kNumCanBuses>> + wpi::util::DenseMap, wpi::hal::kNumCanBuses>> timedFrames; // packet to time - wpi::DenseMap> packetToTime; + wpi::util::DenseMap> packetToTime; - wpi::mutex readMutex[hal::kNumCanBuses]; + wpi::util::mutex readMutex[wpi::hal::kNumCanBuses]; // TODO(thadhouse) we need a MUCH better way of doing this masking - wpi::DenseMap readFrames[hal::kNumCanBuses]; - std::vector canStreams[hal::kNumCanBuses]; + wpi::util::DenseMap readFrames[wpi::hal::kNumCanBuses]; + std::vector canStreams[wpi::hal::kNumCanBuses]; bool InitializeBuses(); void TimerCallback(uint16_t time); void RemovePeriodic(uint8_t busMask, uint32_t messageId); - void AddPeriodic(wpi::uv::Loop& loop, uint8_t busMask, uint16_t time, + void AddPeriodic(wpi::net::uv::Loop& loop, uint8_t busMask, uint16_t time, const canfd_frame& frame); }; @@ -118,7 +118,7 @@ static UnlimitedHandleResource(&addr), sizeof(addr)) == -1) { - wpi::print("bind() for CAN {} failed with {}\n", ifr.ifr_name, + wpi::util::print("bind() for CAN {} failed with {}\n", ifr.ifr_name, std::strerror(errno)); success = false; return; } if (ioctl(socketHandle[i], SIOCGIFMTU, &ifr) == -1) { - wpi::print("ioctl(SIOCGIFMTU) for CAN {} failed with {}\n", + wpi::util::print("ioctl(SIOCGIFMTU) for CAN {} failed with {}\n", ifr.ifr_name, std::strerror(errno)); success = false; return; @@ -196,7 +196,7 @@ bool SocketCanState::InitializeBuses() { int fdSet = 1; if (setsockopt(socketHandle[i], SOL_CAN_RAW, CAN_RAW_FD_FRAMES, &fdSet, sizeof(fdSet)) != 0) { - wpi::print( + wpi::util::print( "setsockopt(CAN_RAW_FD_FRAMES) for CAN {} failed with {}\n", ifr.ifr_name, std::strerror(errno)); success = false; @@ -204,9 +204,9 @@ bool SocketCanState::InitializeBuses() { } } - auto poll = wpi::uv::Poll::Create(loop, socketHandle[i]); + auto poll = wpi::net::uv::Poll::Create(loop, socketHandle[i]); if (!poll) { - wpi::print("wpi::uv::Poll::Create for CAN {} failed\n", ifr.ifr_name); + wpi::util::print("wpi::net::uv::Poll::Create for CAN {} failed\n", ifr.ifr_name); success = false; return; } @@ -226,7 +226,7 @@ bool SocketCanState::InitializeBuses() { } uint32_t messageId = MapSocketCanToMessageId(frame.can_id); - uint64_t timestamp = wpi::Now(); + uint64_t timestamp = wpi::util::Now(); // Ensure FDF flag is set for the read later. if (rVal == CANFD_MTU) { frame.flags = CANFD_FDF; @@ -300,24 +300,24 @@ void SocketCanState::RemovePeriodic(uint8_t busId, uint32_t messageId) { } } -void SocketCanState::AddPeriodic(wpi::uv::Loop& loop, uint8_t busId, +void SocketCanState::AddPeriodic(wpi::net::uv::Loop& loop, uint8_t busId, uint16_t time, const canfd_frame& frame) { packetToTime[frame.can_id][busId] = time; timedFrames[time][busId] = frame; auto& timer = timers[time]; timer.first++; if (timer.first == 1) { - auto newTimer = wpi::uv::Timer::Create(loop); + auto newTimer = wpi::net::uv::Timer::Create(loop); newTimer->timeout.connect([this, time] { TimerCallback(time); }); - newTimer->Start(wpi::uv::Timer::Time{time}, wpi::uv::Timer::Time{time}); + newTimer->Start(wpi::net::uv::Timer::Time{time}, wpi::net::uv::Timer::Time{time}); } } -namespace hal { +namespace wpi::hal { bool InitializeCanBuses() { return canState->InitializeBuses(); } -} // namespace hal +} // namespace wpi::hal namespace {} // namespace @@ -326,7 +326,7 @@ extern "C" { void HAL_CAN_SendMessage(int32_t busId, uint32_t messageId, const struct HAL_CANMessage* message, int32_t periodMs, int32_t* status) { - if (busId < 0 || busId >= hal::kNumCanBuses) { + if (busId < 0 || busId >= wpi::hal::kNumCanBuses) { *status = PARAMETER_OUT_OF_RANGE; return; } @@ -336,7 +336,7 @@ void HAL_CAN_SendMessage(int32_t busId, uint32_t messageId, // TODO determine on the real roborio is a non periodic send removes any // periodic send. if (periodMs == HAL_CAN_SEND_PERIOD_STOP_REPEATING) { - canState->writeLoopRunner.ExecSync([messageId, busId](wpi::uv::Loop&) { + canState->writeLoopRunner.ExecSync([messageId, busId](wpi::net::uv::Loop&) { canState->RemovePeriodic(busId, messageId); }); @@ -385,7 +385,7 @@ void HAL_CAN_SendMessage(int32_t busId, uint32_t messageId, if (periodMs > 0) { canState->writeLoopRunner.ExecAsync( - [busId, periodMs, frame](wpi::uv::Loop& loop) { + [busId, periodMs, frame](wpi::net::uv::Loop& loop) { canState->AddPeriodic(loop, busId, periodMs, frame); }); } @@ -393,7 +393,7 @@ void HAL_CAN_SendMessage(int32_t busId, uint32_t messageId, void HAL_CAN_ReceiveMessage(int32_t busId, uint32_t messageId, struct HAL_CANReceiveMessage* message, int32_t* status) { - if (busId < 0 || busId >= hal::kNumCanBuses) { + if (busId < 0 || busId >= wpi::hal::kNumCanBuses) { message->message.dataSize = 0; message->timeStamp = 0; *status = PARAMETER_OUT_OF_RANGE; @@ -421,7 +421,7 @@ HAL_CANStreamHandle HAL_CAN_OpenStreamSession(int32_t busId, uint32_t messageId, uint32_t messageIdMask, uint32_t maxMessages, int32_t* status) { - if (busId < 0 || busId >= hal::kNumCanBuses) { + if (busId < 0 || busId >= wpi::hal::kNumCanBuses) { *status = PARAMETER_OUT_OF_RANGE; return HAL_kInvalidHandle; } diff --git a/hal/src/main/native/systemcore/CANAPI.cpp b/hal/src/main/native/systemcore/CANAPI.cpp index 22b3cd21aa..1a4d37b9d2 100644 --- a/hal/src/main/native/systemcore/CANAPI.cpp +++ b/hal/src/main/native/systemcore/CANAPI.cpp @@ -16,7 +16,7 @@ #include "wpi/util/mutex.hpp" #include "wpi/util/timestamp.h" -using namespace hal; +using namespace wpi::hal; namespace { struct CANStorage { @@ -24,23 +24,23 @@ struct CANStorage { HAL_CANDeviceType deviceType; int32_t busId; uint8_t deviceId; - wpi::mutex periodicSendsMutex; - wpi::SmallDenseMap periodicSends; - wpi::mutex receivesMutex; - wpi::SmallDenseMap receives; + wpi::util::mutex periodicSendsMutex; + wpi::util::SmallDenseMap periodicSends; + wpi::util::mutex receivesMutex; + wpi::util::SmallDenseMap receives; }; } // namespace static UnlimitedHandleResource* canHandles; -namespace hal::init { +namespace wpi::hal::init { void InitializeCANAPI() { static UnlimitedHandleResource cH; canHandles = &cH; } -} // namespace hal::init +} // namespace wpi::hal::init static int32_t CreateCANId(CANStorage* storage, int32_t apiId) { int32_t createdId = 0; @@ -56,9 +56,9 @@ extern "C" { HAL_CANHandle HAL_InitializeCAN(int32_t busId, HAL_CANManufacturer manufacturer, int32_t deviceId, HAL_CANDeviceType deviceType, int32_t* status) { - hal::init::CheckInit(); + wpi::hal::init::CheckInit(); - if (busId < 0 || busId > hal::kNumCanBuses) { + if (busId < 0 || busId > wpi::hal::kNumCanBuses) { *status = PARAMETER_OUT_OF_RANGE; return HAL_kInvalidHandle; } @@ -231,7 +231,7 @@ void HAL_ReadCANPacketTimeout(HAL_CANHandle handle, int32_t apiId, auto i = can->receives.find(messageId); if (i != can->receives.end()) { // Found, check if new enough - uint64_t now = wpi::Now(); + uint64_t now = wpi::util::Now(); if (now - i->second.timeStamp > (static_cast(timeoutMs) * 1000)) { // Timeout, return bad status diff --git a/hal/src/main/native/systemcore/CANInternal.h b/hal/src/main/native/systemcore/CANInternal.h index d60d845111..7d453b6849 100644 --- a/hal/src/main/native/systemcore/CANInternal.h +++ b/hal/src/main/native/systemcore/CANInternal.h @@ -4,6 +4,6 @@ #pragma once -namespace hal { +namespace wpi::hal { bool InitializeCanBuses(); -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/main/native/systemcore/CTREPCM.cpp b/hal/src/main/native/systemcore/CTREPCM.cpp index b996b832e0..dc738e70dd 100644 --- a/hal/src/main/native/systemcore/CTREPCM.cpp +++ b/hal/src/main/native/systemcore/CTREPCM.cpp @@ -15,7 +15,7 @@ #include "wpi/hal/Errors.h" #include "wpi/hal/handles/IndexedHandleResource.h" -using namespace hal; +using namespace wpi::hal; static constexpr HAL_CANManufacturer manufacturer = HAL_CANManufacturer::HAL_CAN_Man_kCTRE; @@ -126,7 +126,7 @@ union PcmDebug { namespace { struct PCM { HAL_CANHandle canHandle; - wpi::mutex lock; + wpi::util::mutex lock; std::string previousAllocation; PcmControl control; PcmControlSetOneShotDur oneShot; @@ -136,14 +136,14 @@ struct PCM { static IndexedHandleResource* pcmHandles; -namespace hal::init { +namespace wpi::hal::init { void InitializeCTREPCM() { static IndexedHandleResource pH; pcmHandles = &pH; } -} // namespace hal::init +} // namespace wpi::hal::init #define READ_PACKET(type, frame, failureValue) \ auto pcm = pcmHandles->Get(handle); \ @@ -178,17 +178,17 @@ extern "C" { HAL_CTREPCMHandle HAL_InitializeCTREPCM(int32_t busId, int32_t module, const char* allocationLocation, int32_t* status) { - hal::init::CheckInit(); + wpi::hal::init::CheckInit(); HAL_CTREPCMHandle handle; auto pcm = pcmHandles->Allocate(module, &handle, status); if (*status != 0) { if (pcm) { - hal::SetLastErrorPreviouslyAllocated(status, "CTRE PCM", module, + wpi::hal::SetLastErrorPreviouslyAllocated(status, "CTRE PCM", module, pcm->previousAllocation); } else { - hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for CTRE PCM", 0, + wpi::hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for CTRE PCM", 0, kNumCTREPCMModules - 1, module); } return HAL_kInvalidHandle; // failed to allocate. Pass error back. @@ -360,7 +360,7 @@ void HAL_FireCTREPCMOneShot(HAL_CTREPCMHandle handle, int32_t index, int32_t* status) { if (index > 7 || index < 0) { *status = PARAMETER_OUT_OF_RANGE; - hal::SetLastError( + wpi::hal::SetLastError( status, fmt::format("Only [0-7] are valid index values. Requested {}", index)); return; @@ -392,7 +392,7 @@ void HAL_SetCTREPCMOneShotDuration(HAL_CTREPCMHandle handle, int32_t index, int32_t durMs, int32_t* status) { if (index > 7 || index < 0) { *status = PARAMETER_OUT_OF_RANGE; - hal::SetLastError( + wpi::hal::SetLastError( status, fmt::format("Only [0-7] are valid index values. Requested {}", index)); return; diff --git a/hal/src/main/native/systemcore/CTREPDP.cpp b/hal/src/main/native/systemcore/CTREPDP.cpp index 231762dce5..c5482a11d0 100644 --- a/hal/src/main/native/systemcore/CTREPDP.cpp +++ b/hal/src/main/native/systemcore/CTREPDP.cpp @@ -17,7 +17,7 @@ #include "wpi/hal/handles/IndexedHandleResource.h" #include "wpi/util/mutex.hpp" -using namespace hal; +using namespace wpi::hal; static constexpr HAL_CANManufacturer manufacturer = HAL_CANManufacturer::HAL_CAN_Man_kCTRE; @@ -118,24 +118,24 @@ struct PDP { static IndexedHandleResource* pdpHandles; -namespace hal::init { +namespace wpi::hal::init { void InitializeCTREPDP() { static IndexedHandleResource pH; pdpHandles = &pH; } -} // namespace hal::init +} // namespace wpi::hal::init extern "C" { HAL_PDPHandle HAL_InitializePDP(int32_t busId, int32_t module, const char* allocationLocation, int32_t* status) { - hal::init::CheckInit(); + wpi::hal::init::CheckInit(); if (!HAL_CheckPDPModule(module)) { *status = RESOURCE_OUT_OF_RANGE; - hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for CTRE PDP", 0, + wpi::hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for CTRE PDP", 0, kNumCTREPDPModules - 1, module); return HAL_kInvalidHandle; } @@ -145,10 +145,10 @@ HAL_PDPHandle HAL_InitializePDP(int32_t busId, int32_t module, if (*status != 0) { if (pdp) { - hal::SetLastErrorPreviouslyAllocated(status, "CTRE PDP", module, + wpi::hal::SetLastErrorPreviouslyAllocated(status, "CTRE PDP", module, pdp->previousAllocation); } else { - hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for CTRE PDP", 0, + wpi::hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for CTRE PDP", 0, kNumCTREPDPModules - 1, module); } return HAL_kInvalidHandle; // failed to allocate. Pass error back. @@ -175,7 +175,7 @@ void HAL_CleanPDP(HAL_PDPHandle handle) { } int32_t HAL_GetPDPModuleNumber(HAL_PDPHandle handle, int32_t* status) { - return hal::getHandleIndex(handle); + return wpi::hal::getHandleIndex(handle); } HAL_Bool HAL_CheckPDPModule(int32_t module) { @@ -232,7 +232,7 @@ double HAL_GetPDPChannelCurrent(HAL_PDPHandle handle, int32_t channel, int32_t* status) { if (!HAL_CheckPDPChannel(channel)) { *status = PARAMETER_OUT_OF_RANGE; - hal::SetLastError(status, fmt::format("Invalid pdp channel {}", channel)); + wpi::hal::SetLastError(status, fmt::format("Invalid pdp channel {}", channel)); return 0; } diff --git a/hal/src/main/native/systemcore/Constants.cpp b/hal/src/main/native/systemcore/Constants.cpp index d52692612a..795544e637 100644 --- a/hal/src/main/native/systemcore/Constants.cpp +++ b/hal/src/main/native/systemcore/Constants.cpp @@ -6,11 +6,11 @@ #include "ConstantsInternal.h" -using namespace hal; +using namespace wpi::hal; -namespace hal::init { +namespace wpi::hal::init { void InitializeConstants() {} -} // namespace hal::init +} // namespace wpi::hal::init extern "C" { int32_t HAL_GetSystemClockTicksPerMicrosecond(void) { diff --git a/hal/src/main/native/systemcore/ConstantsInternal.h b/hal/src/main/native/systemcore/ConstantsInternal.h index f4af049d4f..1afdd66979 100644 --- a/hal/src/main/native/systemcore/ConstantsInternal.h +++ b/hal/src/main/native/systemcore/ConstantsInternal.h @@ -6,6 +6,6 @@ #include -namespace hal { +namespace wpi::hal { constexpr int32_t kSystemClockTicksPerMicrosecond = 40; -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/main/native/systemcore/Counter.cpp b/hal/src/main/native/systemcore/Counter.cpp index 2970d656c5..5cb4d73402 100644 --- a/hal/src/main/native/systemcore/Counter.cpp +++ b/hal/src/main/native/systemcore/Counter.cpp @@ -19,21 +19,21 @@ #include "wpi/hal/cpp/fpga_clock.h" #include "wpi/hal/handles/LimitedHandleResource.h" -using namespace hal; +using namespace wpi::hal; -namespace hal::init { +namespace wpi::hal::init { void InitializeCounter() {} -} // namespace hal::init +} // namespace wpi::hal::init extern "C" { HAL_CounterHandle HAL_InitializeCounter(int channel, HAL_Bool risingEdge, const char* allocationLocation, int32_t* status) { - hal::init::CheckInit(); + wpi::hal::init::CheckInit(); if (channel == InvalidHandleIndex || channel >= kNumSmartIo) { *status = RESOURCE_OUT_OF_RANGE; - hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for Counter", 0, + wpi::hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for Counter", 0, kNumSmartIo, channel); return HAL_kInvalidHandle; } @@ -45,10 +45,10 @@ HAL_CounterHandle HAL_InitializeCounter(int channel, HAL_Bool risingEdge, if (*status != 0) { if (port) { - hal::SetLastErrorPreviouslyAllocated(status, "SmartIo", channel, + wpi::hal::SetLastErrorPreviouslyAllocated(status, "SmartIo", channel, port->previousAllocation); } else { - hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for Counter", 0, + wpi::hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for Counter", 0, kNumSmartIo, channel); } return HAL_kInvalidHandle; // failed to allocate. Pass error back. @@ -78,9 +78,9 @@ void HAL_FreeCounter(HAL_CounterHandle counterHandle) { smartIoHandles->Free(counterHandle, HAL_HandleEnum::Counter); // Wait for no other object to hold this handle. - auto start = hal::fpga_clock::now(); + auto start = wpi::hal::fpga_clock::now(); while (port.use_count() != 1) { - auto current = hal::fpga_clock::now(); + auto current = wpi::hal::fpga_clock::now(); if (start + std::chrono::seconds(1) < current) { std::puts("DIO handle free timeout"); std::fflush(stdout); diff --git a/hal/src/main/native/systemcore/DIO.cpp b/hal/src/main/native/systemcore/DIO.cpp index c65b294f5f..b8850828dc 100644 --- a/hal/src/main/native/systemcore/DIO.cpp +++ b/hal/src/main/native/systemcore/DIO.cpp @@ -17,22 +17,22 @@ #include "wpi/hal/handles/HandlesInternal.h" #include "wpi/hal/handles/LimitedHandleResource.h" -using namespace hal; +using namespace wpi::hal; -namespace hal::init { +namespace wpi::hal::init { void InitializeDIO() {} -} // namespace hal::init +} // namespace wpi::hal::init extern "C" { HAL_DigitalHandle HAL_InitializeDIOPort(int32_t channel, HAL_Bool input, const char* allocationLocation, int32_t* status) { - hal::init::CheckInit(); + wpi::hal::init::CheckInit(); if (channel < 0 || channel >= kNumSmartIo) { *status = RESOURCE_OUT_OF_RANGE; - hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for DIO", 0, + wpi::hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for DIO", 0, kNumSmartIo, channel); return HAL_kInvalidHandle; } @@ -44,10 +44,10 @@ HAL_DigitalHandle HAL_InitializeDIOPort(int32_t channel, HAL_Bool input, if (*status != 0) { if (port) { - hal::SetLastErrorPreviouslyAllocated(status, "SmartIo", channel, + wpi::hal::SetLastErrorPreviouslyAllocated(status, "SmartIo", channel, port->previousAllocation); } else { - hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for DIO", 0, + wpi::hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for DIO", 0, kNumSmartIo, channel); } return HAL_kInvalidHandle; // failed to allocate. Pass error back. @@ -80,9 +80,9 @@ void HAL_FreeDIOPort(HAL_DigitalHandle dioPortHandle) { smartIoHandles->Free(dioPortHandle, HAL_HandleEnum::DIO); // Wait for no other object to hold this handle. - auto start = hal::fpga_clock::now(); + auto start = wpi::hal::fpga_clock::now(); while (port.use_count() != 1) { - auto current = hal::fpga_clock::now(); + auto current = wpi::hal::fpga_clock::now(); if (start + std::chrono::seconds(1) < current) { std::puts("DIO handle free timeout"); std::fflush(stdout); diff --git a/hal/src/main/native/systemcore/DutyCycle.cpp b/hal/src/main/native/systemcore/DutyCycle.cpp index 260dd6cecd..b19ea5ec85 100644 --- a/hal/src/main/native/systemcore/DutyCycle.cpp +++ b/hal/src/main/native/systemcore/DutyCycle.cpp @@ -17,21 +17,21 @@ #include "wpi/hal/handles/HandlesInternal.h" #include "wpi/hal/handles/LimitedHandleResource.h" -using namespace hal; +using namespace wpi::hal; -namespace hal::init { +namespace wpi::hal::init { void InitializeDutyCycle() {} -} // namespace hal::init +} // namespace wpi::hal::init extern "C" { HAL_DutyCycleHandle HAL_InitializeDutyCycle(int32_t channel, const char* allocationLocation, int32_t* status) { - hal::init::CheckInit(); + wpi::hal::init::CheckInit(); if (channel < 0 || channel >= kNumSmartIo) { *status = RESOURCE_OUT_OF_RANGE; - hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for DutyCycle", 0, + wpi::hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for DutyCycle", 0, kNumSmartIo, channel); return HAL_kInvalidHandle; } @@ -43,10 +43,10 @@ HAL_DutyCycleHandle HAL_InitializeDutyCycle(int32_t channel, if (*status != 0) { if (port) { - hal::SetLastErrorPreviouslyAllocated(status, "SmartIo", channel, + wpi::hal::SetLastErrorPreviouslyAllocated(status, "SmartIo", channel, port->previousAllocation); } else { - hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for DutyCycle", 0, + wpi::hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for DutyCycle", 0, kNumSmartIo, channel); } return HAL_kInvalidHandle; // failed to allocate. Pass error back. @@ -73,9 +73,9 @@ void HAL_FreeDutyCycle(HAL_DutyCycleHandle dutyCycleHandle) { smartIoHandles->Free(dutyCycleHandle, HAL_HandleEnum::DutyCycle); // Wait for no other object to hold this handle. - auto start = hal::fpga_clock::now(); + auto start = wpi::hal::fpga_clock::now(); while (port.use_count() != 1) { - auto current = hal::fpga_clock::now(); + auto current = wpi::hal::fpga_clock::now(); if (start + std::chrono::seconds(1) < current) { std::puts("DIO handle free timeout"); std::fflush(stdout); diff --git a/hal/src/main/native/systemcore/Encoder.cpp b/hal/src/main/native/systemcore/Encoder.cpp index d3a1f38542..9959c11032 100644 --- a/hal/src/main/native/systemcore/Encoder.cpp +++ b/hal/src/main/native/systemcore/Encoder.cpp @@ -15,18 +15,18 @@ #include "wpi/hal/Errors.h" #include "wpi/hal/handles/LimitedClassedHandleResource.h" -using namespace hal; +using namespace wpi::hal; -namespace hal::init { +namespace wpi::hal::init { void InitializeEncoder() {} -} // namespace hal::init +} // namespace wpi::hal::init extern "C" { HAL_EncoderHandle HAL_InitializeEncoder(int32_t aChannel, int32_t bChannel, HAL_Bool reverseDirection, HAL_EncoderEncodingType encodingType, int32_t* status) { - hal::init::CheckInit(); + wpi::hal::init::CheckInit(); *status = HAL_HANDLE_ERROR; return HAL_kInvalidHandle; } diff --git a/hal/src/main/native/systemcore/FRCDriverStation.cpp b/hal/src/main/native/systemcore/FRCDriverStation.cpp index 7454dd0e4a..ed64ebc1f6 100644 --- a/hal/src/main/native/systemcore/FRCDriverStation.cpp +++ b/hal/src/main/native/systemcore/FRCDriverStation.cpp @@ -62,43 +62,43 @@ static_assert(std::is_standard_layout_v); // static_assert(std::is_trivial_v); struct SystemServerDriverStation { - nt::NetworkTableInstance ntInst; - nt::BooleanPublisher hasUserCodePublisher; - nt::BooleanPublisher hasUserCodeReadyPublisher; + wpi::nt::NetworkTableInstance ntInst; + wpi::nt::BooleanPublisher hasUserCodePublisher; + wpi::nt::BooleanPublisher hasUserCodeReadyPublisher; - nt::BooleanSubscriber hasSetWallClockSubscriber; + wpi::nt::BooleanSubscriber hasSetWallClockSubscriber; - nt::ProtobufSubscriber controlDataSubscriber; - nt::ProtobufSubscriber matchInfoSubscriber; - nt::StringSubscriber gameSpecificMessageSubscriber; + wpi::nt::ProtobufSubscriber controlDataSubscriber; + wpi::nt::ProtobufSubscriber matchInfoSubscriber; + wpi::nt::StringSubscriber gameSpecificMessageSubscriber; - std::array, + std::array, MRC_MAX_NUM_JOYSTICKS> joystickDescriptorTopics; - nt::StringPublisher versionPublisher; - nt::StringPublisher consoleLinePublisher; - nt::ProtobufPublisher errorInfoPublisher; + wpi::nt::StringPublisher versionPublisher; + wpi::nt::StringPublisher consoleLinePublisher; + wpi::nt::ProtobufPublisher errorInfoPublisher; - std::array, + std::array, MRC_MAX_NUM_JOYSTICKS> joystickRumbleTopics; - nt::ProtobufPublisher> teleopOpModes; - nt::ProtobufPublisher> autoOpModes; - nt::ProtobufPublisher> testOpModes; - nt::IntegerPublisher traceOpModePublisher; + wpi::nt::ProtobufPublisher> teleopOpModes; + wpi::nt::ProtobufPublisher> autoOpModes; + wpi::nt::ProtobufPublisher> testOpModes; + wpi::nt::IntegerPublisher traceOpModePublisher; NT_Listener controlDataListener; - wpi::mutex controlDataMutex; - wpi::ProtobufMessage controlDataMsg; - nt::Value lastValue; + wpi::util::mutex controlDataMutex; + wpi::util::ProtobufMessage controlDataMsg; + wpi::nt::Value lastValue; - explicit SystemServerDriverStation(nt::NetworkTableInstance inst) { + explicit SystemServerDriverStation(wpi::nt::NetworkTableInstance inst) { ntInst = inst; - nt::PubSubOptions options; + wpi::nt::PubSubOptions options; options.sendAll = true; options.keepDuplicates = true; options.periodic = 0.005; @@ -179,7 +179,7 @@ struct SystemServerDriverStation { ntInst.AddListener( controlDataSubscriber, NT_EVENT_VALUE_REMOTE | NT_EVENT_UNPUBLISH, - [this](const nt::Event& event) { HandleListener(event); }); + [this](const wpi::nt::Event& event) { HandleListener(event); }); traceOpModePublisher = ntInst.GetIntegerTopic(ROBOT_CURRENT_OPMODE_TRACE_PATH) @@ -187,7 +187,7 @@ struct SystemServerDriverStation { traceOpModePublisher.GetTopic().SetCached(false); } - void HandleListener(const nt::Event& event); + void HandleListener(const wpi::nt::Event& event); bool GetLastControlData(mrc::ControlData* data, int64_t* time) { std::scoped_lock lock{controlDataMutex}; @@ -205,14 +205,14 @@ struct SystemServerDriverStation { }; struct FRCDriverStation { - wpi::EventVector newDataEvents; + wpi::util::EventVector newDataEvents; }; } // namespace static ::SystemServerDriverStation* systemServerDs; static ::FRCDriverStation* driverStation; -void SystemServerDriverStation::HandleListener(const nt::Event& event) { +void SystemServerDriverStation::HandleListener(const wpi::nt::Event& event) { auto valueEvent = event.GetValueEventData(); bool isValid = valueEvent && valueEvent->value.IsRaw(); @@ -224,7 +224,7 @@ void SystemServerDriverStation::HandleListener(const nt::Event& event) { } else { // We've either been unpublished, or type changed. // Treat either as a disconnect. - lastValue = nt::Value{}; + lastValue = wpi::nt::Value{}; } } if (isValid) { @@ -233,7 +233,7 @@ void SystemServerDriverStation::HandleListener(const nt::Event& event) { } // Message and Data variables -static wpi::mutex msgMutex; +static wpi::util::mutex msgMutex; void JoystickDataCache::Update(const mrc::ControlData& data) { matchTime = data.MatchTime; @@ -288,7 +288,7 @@ static JoystickDataCache caches[2]; static JoystickDataCache* currentRead = &caches[0]; static JoystickDataCache* cacheToUpdate = &caches[1]; -static wpi::mutex cacheMutex; +static wpi::util::mutex cacheMutex; namespace { struct TcpCache { @@ -306,7 +306,7 @@ static TcpCache tcpCaches[2]; static TcpCache* tcpCurrentRead = &tcpCaches[0]; static TcpCache* tcpCacheToUpdate = &tcpCaches[1]; -static wpi::mutex tcpCacheMutex; +static wpi::util::mutex tcpCacheMutex; void TcpCache::Update() { auto newMatchInfo = systemServerDs->matchInfoSubscriber.Get(); @@ -353,22 +353,22 @@ void TcpCache::Update() { } } -namespace hal::init { +namespace wpi::hal::init { void InitializeFRCDriverStation() { std::memset(&newestControlWord, 0, sizeof(newestControlWord)); static FRCDriverStation ds; driverStation = &ds; } -} // namespace hal::init +} // namespace wpi::hal::init -namespace hal { +namespace wpi::hal { static void DefaultPrintErrorImpl(const char* line, size_t size) { std::fwrite(line, size, 1, stderr); } -} // namespace hal +} // namespace wpi::hal static std::atomic gPrintErrorImpl{ - hal::DefaultPrintErrorImpl}; + wpi::hal::DefaultPrintErrorImpl}; extern "C" { @@ -446,7 +446,7 @@ int32_t HAL_SendError(HAL_Bool isError, int32_t errorCode, HAL_Bool isLVCode, } void HAL_SetPrintErrorImpl(void (*func)(const char* line, size_t size)) { - gPrintErrorImpl.store(func ? func : hal::DefaultPrintErrorImpl); + gPrintErrorImpl.store(func ? func : wpi::hal::DefaultPrintErrorImpl); } int32_t HAL_SendConsoleLine(const char* line) { @@ -592,7 +592,7 @@ HAL_Bool HAL_RefreshDSData(void) { int64_t dataTime{0}; bool dataValid = systemServerDs->GetLastControlData(&newestData, &dataTime); - // auto now = wpi::Now(); + // auto now = wpi::util::Now(); // auto delta = now - dataTime; bool updatedData = false; @@ -622,7 +622,7 @@ HAL_Bool HAL_RefreshDSData(void) { } void HAL_ProvideNewDataEventHandle(WPI_EventHandle handle) { - hal::init::CheckInit(); + wpi::hal::init::CheckInit(); driverStation->newDataEvents.Add(handle); } @@ -640,17 +640,17 @@ HAL_Bool HAL_GetSystemTimeValid(int32_t* status) { } // extern "C" -namespace hal { +namespace wpi::hal { void InitializeDriverStation() { - systemServerDs = new ::SystemServerDriverStation{hal::GetSystemServer()}; + systemServerDs = new ::SystemServerDriverStation{wpi::hal::GetSystemServer()}; } void WaitForInitialPacket() { - wpi::Event waitForInitEvent; + wpi::util::Event waitForInitEvent; driverStation->newDataEvents.Add(waitForInitEvent.GetHandle()); bool timed_out = false; - wpi::WaitForObject(waitForInitEvent.GetHandle(), 0.1, &timed_out); + wpi::util::WaitForObject(waitForInitEvent.GetHandle(), 0.1, &timed_out); // Don't care what the result is, just want to give it a chance. driverStation->newDataEvents.Remove(waitForInitEvent.GetHandle()); } -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/main/native/systemcore/HAL.cpp b/hal/src/main/native/systemcore/HAL.cpp index 6a3db125f6..a5e0f311f0 100644 --- a/hal/src/main/native/systemcore/HAL.cpp +++ b/hal/src/main/native/systemcore/HAL.cpp @@ -32,15 +32,15 @@ #include "wpi/util/print.hpp" #include "wpi/util/timestamp.h" -using namespace hal; +using namespace wpi::hal; static uint64_t dsStartTime; static int32_t teamNumber = -1; -using namespace hal; +using namespace wpi::hal; -namespace hal { +namespace wpi::hal { void InitializeDriverStation(); void WaitForInitialPacket(); namespace init { @@ -77,7 +77,7 @@ uint64_t GetDSInitializeTime() { return dsStartTime; } -} // namespace hal +} // namespace wpi::hal extern "C" { @@ -199,9 +199,9 @@ void InitializeTeamNumber(void) { // Split string around '-' (max of 2 splits), take the second element teamNumber = 0; int i = 0; - wpi::split(hostname, '-', 2, false, [&](auto part) { + wpi::util::split(hostname, '-', 2, false, [&](auto part) { if (i == 1) { - teamNumber = wpi::parse_integer(part, 10).value_or(0); + teamNumber = wpi::util::parse_integer(part, 10).value_or(0); } ++i; }); @@ -215,8 +215,8 @@ int32_t HAL_GetTeamNumber(void) { } uint64_t HAL_GetFPGATime(int32_t* status) { - hal::init::CheckInit(); - return wpi::NowDefault(); + wpi::hal::init::CheckInit(); + return wpi::util::NowDefault(); } uint64_t HAL_ExpandFPGATime(uint32_t unexpandedLower, int32_t* status) { @@ -244,32 +244,32 @@ uint64_t HAL_ExpandFPGATime(uint32_t unexpandedLower, int32_t* status) { } HAL_Bool HAL_GetSystemActive(int32_t* status) { - hal::init::CheckInit(); + wpi::hal::init::CheckInit(); *status = HAL_HANDLE_ERROR; return false; } HAL_Bool HAL_GetBrownedOut(int32_t* status) { - hal::init::CheckInit(); + wpi::hal::init::CheckInit(); *status = HAL_HANDLE_ERROR; return false; } int32_t HAL_GetCommsDisableCount(int32_t* status) { - hal::init::CheckInit(); + wpi::hal::init::CheckInit(); *status = HAL_HANDLE_ERROR; return 0; } HAL_Bool HAL_GetRSLState(int32_t* status) { - hal::init::CheckInit(); + wpi::hal::init::CheckInit(); *status = HAL_HANDLE_ERROR; return false; } HAL_Bool HAL_Initialize(int32_t timeout, int32_t mode) { static std::atomic_bool initialized{false}; - static wpi::mutex initializeMutex; + static wpi::util::mutex initializeMutex; // Initial check, as if it's true initialization has finished if (initialized) { return true; @@ -282,18 +282,18 @@ HAL_Bool HAL_Initialize(int32_t timeout, int32_t mode) { } // Initialize system server first, other things might use it - hal::InitializeSystemServer(); + wpi::hal::InitializeSystemServer(); - hal::init::InitializeHAL(); + wpi::hal::init::InitializeHAL(); - hal::init::HAL_IsInitialized.store(true); + wpi::hal::init::HAL_IsInitialized.store(true); setlinebuf(stdin); setlinebuf(stdout); prctl(PR_SET_PDEATHSIG, SIGTERM); - if (!hal::InitializeCanBuses()) { + if (!wpi::hal::InitializeCanBuses()) { std::printf("Failed to initialize can buses\n"); return false; } @@ -307,14 +307,14 @@ HAL_Bool HAL_Initialize(int32_t timeout, int32_t mode) { int32_t status = 0; - hal::InitializeDriverStation(); + wpi::hal::InitializeDriverStation(); dsStartTime = HAL_GetFPGATime(&status); if (status != 0) { return false; } - hal::WaitForInitialPacket(); + wpi::hal::WaitForInitialPacket(); initialized = true; return true; diff --git a/hal/src/main/native/systemcore/HALInitializer.cpp b/hal/src/main/native/systemcore/HALInitializer.cpp index 84ba73e6d4..4312571b81 100644 --- a/hal/src/main/native/systemcore/HALInitializer.cpp +++ b/hal/src/main/native/systemcore/HALInitializer.cpp @@ -6,9 +6,9 @@ #include "wpi/hal/HALBase.h" -namespace hal::init { +namespace wpi::hal::init { std::atomic_bool HAL_IsInitialized{false}; void RunInitialize() { HAL_Initialize(500, 0); } -} // namespace hal::init +} // namespace wpi::hal::init diff --git a/hal/src/main/native/systemcore/HALInitializer.h b/hal/src/main/native/systemcore/HALInitializer.h index 558f574207..070f0ac955 100644 --- a/hal/src/main/native/systemcore/HALInitializer.h +++ b/hal/src/main/native/systemcore/HALInitializer.h @@ -6,7 +6,7 @@ #include -namespace hal::init { +namespace wpi::hal::init { extern std::atomic_bool HAL_IsInitialized; extern void RunInitialize(); inline void CheckInit() { @@ -44,4 +44,4 @@ extern void InitializeSerialPort(); extern void InitializeSmartIo(); extern void InitializeThreads(); extern void InitializeUsageReporting(); -} // namespace hal::init +} // namespace wpi::hal::init diff --git a/hal/src/main/native/systemcore/HALInternal.h b/hal/src/main/native/systemcore/HALInternal.h index b384b51bfa..628763c9ed 100644 --- a/hal/src/main/native/systemcore/HALInternal.h +++ b/hal/src/main/native/systemcore/HALInternal.h @@ -8,7 +8,7 @@ #include -namespace hal { +namespace wpi::hal { void SetLastError(int32_t* status, std::string_view value); void SetLastErrorIndexOutOfRange(int32_t* status, std::string_view message, int32_t minimum, int32_t maximum, @@ -17,4 +17,4 @@ void SetLastErrorPreviouslyAllocated(int32_t* status, std::string_view message, int32_t channel, std::string_view previousAllocation); uint64_t GetDSInitializeTime(); -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/main/native/systemcore/I2C.cpp b/hal/src/main/native/systemcore/I2C.cpp index 09f6ef6dc8..502e38c296 100644 --- a/hal/src/main/native/systemcore/I2C.cpp +++ b/hal/src/main/native/systemcore/I2C.cpp @@ -22,14 +22,14 @@ #include "wpi/util/mutex.hpp" #include "wpi/util/print.hpp" -using namespace hal; +using namespace wpi::hal; namespace { constexpr const char* physicalPorts[kNumI2cBuses] = {"/dev/i2c-10", "/dev/i2c-1"}; struct I2C { - wpi::mutex initMutex; + wpi::util::mutex initMutex; int objCount = 0; int fd = -1; }; @@ -37,17 +37,17 @@ struct I2C { static I2C i2cObjs[kNumI2cBuses]; } // namespace -namespace hal::init { +namespace wpi::hal::init { void InitializeI2C() {} -} // namespace hal::init +} // namespace wpi::hal::init extern "C" { void HAL_InitializeI2C(HAL_I2CPort port, int32_t* status) { - hal::init::CheckInit(); + wpi::hal::init::CheckInit(); if (port < 0 || port > 2) { *status = RESOURCE_OUT_OF_RANGE; - hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for I2C", 0, 1, + wpi::hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for I2C", 0, 1, port); return; } @@ -61,9 +61,9 @@ void HAL_InitializeI2C(HAL_I2CPort port, int32_t* status) { if (handle < 0) { int err = errno; *status = NO_AVAILABLE_RESOURCES; - hal::SetLastError(status, fmt::format("Failed to open onboard i2c bus: {}", + wpi::hal::SetLastError(status, fmt::format("Failed to open onboard i2c bus: {}", std::strerror(err))); - wpi::print("Failed to open onboard i2c bus: {}\n", std::strerror(err)); + wpi::util::print("Failed to open onboard i2c bus: {}\n", std::strerror(err)); handle = -1; i2cObjs[port].objCount--; return; @@ -76,7 +76,7 @@ int32_t HAL_TransactionI2C(HAL_I2CPort port, int32_t deviceAddress, uint8_t* dataReceived, int32_t receiveSize) { if (port < 0 || port > 2) { int32_t status = 0; - hal::SetLastErrorIndexOutOfRange(&status, "Invalid Index for I2C", 0, 1, + wpi::hal::SetLastErrorIndexOutOfRange(&status, "Invalid Index for I2C", 0, 1, port); return -1; } @@ -103,7 +103,7 @@ int32_t HAL_WriteI2C(HAL_I2CPort port, int32_t deviceAddress, const uint8_t* dataToSend, int32_t sendSize) { if (port < 0 || port > 2) { int32_t status = 0; - hal::SetLastErrorIndexOutOfRange(&status, "Invalid Index for I2C", 0, 2, + wpi::hal::SetLastErrorIndexOutOfRange(&status, "Invalid Index for I2C", 0, 2, port); return -1; } @@ -126,7 +126,7 @@ int32_t HAL_ReadI2C(HAL_I2CPort port, int32_t deviceAddress, uint8_t* buffer, int32_t count) { if (port < 0 || port > 2) { int32_t status = 0; - hal::SetLastErrorIndexOutOfRange(&status, "Invalid Index for I2C", 0, 1, + wpi::hal::SetLastErrorIndexOutOfRange(&status, "Invalid Index for I2C", 0, 1, port); return -1; } @@ -148,7 +148,7 @@ int32_t HAL_ReadI2C(HAL_I2CPort port, int32_t deviceAddress, uint8_t* buffer, void HAL_CloseI2C(HAL_I2CPort port) { if (port < 0 || port > 2) { int32_t status = 0; - hal::SetLastErrorIndexOutOfRange(&status, "Invalid Index for I2C", 0, 1, + wpi::hal::SetLastErrorIndexOutOfRange(&status, "Invalid Index for I2C", 0, 1, port); return; } diff --git a/hal/src/main/native/systemcore/IMU.cpp b/hal/src/main/native/systemcore/IMU.cpp index 2e2eb7b22d..96abc1f541 100644 --- a/hal/src/main/native/systemcore/IMU.cpp +++ b/hal/src/main/native/systemcore/IMU.cpp @@ -28,7 +28,7 @@ constexpr const char* kYawLandscapeKey = IMU_PREFIX "yaw_landscape"; constexpr const char* kYawPortraitKey = IMU_PREFIX "yaw_portrait"; struct IMU { - explicit IMU(nt::NetworkTableInstance inst) + explicit IMU(wpi::nt::NetworkTableInstance inst) : rawAccelSub{inst.GetDoubleArrayTopic(kRawAccelKey).Subscribe({})}, rawGyroSub{inst.GetDoubleArrayTopic(kRawGyroKey).Subscribe({})}, quatSub{inst.GetDoubleArrayTopic(kQuaternionKey).Subscribe({})}, @@ -42,15 +42,15 @@ struct IMU { yawLandscapeSub{inst.GetDoubleTopic(kYawLandscapeKey).Subscribe(0)}, yawPortraitSub{inst.GetDoubleTopic(kYawPortraitKey).Subscribe(0)} {} - nt::DoubleArraySubscriber rawAccelSub; - nt::DoubleArraySubscriber rawGyroSub; - nt::DoubleArraySubscriber quatSub; - nt::DoubleArraySubscriber eulerFlatSub; - nt::DoubleArraySubscriber eulerLandscapeSub; - nt::DoubleArraySubscriber eulerPortraitSub; - nt::DoubleSubscriber yawFlatSub; - nt::DoubleSubscriber yawLandscapeSub; - nt::DoubleSubscriber yawPortraitSub; + wpi::nt::DoubleArraySubscriber rawAccelSub; + wpi::nt::DoubleArraySubscriber rawGyroSub; + wpi::nt::DoubleArraySubscriber quatSub; + wpi::nt::DoubleArraySubscriber eulerFlatSub; + wpi::nt::DoubleArraySubscriber eulerLandscapeSub; + wpi::nt::DoubleArraySubscriber eulerPortraitSub; + wpi::nt::DoubleSubscriber yawFlatSub; + wpi::nt::DoubleSubscriber yawLandscapeSub; + wpi::nt::DoubleSubscriber yawPortraitSub; }; static IMU* imu; @@ -59,12 +59,12 @@ constexpr double kDegreesToRadians = std::numbers::pi / 180.0; constexpr double kGToMetersPerSecondSquared = 9.80665; } // namespace -namespace hal::init { +namespace wpi::hal::init { void InitializeIMU() { - static IMU imu_static{hal::GetSystemServer()}; + static IMU imu_static{wpi::hal::GetSystemServer()}; imu = &imu_static; } -} // namespace hal::init +} // namespace wpi::hal::init extern "C" { void HAL_GetIMUAcceleration(HAL_Acceleration3d* accel, int32_t* status) { diff --git a/hal/src/main/native/systemcore/Notifier.cpp b/hal/src/main/native/systemcore/Notifier.cpp index cbc2e0757b..9288aad5ee 100644 --- a/hal/src/main/native/systemcore/Notifier.cpp +++ b/hal/src/main/native/systemcore/Notifier.cpp @@ -29,15 +29,15 @@ struct Notifier { uint64_t waitTime = UINT64_MAX; bool active = true; bool waitTimeValid = false; // True if waitTime is set and in the future - wpi::mutex mutex; - wpi::condition_variable cond; + wpi::util::mutex mutex; + wpi::util::condition_variable cond; }; } // namespace -using namespace hal; +using namespace wpi::hal; -static wpi::mutex notifiersWaiterMutex; -static wpi::condition_variable notifiersWaiterCond; +static wpi::util::mutex notifiersWaiterMutex; +static wpi::util::condition_variable notifiersWaiterCond; class NotifierHandleContainer : public UnlimitedHandleResource notifier = std::make_shared(); HAL_NotifierHandle handle = notifierHandles->Allocate(notifier); if (handle == HAL_kInvalidHandle) { diff --git a/hal/src/main/native/systemcore/PWM.cpp b/hal/src/main/native/systemcore/PWM.cpp index af3048638e..df13831969 100644 --- a/hal/src/main/native/systemcore/PWM.cpp +++ b/hal/src/main/native/systemcore/PWM.cpp @@ -20,22 +20,22 @@ #include "wpi/hal/handles/HandlesInternal.h" #include "wpi/util/print.hpp" -using namespace hal; +using namespace wpi::hal; -namespace hal::init { +namespace wpi::hal::init { void InitializePWM() {} -} // namespace hal::init +} // namespace wpi::hal::init extern "C" { HAL_DigitalHandle HAL_InitializePWMPort(int32_t channel, const char* allocationLocation, int32_t* status) { - hal::init::CheckInit(); + wpi::hal::init::CheckInit(); if (channel < 0 || channel >= kNumSmartIo) { *status = RESOURCE_OUT_OF_RANGE; - hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for PWM", 0, + wpi::hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for PWM", 0, kNumSmartIo, channel); return HAL_kInvalidHandle; } @@ -47,10 +47,10 @@ HAL_DigitalHandle HAL_InitializePWMPort(int32_t channel, if (*status != 0) { if (port) { - hal::SetLastErrorPreviouslyAllocated(status, "SmartIo", channel, + wpi::hal::SetLastErrorPreviouslyAllocated(status, "SmartIo", channel, port->previousAllocation); } else { - hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for PWM", 0, + wpi::hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for PWM", 0, kNumSmartIo, channel); } return HAL_kInvalidHandle; // failed to allocate. Pass error back. @@ -85,9 +85,9 @@ void HAL_FreePWMPort(HAL_DigitalHandle pwmPortHandle) { smartIoHandles->Free(pwmPortHandle, HAL_HandleEnum::PWM); // Wait for no other object to hold this handle. - auto start = hal::fpga_clock::now(); + auto start = wpi::hal::fpga_clock::now(); while (port.use_count() != 1) { - auto current = hal::fpga_clock::now(); + auto current = wpi::hal::fpga_clock::now(); if (start + std::chrono::seconds(1) < current) { std::puts("PWM handle free timeout"); std::fflush(stdout); @@ -116,7 +116,7 @@ void HAL_SetPWMPulseTimeMicroseconds(HAL_DigitalHandle pwmPortHandle, if (microsecondPulseTime < 0 || (microsecondPulseTime != 0xFFFF && microsecondPulseTime >= 4096)) { *status = PARAMETER_OUT_OF_RANGE; - hal::SetLastError( + wpi::hal::SetLastError( status, fmt::format("Pulse time {} out of range. Expect [0-4096) or 0xFFFF", microsecondPulseTime)); @@ -149,14 +149,14 @@ void HAL_SetPWMOutputPeriod(HAL_DigitalHandle pwmPortHandle, int32_t period, switch (period) { case 0: - *status = port->SetPwmOutputPeriod(hal::PwmOutputPeriod::k5ms); + *status = port->SetPwmOutputPeriod(wpi::hal::PwmOutputPeriod::k5ms); break; case 1: case 2: - *status = port->SetPwmOutputPeriod(hal::PwmOutputPeriod::k10ms); + *status = port->SetPwmOutputPeriod(wpi::hal::PwmOutputPeriod::k10ms); break; case 3: - *status = port->SetPwmOutputPeriod(hal::PwmOutputPeriod::k20ms); + *status = port->SetPwmOutputPeriod(wpi::hal::PwmOutputPeriod::k20ms); break; default: *status = PARAMETER_OUT_OF_RANGE; diff --git a/hal/src/main/native/systemcore/Ports.cpp b/hal/src/main/native/systemcore/Ports.cpp index 121f068929..1fec512684 100644 --- a/hal/src/main/native/systemcore/Ports.cpp +++ b/hal/src/main/native/systemcore/Ports.cpp @@ -6,11 +6,11 @@ #include "PortsInternal.h" -using namespace hal; +using namespace wpi::hal; -namespace hal::init { +namespace wpi::hal::init { void InitializePorts() {} -} // namespace hal::init +} // namespace wpi::hal::init extern "C" { int32_t HAL_GetNumCanBuses(void) { diff --git a/hal/src/main/native/systemcore/PortsInternal.h b/hal/src/main/native/systemcore/PortsInternal.h index 5600d88bb2..bb3439ef5a 100644 --- a/hal/src/main/native/systemcore/PortsInternal.h +++ b/hal/src/main/native/systemcore/PortsInternal.h @@ -6,7 +6,7 @@ #include -namespace hal { +namespace wpi::hal { constexpr int32_t kNumCanBuses = 5; constexpr int32_t kNumSmartIo = 6; @@ -33,4 +33,4 @@ constexpr int32_t kNumAddressableLEDs = 6; constexpr int32_t kNumREVPHModules = 63; constexpr int32_t kNumREVPHChannels = 16; -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/main/native/systemcore/Power.cpp b/hal/src/main/native/systemcore/Power.cpp index c97001a3e4..0006da40f3 100644 --- a/hal/src/main/native/systemcore/Power.cpp +++ b/hal/src/main/native/systemcore/Power.cpp @@ -12,23 +12,23 @@ #include "wpi/hal/Errors.h" #include "wpi/nt/DoubleTopic.hpp" -using namespace hal; +using namespace wpi::hal; -namespace hal { +namespace wpi::hal { static void initializePower(int32_t* status) { - hal::init::CheckInit(); + wpi::hal::init::CheckInit(); } -} // namespace hal +} // namespace wpi::hal namespace { struct SystemServerPower { - nt::NetworkTableInstance ntInst; + wpi::nt::NetworkTableInstance ntInst; - nt::DoubleSubscriber batterySubscriber; + wpi::nt::DoubleSubscriber batterySubscriber; - explicit SystemServerPower(nt::NetworkTableInstance inst) { + explicit SystemServerPower(wpi::nt::NetworkTableInstance inst) { ntInst = inst; batterySubscriber = @@ -39,11 +39,11 @@ struct SystemServerPower { static ::SystemServerPower* systemServerPower; -namespace hal::init { +namespace wpi::hal::init { void InitializePower() { - systemServerPower = new ::SystemServerPower{hal::GetSystemServer()}; + systemServerPower = new ::SystemServerPower{wpi::hal::GetSystemServer()}; } -} // namespace hal::init +} // namespace wpi::hal::init extern "C" { diff --git a/hal/src/main/native/systemcore/PowerDistribution.cpp b/hal/src/main/native/systemcore/PowerDistribution.cpp index 5d667efd09..c9c6bf7778 100644 --- a/hal/src/main/native/systemcore/PowerDistribution.cpp +++ b/hal/src/main/native/systemcore/PowerDistribution.cpp @@ -15,7 +15,7 @@ #include "wpi/hal/HALBase.h" #include "wpi/hal/handles/HandlesInternal.h" -using namespace hal; +using namespace wpi::hal; extern "C" { @@ -25,12 +25,12 @@ HAL_PowerDistributionHandle HAL_InitializePowerDistribution( if (type == HAL_PowerDistributionType::HAL_PowerDistributionType_kAutomatic) { if (moduleNumber != HAL_DEFAULT_POWER_DISTRIBUTION_MODULE) { *status = PARAMETER_OUT_OF_RANGE; - hal::SetLastError( + wpi::hal::SetLastError( status, "Automatic PowerDistributionType must have default module"); return HAL_kInvalidHandle; } - uint64_t waitTime = hal::GetDSInitializeTime() + 400000; + uint64_t waitTime = wpi::hal::GetDSInitializeTime() + 400000; // Ensure we have been alive for long enough to receive a few Power packets. do { @@ -75,7 +75,7 @@ HAL_PowerDistributionHandle HAL_InitializePowerDistribution( } } -#define IsCtre(handle) ::hal::isHandleType(handle, HAL_HandleEnum::CTREPDP) +#define IsCtre(handle) ::wpi::hal::isHandleType(handle, HAL_HandleEnum::CTREPDP) void HAL_CleanPowerDistribution(HAL_PowerDistributionHandle handle) { if (IsCtre(handle)) { diff --git a/hal/src/main/native/systemcore/REVPDH.cpp b/hal/src/main/native/systemcore/REVPDH.cpp index a2b8ad2e4b..e8d26cdbf9 100644 --- a/hal/src/main/native/systemcore/REVPDH.cpp +++ b/hal/src/main/native/systemcore/REVPDH.cpp @@ -21,7 +21,7 @@ #include "wpi/hal/handles/HandlesInternal.h" #include "wpi/hal/handles/IndexedHandleResource.h" -using namespace hal; +using namespace wpi::hal; static constexpr HAL_CANManufacturer manufacturer = HAL_CANManufacturer::HAL_CAN_Man_kREV; @@ -77,14 +77,14 @@ static constexpr int32_t kPDHFrameStatus4Timeout = 20; static IndexedHandleResource* REVPDHHandles; -namespace hal::init { +namespace wpi::hal::init { void InitializeREVPDH() { static IndexedHandleResource rH; REVPDHHandles = &rH; } -} // namespace hal::init +} // namespace wpi::hal::init extern "C" { @@ -191,10 +191,10 @@ PDH_status_4_t HAL_GetREVPDHStatus4(HAL_REVPDHHandle handle, int32_t* status) { HAL_REVPDHHandle HAL_InitializeREVPDH(int32_t busId, int32_t module, const char* allocationLocation, int32_t* status) { - hal::init::CheckInit(); + wpi::hal::init::CheckInit(); if (!HAL_CheckREVPDHModuleNumber(module)) { *status = RESOURCE_OUT_OF_RANGE; - hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for REV PDH", 1, + wpi::hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for REV PDH", 1, kNumREVPDHModules, module); return HAL_kInvalidHandle; } @@ -204,10 +204,10 @@ HAL_REVPDHHandle HAL_InitializeREVPDH(int32_t busId, int32_t module, auto hpdh = REVPDHHandles->Allocate(module - 1, &handle, status); if (*status != 0) { if (hpdh) { - hal::SetLastErrorPreviouslyAllocated(status, "REV PDH", module, + wpi::hal::SetLastErrorPreviouslyAllocated(status, "REV PDH", module, hpdh->previousAllocation); } else { - hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for REV PDH", 1, + wpi::hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for REV PDH", 1, kNumREVPDHModules, module); } return HAL_kInvalidHandle; // failed to allocate. Pass error back. @@ -241,7 +241,7 @@ void HAL_FreeREVPDH(HAL_REVPDHHandle handle) { } int32_t HAL_GetREVPDHModuleNumber(HAL_REVPDHHandle handle, int32_t* status) { - return hal::getHandleIndex(handle); + return wpi::hal::getHandleIndex(handle); } HAL_Bool HAL_CheckREVPDHModuleNumber(int32_t module) { diff --git a/hal/src/main/native/systemcore/REVPH.cpp b/hal/src/main/native/systemcore/REVPH.cpp index 4a0cb7f01b..fa99da831b 100644 --- a/hal/src/main/native/systemcore/REVPH.cpp +++ b/hal/src/main/native/systemcore/REVPH.cpp @@ -17,7 +17,7 @@ #include "wpi/hal/Errors.h" #include "wpi/hal/handles/IndexedHandleResource.h" -using namespace hal; +using namespace wpi::hal; static constexpr HAL_CANManufacturer manufacturer = HAL_CANManufacturer::HAL_CAN_Man_kREV; @@ -63,7 +63,7 @@ namespace { struct REV_PHObj { int32_t controlPeriod; PH_set_all_t desiredSolenoidsState; - wpi::mutex solenoidLock; + wpi::util::mutex solenoidLock; HAL_CANHandle hcan; std::string previousAllocation; HAL_REVPHVersion versionInfo; @@ -74,14 +74,14 @@ struct REV_PHObj { static IndexedHandleResource* REVPHHandles; -namespace hal::init { +namespace wpi::hal::init { void InitializeREVPH() { static IndexedHandleResource rH; REVPHHandles = &rH; } -} // namespace hal::init +} // namespace wpi::hal::init static PH_status_0_t HAL_ReadREVPHStatus0(HAL_CANHandle hcan, int32_t* status) { HAL_CANReceiveMessage message; @@ -194,10 +194,10 @@ static HAL_Bool HAL_CheckREVPHPulseTime(int32_t time) { HAL_REVPHHandle HAL_InitializeREVPH(int32_t busId, int32_t module, const char* allocationLocation, int32_t* status) { - hal::init::CheckInit(); + wpi::hal::init::CheckInit(); if (!HAL_CheckREVPHModuleNumber(module)) { *status = RESOURCE_OUT_OF_RANGE; - hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for REV PH", 1, + wpi::hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for REV PH", 1, kNumREVPHModules, module); return HAL_kInvalidHandle; } @@ -207,10 +207,10 @@ HAL_REVPHHandle HAL_InitializeREVPH(int32_t busId, int32_t module, auto hph = REVPHHandles->Allocate(module - 1, &handle, status); if (*status != 0) { if (hph) { - hal::SetLastErrorPreviouslyAllocated(status, "REV PH", module, + wpi::hal::SetLastErrorPreviouslyAllocated(status, "REV PH", module, hph->previousAllocation); } else { - hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for REV PH", 1, + wpi::hal::SetLastErrorIndexOutOfRange(status, "Invalid Index for REV PH", 1, kNumREVPHModules, module); } return HAL_kInvalidHandle; // failed to allocate. Pass error back. @@ -398,7 +398,7 @@ double HAL_GetREVPHAnalogVoltage(HAL_REVPHHandle handle, int32_t channel, if (channel < 0 || channel > 1) { *status = PARAMETER_OUT_OF_RANGE; - hal::SetLastErrorIndexOutOfRange(status, "Invalid REV Analog Index", 0, 2, + wpi::hal::SetLastErrorIndexOutOfRange(status, "Invalid REV Analog Index", 0, 2, channel); return 0; } @@ -601,7 +601,7 @@ void HAL_FireREVPHOneShot(HAL_REVPHHandle handle, int32_t index, int32_t durMs, if (index >= kNumREVPHChannels || index < 0) { *status = PARAMETER_OUT_OF_RANGE; - hal::SetLastError( + wpi::hal::SetLastError( status, fmt::format("Only [0-15] are valid index values. Requested {}", index)); return; @@ -609,7 +609,7 @@ void HAL_FireREVPHOneShot(HAL_REVPHHandle handle, int32_t index, int32_t durMs, if (!HAL_CheckREVPHPulseTime(durMs)) { *status = PARAMETER_OUT_OF_RANGE; - hal::SetLastError( + wpi::hal::SetLastError( status, fmt::format("Time not within expected range [0-65534]. Requested {}", durMs)); diff --git a/hal/src/main/native/systemcore/SerialPort.cpp b/hal/src/main/native/systemcore/SerialPort.cpp index 8cb7981802..d54b5b049b 100644 --- a/hal/src/main/native/systemcore/SerialPort.cpp +++ b/hal/src/main/native/systemcore/SerialPort.cpp @@ -24,16 +24,16 @@ #include "wpi/hal/handles/HandlesInternal.h" #include "wpi/hal/handles/IndexedHandleResource.h" -namespace hal::init { +namespace wpi::hal::init { void InitializeSerialPort() {} -} // namespace hal::init +} // namespace wpi::hal::init -using namespace hal; +using namespace wpi::hal; extern "C" { HAL_SerialPortHandle HAL_InitializeSerialPort(HAL_SerialPort port, int32_t* status) { - // hal::init::CheckInit(); + // wpi::hal::init::CheckInit(); *status = HAL_HANDLE_ERROR; return HAL_kInvalidHandle; diff --git a/hal/src/main/native/systemcore/SimDevice.cpp b/hal/src/main/native/systemcore/SimDevice.cpp index 7c24867374..5300c705c5 100644 --- a/hal/src/main/native/systemcore/SimDevice.cpp +++ b/hal/src/main/native/systemcore/SimDevice.cpp @@ -46,8 +46,8 @@ void HAL_SetSimValue(HAL_SimValueHandle handle, const struct HAL_Value* value) { void HAL_ResetSimValue(HAL_SimValueHandle handle) {} -hal::SimDevice::SimDevice(const char* name, int index) {} +wpi::hal::SimDevice::SimDevice(const char* name, int index) {} -hal::SimDevice::SimDevice(const char* name, int index, int channel) {} +wpi::hal::SimDevice::SimDevice(const char* name, int index, int channel) {} } // extern "C" diff --git a/hal/src/main/native/systemcore/SmartIo.cpp b/hal/src/main/native/systemcore/SmartIo.cpp index f0ff8fbabc..9f74eed150 100644 --- a/hal/src/main/native/systemcore/SmartIo.cpp +++ b/hal/src/main/native/systemcore/SmartIo.cpp @@ -11,9 +11,9 @@ #include "wpi/hal/AddressableLEDTypes.h" #include "wpi/hal/Errors.h" -namespace hal { +namespace wpi::hal { -wpi::mutex smartIoMutex; +wpi::util::mutex smartIoMutex; DigitalHandleResource* smartIoHandles; namespace init { @@ -24,9 +24,9 @@ void InitializeSmartIo() { } // namespace init int32_t SmartIo::InitializeMode(SmartIoMode mode) { - auto inst = hal::GetSystemServer(); + auto inst = wpi::hal::GetSystemServer(); - nt::PubSubOptions options; + wpi::nt::PubSubOptions options; options.sendAll = true; options.keepDuplicates = true; options.periodic = 0.005; @@ -221,4 +221,4 @@ int32_t SmartIo::SetLedLength(int32_t length) { return 0; } -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/main/native/systemcore/SmartIo.h b/hal/src/main/native/systemcore/SmartIo.h index 916b2abdc8..be09096b00 100644 --- a/hal/src/main/native/systemcore/SmartIo.h +++ b/hal/src/main/native/systemcore/SmartIo.h @@ -11,7 +11,7 @@ #include "wpi/hal/handles/HandlesInternal.h" #include "wpi/nt/IntegerTopic.hpp" -namespace hal { +namespace wpi::hal { constexpr int32_t kPwmDisabled = 0; constexpr int32_t kPwmAlwaysHigh = 0xFFFF; @@ -38,16 +38,16 @@ struct SmartIo { uint8_t channel; std::string previousAllocation; SmartIoMode currentMode{SmartIoMode::DigitalInput}; - nt::IntegerPublisher modePublisher; + wpi::nt::IntegerPublisher modePublisher; - nt::IntegerPublisher setPublisher; - nt::IntegerSubscriber getSubscriber; + wpi::nt::IntegerPublisher setPublisher; + wpi::nt::IntegerSubscriber getSubscriber; - nt::IntegerPublisher periodSetPublisher; - nt::IntegerSubscriber periodGetSubscriber; + wpi::nt::IntegerPublisher periodSetPublisher; + wpi::nt::IntegerSubscriber periodGetSubscriber; - nt::IntegerPublisher ledcountPublisher; - nt::IntegerPublisher ledoffsetPublisher; + wpi::nt::IntegerPublisher ledcountPublisher; + wpi::nt::IntegerPublisher ledoffsetPublisher; int32_t InitializeMode(SmartIoMode mode); int32_t SwitchDioDirection(bool input); @@ -74,6 +74,6 @@ struct SmartIo { extern DigitalHandleResource* smartIoHandles; -extern wpi::mutex smartIoMutex; +extern wpi::util::mutex smartIoMutex; -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/main/native/systemcore/SystemServer.cpp b/hal/src/main/native/systemcore/SystemServer.cpp index 1c16e29962..467517eb70 100644 --- a/hal/src/main/native/systemcore/SystemServer.cpp +++ b/hal/src/main/native/systemcore/SystemServer.cpp @@ -7,15 +7,15 @@ #include "SystemServerInternal.h" #include "mrc/NtNetComm.h" -namespace hal { +namespace wpi::hal { -static nt::NetworkTableInstance ServerInstance; +static wpi::nt::NetworkTableInstance ServerInstance; void InitializeSystemServer() { if (ServerInstance) { return; } - ServerInstance = nt::NetworkTableInstance::Create(); + ServerInstance = wpi::nt::NetworkTableInstance::Create(); ServerInstance.SetServer("localhost", ROBOT_SYSTEM_SERVER_NT_PORT); ServerInstance.StartClient("RobotProgram"); } @@ -26,18 +26,18 @@ void ShutdownSystemServer() { } ServerInstance.StopClient(); - nt::NetworkTableInstance::Destroy(ServerInstance); + wpi::nt::NetworkTableInstance::Destroy(ServerInstance); } -nt::NetworkTableInstance GetSystemServer() { +wpi::nt::NetworkTableInstance GetSystemServer() { return ServerInstance; } -} // namespace hal +} // namespace wpi::hal extern "C" { NT_Inst HAL_GetSystemServerHandle(void) { - return hal::ServerInstance.GetHandle(); + return wpi::hal::ServerInstance.GetHandle(); } } // extern "C" diff --git a/hal/src/main/native/systemcore/SystemServerInternal.h b/hal/src/main/native/systemcore/SystemServerInternal.h index 1209c8b395..3e06476cd6 100644 --- a/hal/src/main/native/systemcore/SystemServerInternal.h +++ b/hal/src/main/native/systemcore/SystemServerInternal.h @@ -6,8 +6,8 @@ #include "wpi/nt/NetworkTableInstance.hpp" -namespace hal { +namespace wpi::hal { void InitializeSystemServer(); void ShutdownSystemServer(); -nt::NetworkTableInstance GetSystemServer(); -} // namespace hal +wpi::nt::NetworkTableInstance GetSystemServer(); +} // namespace wpi::hal diff --git a/hal/src/main/native/systemcore/Threads.cpp b/hal/src/main/native/systemcore/Threads.cpp index 8b76314ab5..dd1a5ab6f8 100644 --- a/hal/src/main/native/systemcore/Threads.cpp +++ b/hal/src/main/native/systemcore/Threads.cpp @@ -9,9 +9,9 @@ #include "wpi/hal/Errors.h" -namespace hal::init { +namespace wpi::hal::init { void InitializeThreads() {} -} // namespace hal::init +} // namespace wpi::hal::init extern "C" { diff --git a/hal/src/main/native/systemcore/UsageReporting.cpp b/hal/src/main/native/systemcore/UsageReporting.cpp index 08c0ae2e5c..6d7f48f83c 100644 --- a/hal/src/main/native/systemcore/UsageReporting.cpp +++ b/hal/src/main/native/systemcore/UsageReporting.cpp @@ -14,10 +14,10 @@ namespace { struct SystemServerUsageReporting { - nt::NetworkTableInstance ntInst; - wpi::StringMap publishers; + wpi::nt::NetworkTableInstance ntInst; + wpi::util::StringMap publishers; - explicit SystemServerUsageReporting(nt::NetworkTableInstance inst) + explicit SystemServerUsageReporting(wpi::nt::NetworkTableInstance inst) : ntInst{inst} {} }; @@ -29,7 +29,7 @@ extern "C" { int32_t HAL_ReportUsage(const struct WPI_String* resource, const struct WPI_String* data) { - auto resourceStr = wpi::to_string_view(resource); + auto resourceStr = wpi::util::to_string_view(resource); auto& publisher = systemServerUsage->publishers[resourceStr]; if (!publisher) { publisher = @@ -37,15 +37,15 @@ int32_t HAL_ReportUsage(const struct WPI_String* resource, .GetStringTopic(fmt::format("/UsageReporting/{}", resourceStr)) .Publish(); } - publisher.Set(wpi::to_string_view(data)); + publisher.Set(wpi::util::to_string_view(data)); return 0; } } // extern "C" -namespace hal::init { +namespace wpi::hal::init { void InitializeUsageReporting() { - systemServerUsage = new ::SystemServerUsageReporting{hal::GetSystemServer()}; + systemServerUsage = new ::SystemServerUsageReporting{wpi::hal::GetSystemServer()}; } -} // namespace hal::init +} // namespace wpi::hal::init diff --git a/hal/src/main/python/hal/simulation/resethandles.cpp b/hal/src/main/python/hal/simulation/resethandles.cpp index b66b3caa22..b6bf48eb64 100644 --- a/hal/src/main/python/hal/simulation/resethandles.cpp +++ b/hal/src/main/python/hal/simulation/resethandles.cpp @@ -19,7 +19,7 @@ void HALSIM_ResetGlobalHandles() { } } - hal::HandleBase::ResetGlobalHandles(); + wpi::hal::HandleBase::ResetGlobalHandles(); } #else diff --git a/hal/src/main/python/semiwrap/DriverStation.yml b/hal/src/main/python/semiwrap/DriverStation.yml index 7914c87b50..42cc2006ca 100644 --- a/hal/src/main/python/semiwrap/DriverStation.yml +++ b/hal/src/main/python/semiwrap/DriverStation.yml @@ -22,7 +22,7 @@ functions: [](int32_t joystickNum) { WPI_String name; HAL_GetJoystickName(&name, joystickNum); - std::string sname(wpi::to_string_view(&name)); + std::string sname(wpi::util::to_string_view(&name)); WPI_FreeString(&name); return sname; } diff --git a/hal/src/main/python/semiwrap/HALBase.yml b/hal/src/main/python/semiwrap/HALBase.yml index d81d5ac322..a731548e13 100644 --- a/hal/src/main/python/semiwrap/HALBase.yml +++ b/hal/src/main/python/semiwrap/HALBase.yml @@ -13,7 +13,7 @@ functions: []() { WPI_String s; HAL_GetSerialNumber(&s); - std::string ss(wpi::to_string_view(&s)); + std::string ss(wpi::util::to_string_view(&s)); WPI_FreeString(&s); return ss; } @@ -25,7 +25,7 @@ functions: []() { WPI_String s; HAL_GetComments(&s); - std::string ss(wpi::to_string_view(&s)); + std::string ss(wpi::util::to_string_view(&s)); WPI_FreeString(&s); return ss; } diff --git a/hal/src/main/python/semiwrap/HandlesInternal.yml b/hal/src/main/python/semiwrap/HandlesInternal.yml index fb088df26b..8fd81e0f97 100644 --- a/hal/src/main/python/semiwrap/HandlesInternal.yml +++ b/hal/src/main/python/semiwrap/HandlesInternal.yml @@ -11,5 +11,5 @@ functions: getHandleTypedIndex: createHandle: classes: - hal::HandleBase: + wpi::hal::HandleBase: ignore: true diff --git a/hal/src/main/python/semiwrap/SimDevice.yml b/hal/src/main/python/semiwrap/SimDevice.yml index 539fa4fb9e..d6e93d0c6e 100644 --- a/hal/src/main/python/semiwrap/SimDevice.yml +++ b/hal/src/main/python/semiwrap/SimDevice.yml @@ -11,7 +11,7 @@ strip_prefixes: enums: HAL_SimValueDirection: classes: - hal::SimValue: + wpi::hal::SimValue: doc: | Readonly wrapper around a HAL simulator value. @@ -30,7 +30,7 @@ classes: ignore: true SetValue: ignore: true - hal::SimInt: + wpi::hal::SimInt: doc: | Wrapper around a HAL simulator int value handle. @@ -49,7 +49,7 @@ classes: Get: Set: Reset: - hal::SimLong: + wpi::hal::SimLong: doc: | Wrapper around a HAL simulator long value handle. @@ -68,7 +68,7 @@ classes: Get: Set: Reset: - hal::SimDouble: + wpi::hal::SimDouble: doc: | Wrapper around a HAL simulator double value. @@ -87,7 +87,7 @@ classes: Get: Set: Reset: - hal::SimEnum: + wpi::hal::SimEnum: doc: | Wrapper around a HAL simulator enum value. @@ -105,7 +105,7 @@ classes: name: handle Get: Set: - hal::SimBoolean: + wpi::hal::SimBoolean: doc: | Wrapper around a HAL simulator boolean value. @@ -123,7 +123,7 @@ classes: name: handle Get: Set: - hal::SimDevice: + wpi::hal::SimDevice: doc: | Wrapper around a HAL simulation 'device' @@ -133,7 +133,7 @@ classes: .. note:: To interact with an existing device use :class:`hal.simulation.SimDeviceSim` instead. force_type_casters: - - wpi::SmallVector + - wpi::util::SmallVector enums: Direction: methods: @@ -154,8 +154,8 @@ classes: ignore: true const char*, int32_t, std::span, int32_t: cpp_code: | - [](SimDevice &self, const char * name, int32_t direction, const wpi::SmallVector &options, int32_t initialValue) { - wpi::SmallVector coptions; + [](SimDevice &self, const char * name, int32_t direction, const wpi::util::SmallVector &options, int32_t initialValue) { + wpi::util::SmallVector coptions; coptions.reserve(options.size()); for (auto &s: options) { coptions.push_back(s.c_str()); @@ -169,8 +169,8 @@ classes: ignore: true const char*, int32_t, std::span, std::span, int32_t: cpp_code: | - [](SimDevice &self, const char * name, int32_t direction, const wpi::SmallVector &options, const wpi::SmallVector &optionValues, int32_t initialValue) { - wpi::SmallVector coptions; + [](SimDevice &self, const char * name, int32_t direction, const wpi::util::SmallVector &options, const wpi::util::SmallVector &optionValues, int32_t initialValue) { + wpi::util::SmallVector coptions; coptions.reserve(options.size()); for (auto &s: options) { coptions.push_back(s.c_str()); @@ -185,7 +185,7 @@ classes: inline_code: |2 cls_SimValue - .def_property_readonly("value", [](const hal::SimValue &self) -> py::object { + .def_property_readonly("value", [](const wpi::hal::SimValue &self) -> py::object { HAL_Value value; { py::gil_scoped_release release; @@ -206,14 +206,14 @@ inline_code: |2 return py::none(); } }) - .def_property_readonly("type", [](const hal::SimValue &self) -> HAL_Type { + .def_property_readonly("type", [](const wpi::hal::SimValue &self) -> HAL_Type { py::gil_scoped_release release; return self.GetValue().type; }) - .def("__bool__", [](const hal::SimValue &self) -> bool { + .def("__bool__", [](const wpi::hal::SimValue &self) -> bool { return (bool)self; }) - .def("__repr__", [](const hal::SimValue &self) -> py::str { + .def("__repr__", [](const wpi::hal::SimValue &self) -> py::str { if (!self) { return ""; } @@ -258,10 +258,10 @@ inline_code: |2 }); cls_SimDevice - .def("__bool__", [](const hal::SimDevice &self) -> bool { + .def("__bool__", [](const wpi::hal::SimDevice &self) -> bool { return (bool)self; }) - .def_property_readonly("name", [](const hal::SimDevice &self) -> py::str { + .def_property_readonly("name", [](const wpi::hal::SimDevice &self) -> py::str { #ifdef __FRC_SYSTEMCORE__ return ""; #else @@ -277,7 +277,7 @@ inline_code: |2 } #endif }) - .def("__repr__", [](const hal::SimDevice &self) -> py::str { + .def("__repr__", [](const wpi::hal::SimDevice &self) -> py::str { #ifdef __FRC_SYSTEMCORE__ return ""; #else diff --git a/hal/src/main/python/semiwrap/simulation/DriverStationData.yml b/hal/src/main/python/semiwrap/simulation/DriverStationData.yml index 7be9485c45..79f39480be 100644 --- a/hal/src/main/python/semiwrap/simulation/DriverStationData.yml +++ b/hal/src/main/python/semiwrap/simulation/DriverStationData.yml @@ -81,19 +81,19 @@ functions: HALSIM_SetJoystickName: cpp_code: | [](int32_t stick, std::string_view sv) { - auto s = wpi::make_string(sv); + auto s = wpi::util::make_string(sv); HALSIM_SetJoystickName(stick, &s); } HALSIM_SetGameSpecificMessage: cpp_code: | [](std::string_view sv) { - auto s = wpi::make_string(sv); + auto s = wpi::util::make_string(sv); HALSIM_SetGameSpecificMessage(&s); } HALSIM_SetEventName: cpp_code: | [](std::string_view sv) { - auto s = wpi::make_string(sv); + auto s = wpi::util::make_string(sv); HALSIM_SetEventName(&s); } HALSIM_SetMatchType: diff --git a/hal/src/main/python/semiwrap/simulation/RoboRioData.yml b/hal/src/main/python/semiwrap/simulation/RoboRioData.yml index 8bf0f231b4..e016fed574 100644 --- a/hal/src/main/python/semiwrap/simulation/RoboRioData.yml +++ b/hal/src/main/python/semiwrap/simulation/RoboRioData.yml @@ -57,14 +57,14 @@ functions: []() { WPI_String s; HALSIM_GetRoboRioSerialNumber(&s); - std::string ss(wpi::to_string_view(&s)); + std::string ss(wpi::util::to_string_view(&s)); WPI_FreeString(&s); return ss; } HALSIM_SetRoboRioSerialNumber: cpp_code: | [](std::string_view sv) { - auto s = wpi::make_string(sv); + auto s = wpi::util::make_string(sv); HALSIM_SetRoboRioSerialNumber(&s); } HALSIM_RegisterRoboRioCommentsCallback: @@ -78,14 +78,14 @@ functions: []() { WPI_String s; HALSIM_GetRoboRioComments(&s); - std::string ss(wpi::to_string_view(&s)); + std::string ss(wpi::util::to_string_view(&s)); WPI_FreeString(&s); return ss; } HALSIM_SetRoboRioComments: cpp_code: | [](std::string_view sv) { - auto s = wpi::make_string(sv); + auto s = wpi::util::make_string(sv); HALSIM_SetRoboRioComments(&s); } HALSIM_RegisterRoboRioAllCallbacks: diff --git a/hal/src/main/python/semiwrap/simulation/SimDeviceData.yml b/hal/src/main/python/semiwrap/simulation/SimDeviceData.yml index de6cf5b83e..a20a28413d 100644 --- a/hal/src/main/python/semiwrap/simulation/SimDeviceData.yml +++ b/hal/src/main/python/semiwrap/simulation/SimDeviceData.yml @@ -26,7 +26,7 @@ functions: param: ignore: true cpp_code: | - [](hal::SimDevice &simdevice, std::function fn, bool initialNotify) -> std::unique_ptr { + [](wpi::hal::SimDevice &simdevice, std::function fn, bool initialNotify) -> std::unique_ptr { auto cb = std::make_unique(fn, HALSIM_CancelSimDeviceCreatedCallback); auto uid = HALSIM_RegisterSimValueCreatedCallback(simdevice, cb.get(), [](const char* name, void* param, @@ -47,7 +47,7 @@ functions: param: ignore: true cpp_code: | - [](hal::SimValue &simvalue, std::function fn, bool initialNotify) -> std::unique_ptr { + [](wpi::hal::SimValue &simvalue, std::function fn, bool initialNotify) -> std::unique_ptr { auto cb = std::make_unique(fn, HALSIM_CancelSimValueChangedCallback); auto uid = HALSIM_RegisterSimValueChangedCallback(simvalue, cb.get(), [](const char* name, void* param, @@ -68,7 +68,7 @@ functions: param: ignore: true cpp_code: | - [](hal::SimValue &simvalue, std::function fn, bool initialNotify) -> std::unique_ptr { + [](wpi::hal::SimValue &simvalue, std::function fn, bool initialNotify) -> std::unique_ptr { auto cb = std::make_unique(fn, HALSIM_CancelSimValueResetCallback); auto uid = HALSIM_RegisterSimValueChangedCallback(simvalue, cb.get(), [](const char* name, void* param, diff --git a/hal/src/test/native/cpp/HALTest.cpp b/hal/src/test/native/cpp/HALTest.cpp index 1ff2b7f297..3c867f777d 100644 --- a/hal/src/test/native/cpp/HALTest.cpp +++ b/hal/src/test/native/cpp/HALTest.cpp @@ -6,8 +6,8 @@ #include "wpi/hal/HAL.h" -namespace hal { +namespace wpi::hal { TEST(HALTest, RuntimeType) { EXPECT_EQ(HAL_RuntimeType::HAL_Runtime_Simulation, HAL_GetRuntimeType()); } -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/test/native/cpp/can/CANTest.cpp b/hal/src/test/native/cpp/can/CANTest.cpp index b13eaa4811..4b520630ac 100644 --- a/hal/src/test/native/cpp/can/CANTest.cpp +++ b/hal/src/test/native/cpp/can/CANTest.cpp @@ -10,7 +10,7 @@ #include "wpi/hal/CANAPI.h" #include "wpi/hal/simulation/CanData.h" -namespace hal { +namespace wpi::hal { struct CANTestStore { CANTestStore(int32_t busId, int32_t deviceId, int32_t* status) { this->deviceId = deviceId; @@ -83,4 +83,4 @@ TEST(CANTest, CanIdPacking) { ASSERT_EQ(static_cast(HAL_CANDeviceType::HAL_CAN_Dev_kMiscellaneous), (storePair.first & 0x1F000000) >> 24); } -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/test/native/cpp/handles/HandleTest.cpp b/hal/src/test/native/cpp/handles/HandleTest.cpp index cfc7559c0e..7060b805c1 100644 --- a/hal/src/test/native/cpp/handles/HandleTest.cpp +++ b/hal/src/test/native/cpp/handles/HandleTest.cpp @@ -14,9 +14,9 @@ namespace { class MyTestClass {}; } // namespace -namespace hal { +namespace wpi::hal { TEST(HandleTest, ClassedHandle) { - hal::IndexedClassedHandleResource testClass; int32_t status = 0; @@ -24,4 +24,4 @@ TEST(HandleTest, ClassedHandle) { EXPECT_EQ(0, status); } -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/test/native/cpp/mockdata/AnalogInDataTest.cpp b/hal/src/test/native/cpp/mockdata/AnalogInDataTest.cpp index aa562360eb..6a1d4b84a9 100644 --- a/hal/src/test/native/cpp/mockdata/AnalogInDataTest.cpp +++ b/hal/src/test/native/cpp/mockdata/AnalogInDataTest.cpp @@ -11,7 +11,7 @@ #include "wpi/hal/handles/HandlesInternal.h" #include "wpi/hal/simulation/AnalogInData.h" -namespace hal { +namespace wpi::hal { std::string gTestAnalogInCallbackName; HAL_Value gTestAnalogInCallbackValue; @@ -66,7 +66,7 @@ TEST(AnalogInSimTest, AnalogInInitialization) { EXPECT_STREQ("Unset", gTestAnalogInCallbackName.c_str()); // Reset, should allow you to re-register - hal::HandleBase::ResetGlobalHandles(); + wpi::hal::HandleBase::ResetGlobalHandles(); HALSIM_ResetAnalogInData(INDEX_TO_TEST); callbackId = HALSIM_RegisterAnalogInInitializedCallback( INDEX_TO_TEST, &TestAnalogInInitializationCallback, &callbackParam, @@ -81,4 +81,4 @@ TEST(AnalogInSimTest, AnalogInInitialization) { EXPECT_STREQ("Initialized", gTestAnalogInCallbackName.c_str()); HALSIM_CancelAnalogInInitializedCallback(INDEX_TO_TEST, callbackId); } -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/test/native/cpp/mockdata/DIODataTest.cpp b/hal/src/test/native/cpp/mockdata/DIODataTest.cpp index 5512e989b0..b396cdf0de 100644 --- a/hal/src/test/native/cpp/mockdata/DIODataTest.cpp +++ b/hal/src/test/native/cpp/mockdata/DIODataTest.cpp @@ -11,7 +11,7 @@ #include "wpi/hal/handles/HandlesInternal.h" #include "wpi/hal/simulation/DIOData.h" -namespace hal { +namespace wpi::hal { std::string gTestDigitalIoCallbackName; HAL_Value gTestDigitalIoCallbackValue; @@ -66,7 +66,7 @@ TEST(DigitalIoSimTest, DigitalIoInitialization) { EXPECT_STREQ("Unset", gTestDigitalIoCallbackName.c_str()); // Reset, should allow you to re-register - hal::HandleBase::ResetGlobalHandles(); + wpi::hal::HandleBase::ResetGlobalHandles(); HALSIM_ResetDIOData(INDEX_TO_TEST); callbackId = HALSIM_RegisterDIOInitializedCallback( INDEX_TO_TEST, &TestDigitalIoInitializationCallback, &callbackParam, @@ -82,4 +82,4 @@ TEST(DigitalIoSimTest, DigitalIoInitialization) { HALSIM_CancelDIOInitializedCallback(INDEX_TO_TEST, callbackId); } -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/test/native/cpp/mockdata/DriverStationDataTest.cpp b/hal/src/test/native/cpp/mockdata/DriverStationDataTest.cpp index 736101555d..bbdb326b01 100644 --- a/hal/src/test/native/cpp/mockdata/DriverStationDataTest.cpp +++ b/hal/src/test/native/cpp/mockdata/DriverStationDataTest.cpp @@ -11,7 +11,7 @@ #include "wpi/hal/simulation/DriverStationData.h" #include "wpi/util/StringExtras.hpp" -namespace hal { +namespace wpi::hal { TEST(DriverStationTest, Joystick) { HAL_JoystickAxes axes; @@ -122,8 +122,8 @@ TEST(DriverStationTest, EventInfo) { constexpr std::string_view eventName = "UnitTest"; constexpr std::string_view gameData = "Insert game specific info here :D"; HAL_MatchInfo info; - wpi::format_to_n_c_str(info.eventName, sizeof(info.eventName), eventName); - wpi::format_to_n_c_str(reinterpret_cast(info.gameSpecificMessage), + wpi::util::format_to_n_c_str(info.eventName, sizeof(info.eventName), eventName); + wpi::util::format_to_n_c_str(reinterpret_cast(info.gameSpecificMessage), sizeof(info.gameSpecificMessage), gameData); info.gameSpecificMessageSize = gameData.size(); info.matchNumber = 5; @@ -146,4 +146,4 @@ TEST(DriverStationTest, EventInfo) { EXPECT_EQ(42, dataBack.replayNumber); } -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/test/native/cpp/mockdata/I2CDataTest.cpp b/hal/src/test/native/cpp/mockdata/I2CDataTest.cpp index 89364a5b0f..cb310ec021 100644 --- a/hal/src/test/native/cpp/mockdata/I2CDataTest.cpp +++ b/hal/src/test/native/cpp/mockdata/I2CDataTest.cpp @@ -9,7 +9,7 @@ #include "wpi/hal/I2C.h" #include "wpi/hal/simulation/I2CData.h" -namespace hal { +namespace wpi::hal { std::string gTestI2CCallbackName; HAL_Value gTestI2CCallbackValue; @@ -37,4 +37,4 @@ TEST(I2CSimTest, I2CInitialization) { EXPECT_STREQ("Initialized", gTestI2CCallbackName.c_str()); } -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/test/native/cpp/mockdata/PCMDataTest.cpp b/hal/src/test/native/cpp/mockdata/PCMDataTest.cpp index cd321c1874..89c2045bf4 100644 --- a/hal/src/test/native/cpp/mockdata/PCMDataTest.cpp +++ b/hal/src/test/native/cpp/mockdata/PCMDataTest.cpp @@ -11,7 +11,7 @@ #include "wpi/hal/handles/HandlesInternal.h" #include "wpi/hal/simulation/CTREPCMData.h" -namespace hal { +namespace wpi::hal { std::string gTestSolenoidCallbackName; HAL_Value gTestSolenoidCallbackValue; @@ -66,7 +66,7 @@ TEST(PCMDataTest, PCMInitialization) { EXPECT_STREQ("Unset", gTestSolenoidCallbackName.c_str()); // Reset, should allow you to re-register - hal::HandleBase::ResetGlobalHandles(); + wpi::hal::HandleBase::ResetGlobalHandles(); HALSIM_ResetCTREPCMData(MODULE_TO_TEST); callbackId = HALSIM_RegisterCTREPCMInitializedCallback( MODULE_TO_TEST, &TestSolenoidInitializationCallback, &callbackParam, @@ -82,4 +82,4 @@ TEST(PCMDataTest, PCMInitialization) { EXPECT_STREQ("Initialized", gTestSolenoidCallbackName.c_str()); } -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/test/native/cpp/mockdata/PDPDataTest.cpp b/hal/src/test/native/cpp/mockdata/PDPDataTest.cpp index 99a96411d2..42c79330fd 100644 --- a/hal/src/test/native/cpp/mockdata/PDPDataTest.cpp +++ b/hal/src/test/native/cpp/mockdata/PDPDataTest.cpp @@ -9,7 +9,7 @@ #include "wpi/hal/PowerDistribution.h" #include "wpi/hal/simulation/PowerDistributionData.h" -namespace hal { +namespace wpi::hal { std::string gTestPdpCallbackName; HAL_Value gTestPdpCallbackValue; @@ -38,4 +38,4 @@ TEST(PdpSimTest, PdpInitialization) { EXPECT_STREQ("Initialized", gTestPdpCallbackName.c_str()); } -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/test/native/cpp/mockdata/PWMDataTest.cpp b/hal/src/test/native/cpp/mockdata/PWMDataTest.cpp index 268b951b9f..9b61e14bca 100644 --- a/hal/src/test/native/cpp/mockdata/PWMDataTest.cpp +++ b/hal/src/test/native/cpp/mockdata/PWMDataTest.cpp @@ -11,7 +11,7 @@ #include "wpi/hal/handles/HandlesInternal.h" #include "wpi/hal/simulation/PWMData.h" -namespace hal { +namespace wpi::hal { std::string gTestPwmCallbackName; HAL_Value gTestPwmCallbackValue; @@ -65,7 +65,7 @@ TEST(PWMSimTest, PwmInitialization) { EXPECT_STREQ("Unset", gTestPwmCallbackName.c_str()); // Reset, should allow you to re-register - hal::HandleBase::ResetGlobalHandles(); + wpi::hal::HandleBase::ResetGlobalHandles(); HALSIM_ResetPWMData(INDEX_TO_TEST); callbackId = HALSIM_RegisterPWMInitializedCallback( INDEX_TO_TEST, &TestPwmInitializationCallback, &callbackParam, false); @@ -79,4 +79,4 @@ TEST(PWMSimTest, PwmInitialization) { EXPECT_STREQ("Initialized", gTestPwmCallbackName.c_str()); HALSIM_CancelPWMInitializedCallback(INDEX_TO_TEST, callbackId); } -} // namespace hal +} // namespace wpi::hal diff --git a/hal/src/test/native/cpp/mockdata/SimDeviceDataTest.cpp b/hal/src/test/native/cpp/mockdata/SimDeviceDataTest.cpp index 1af4e62c64..f331de6ffc 100644 --- a/hal/src/test/native/cpp/mockdata/SimDeviceDataTest.cpp +++ b/hal/src/test/native/cpp/mockdata/SimDeviceDataTest.cpp @@ -7,7 +7,7 @@ #include "wpi/hal/SimDevice.h" #include "wpi/hal/simulation/SimDeviceData.h" -namespace hal { +namespace wpi::hal { TEST(SimDeviceSimTest, Enabled) { ASSERT_TRUE(HALSIM_IsSimDeviceEnabled("foo")); @@ -20,4 +20,4 @@ TEST(SimDeviceSimTest, Enabled) { ASSERT_EQ(HAL_CreateSimDevice("foo"), 0); } -} // namespace hal +} // namespace wpi::hal diff --git a/ntcore/src/dev/native/cpp/main.cpp b/ntcore/src/dev/native/cpp/main.cpp index 1d9b15e5bd..345e083d81 100644 --- a/ntcore/src/dev/native/cpp/main.cpp +++ b/ntcore/src/dev/native/cpp/main.cpp @@ -54,11 +54,11 @@ int main(int argc, char* argv[]) { return EXIT_SUCCESS; } - auto myValue = nt::GetEntry(nt::GetDefaultInstance(), "MyValue"); + auto myValue = wpi::nt::GetEntry(wpi::nt::GetDefaultInstance(), "MyValue"); - nt::SetEntryValue(myValue, nt::Value::MakeString("Hello World")); + wpi::nt::SetEntryValue(myValue, wpi::nt::Value::MakeString("Hello World")); - wpi::print("{}\n", nt::GetEntryValue(myValue).GetString()); + wpi::util::print("{}\n", wpi::nt::GetEntryValue(myValue).GetString()); } void PrintTimes(std::vector& times) { @@ -72,36 +72,36 @@ void PrintTimes(std::vector& times) { std::inner_product(times.begin(), times.end(), times.begin(), 0); double stdev = std::sqrt(sq_sum / times.size() - mean * mean); - wpi::print("min: {} max: {}, mean: {}, stdev: {}\n", min, max, mean, stdev); - wpi::print("min 10: {}\n", fmt::join(times.begin(), times.begin() + 10, ",")); - wpi::print("max 10: {}\n", fmt::join(times.end() - 10, times.end(), ",")); + wpi::util::print("min: {} max: {}, mean: {}, stdev: {}\n", min, max, mean, stdev); + wpi::util::print("min 10: {}\n", fmt::join(times.begin(), times.begin() + 10, ",")); + wpi::util::print("max 10: {}\n", fmt::join(times.end() - 10, times.end(), ",")); } // benchmark void bench() { // set up instances - auto client = nt::CreateInstance(); - auto server = nt::CreateInstance(); + auto client = wpi::nt::CreateInstance(); + auto server = wpi::nt::CreateInstance(); // connect client and server - nt::StartServer(server, "bench.json", "127.0.0.1", 10000); - nt::StartClient(client, "client"); - nt::SetServer(client, "127.0.0.1", 10000); + wpi::nt::StartServer(server, "bench.json", "127.0.0.1", 10000); + wpi::nt::StartClient(client, "client"); + wpi::nt::SetServer(client, "127.0.0.1", 10000); using namespace std::chrono_literals; std::this_thread::sleep_for(1s); // add "typical" set of subscribers on client and server - nt::SubscribeMultiple(client, {{std::string_view{}}}); - nt::Subscribe(nt::GetTopic(client, "highrate"), NT_DOUBLE, "double", + wpi::nt::SubscribeMultiple(client, {{std::string_view{}}}); + wpi::nt::Subscribe(wpi::nt::GetTopic(client, "highrate"), NT_DOUBLE, "double", {.sendAll = true, .keepDuplicates = true}); - nt::SubscribeMultiple(server, {{std::string_view{}}}); - auto pub = nt::Publish(nt::GetTopic(server, "highrate"), NT_DOUBLE, "double"); - nt::SetDouble(pub, 0); + wpi::nt::SubscribeMultiple(server, {{std::string_view{}}}); + auto pub = wpi::nt::Publish(wpi::nt::GetTopic(server, "highrate"), NT_DOUBLE, "double"); + wpi::nt::SetDouble(pub, 0); // warm up for (int i = 1; i <= 10000; ++i) { - nt::SetDouble(pub, i * 0.01); + wpi::nt::SetDouble(pub, i * 0.01); if (i % 2000 == 0) { std::this_thread::sleep_for(0.02s); } @@ -115,55 +115,55 @@ void bench() { // benchmark auto start = std::chrono::high_resolution_clock::now(); - int64_t now = nt::Now(); + int64_t now = wpi::nt::Now(); for (int i = 1; i <= 100000; ++i) { - nt::SetDouble(pub, i * 0.01, now); + wpi::nt::SetDouble(pub, i * 0.01, now); int64_t prev = now; - now = nt::Now(); + now = wpi::nt::Now(); times.emplace_back(now - prev); if (i % 2000 == 0) { - nt::Flush(server); - flushTimes.emplace_back(nt::Now() - now); + wpi::nt::Flush(server); + flushTimes.emplace_back(wpi::nt::Now() - now); std::this_thread::sleep_for(0.02s); - now = nt::Now(); + now = wpi::nt::Now(); } } auto stop = std::chrono::high_resolution_clock::now(); - wpi::print("total time: {}us\n", + wpi::util::print("total time: {}us\n", std::chrono::duration_cast(stop - start) .count()); PrintTimes(times); - wpi::print("-- Flush --\n"); + wpi::util::print("-- Flush --\n"); PrintTimes(flushTimes); } void bench2() { // set up instances - auto client1 = nt::CreateInstance(); - auto client2 = nt::CreateInstance(); - auto server = nt::CreateInstance(); + auto client1 = wpi::nt::CreateInstance(); + auto client2 = wpi::nt::CreateInstance(); + auto server = wpi::nt::CreateInstance(); // connect client and server - nt::StartServer(server, "bench2.json", "127.0.0.1", 10000); - nt::StartClient(client1, "client1"); - nt::StartClient(client2, "client2"); - nt::SetServer(client1, "127.0.0.1", 10000); - nt::SetServer(client2, "127.0.0.1", 10000); + wpi::nt::StartServer(server, "bench2.json", "127.0.0.1", 10000); + wpi::nt::StartClient(client1, "client1"); + wpi::nt::StartClient(client2, "client2"); + wpi::nt::SetServer(client1, "127.0.0.1", 10000); + wpi::nt::SetServer(client2, "127.0.0.1", 10000); using namespace std::chrono_literals; std::this_thread::sleep_for(1s); // add "typical" set of subscribers on client and server - nt::SubscribeMultiple(client1, {{std::string_view{}}}); - nt::SubscribeMultiple(client2, {{std::string_view{}}}); - nt::SubscribeMultiple(server, {{std::string_view{}}}); + wpi::nt::SubscribeMultiple(client1, {{std::string_view{}}}); + wpi::nt::SubscribeMultiple(client2, {{std::string_view{}}}); + wpi::nt::SubscribeMultiple(server, {{std::string_view{}}}); // create 1000 entries std::array pubs; for (int i = 0; i < 1000; ++i) { - pubs[i] = nt::GetEntry( - nt::GetTopic(server, + pubs[i] = wpi::nt::GetEntry( + wpi::nt::GetTopic(server, fmt::format("/some/long/name/with/lots/of/slashes/{}", i)), NT_DOUBLE_ARRAY, "double[]"); } @@ -172,9 +172,9 @@ void bench2() { for (int i = 1; i <= 100; ++i) { for (auto pub : pubs) { double vals[3] = {i * 0.01, i * 0.02, i * 0.03}; - nt::SetDoubleArray(pub, vals); + wpi::nt::SetDoubleArray(pub, vals); } - nt::FlushLocal(server); + wpi::nt::FlushLocal(server); std::this_thread::sleep_for(0.02s); } @@ -186,28 +186,28 @@ void bench2() { // benchmark auto start = std::chrono::high_resolution_clock::now(); - int64_t now = nt::Now(); + int64_t now = wpi::nt::Now(); for (int i = 1; i <= 1000; ++i) { for (auto pub : pubs) { double vals[3] = {i * 0.01, i * 0.02, i * 0.03}; - nt::SetDoubleArray(pub, vals); + wpi::nt::SetDoubleArray(pub, vals); } int64_t prev = now; - now = nt::Now(); + now = wpi::nt::Now(); times.emplace_back(now - prev); - nt::FlushLocal(server); - nt::Flush(server); - flushTimes.emplace_back(nt::Now() - now); + wpi::nt::FlushLocal(server); + wpi::nt::Flush(server); + flushTimes.emplace_back(wpi::nt::Now() - now); std::this_thread::sleep_for(0.02s); - now = nt::Now(); + now = wpi::nt::Now(); } auto stop = std::chrono::high_resolution_clock::now(); - wpi::print("total time: {}us\n", + wpi::util::print("total time: {}us\n", std::chrono::duration_cast(stop - start) .count()); PrintTimes(times); - wpi::print("-- Flush --\n"); + wpi::util::print("-- Flush --\n"); PrintTimes(flushTimes); } @@ -216,31 +216,31 @@ static std::mt19937 gen(r()); static std::uniform_real_distribution dist; void stress() { - auto server = nt::CreateInstance(); - nt::StartServer(server, "stress.json", "127.0.0.1", 10000); - nt::SubscribeMultiple(server, {{std::string_view{}}}); + auto server = wpi::nt::CreateInstance(); + wpi::nt::StartServer(server, "stress.json", "127.0.0.1", 10000); + wpi::nt::SubscribeMultiple(server, {{std::string_view{}}}); using namespace std::chrono_literals; for (int count = 0; count < 10; ++count) { std::thread{[] { - auto client = nt::CreateInstance(); - nt::SubscribeMultiple(client, {{std::string_view{}}}); + auto client = wpi::nt::CreateInstance(); + wpi::nt::SubscribeMultiple(client, {{std::string_view{}}}); for (int i = 0; i < 300; ++i) { // sleep a random amount of time std::this_thread::sleep_for(0.1s * dist(gen)); // connect - nt::StartClient(client, "client"); - nt::SetServer(client, "127.0.0.1", 10000); + wpi::nt::StartClient(client, "client"); + wpi::nt::SetServer(client, "127.0.0.1", 10000); // sleep a random amount of time std::this_thread::sleep_for(0.1s * dist(gen)); // disconnect - nt::StopClient(client); + wpi::nt::StopClient(client); } - nt::DestroyInstance(client); + wpi::nt::DestroyInstance(client); }}.detach(); std::thread{[server, count] { @@ -252,7 +252,7 @@ void stress() { NT_Publisher pub[30]; for (int i = 0; i < 30; ++i) { pub[i] = - nt::Publish(nt::GetTopic(server, fmt::format("{}_{}", count, i)), + wpi::nt::Publish(wpi::nt::GetTopic(server, fmt::format("{}_{}", count, i)), NT_DOUBLE, "double", {}); } @@ -261,9 +261,9 @@ void stress() { // sleep a random amount of time between each value set std::this_thread::sleep_for(0.001s * dist(gen)); for (int i = 0; i < 30; ++i) { - nt::SetDouble(pub[i], dist(gen)); + wpi::nt::SetDouble(pub[i], dist(gen)); } - nt::FlushLocal(server); + wpi::nt::FlushLocal(server); } // sleep a random amount of time @@ -271,7 +271,7 @@ void stress() { // remove publishers for (int i = 0; i < 30; ++i) { - nt::Unpublish(pub[i]); + wpi::nt::Unpublish(pub[i]); } } }}.detach(); @@ -286,11 +286,11 @@ void stress2() { auto testTopicName = "testTopic"; auto count = 1000; std::atomic_bool isDone{false}; - nt::PubSubOptions pubSubOptions{ + wpi::nt::PubSubOptions pubSubOptions{ .periodic = std::numeric_limits::min(), .sendAll = true, .keepDuplicates = true}; - auto server = nt::NetworkTableInstance::Create(); + auto server = wpi::nt::NetworkTableInstance::Create(); server.StartServer(); auto serverTopic = server.GetDoubleArrayTopic(testTopicName); auto subscriber = serverTopic.Subscribe({}, pubSubOptions); @@ -308,7 +308,7 @@ void stress2() { // event.valueData.value.getDoubleArray()))); }); - auto client = nt::NetworkTableInstance::Create(); + auto client = wpi::nt::NetworkTableInstance::Create(); client.SetServer("localhost"); auto clientName = "test client"; client.StartClient(clientName); @@ -333,36 +333,36 @@ void stress2() { void latency() { // set up instances - auto client1 = nt::CreateInstance(); - auto client2 = nt::CreateInstance(); - auto server = nt::CreateInstance(); + auto client1 = wpi::nt::CreateInstance(); + auto client2 = wpi::nt::CreateInstance(); + auto server = wpi::nt::CreateInstance(); // connect client and server - nt::StartServer(server, "latency.json", "127.0.0.1", 10000); - nt::StartClient(client1, "client1"); - nt::SetServer(client1, "127.0.0.1", 10000); - nt::StartClient(client2, "client2"); - nt::SetServer(client2, "127.0.0.1", 10000); + wpi::nt::StartServer(server, "latency.json", "127.0.0.1", 10000); + wpi::nt::StartClient(client1, "client1"); + wpi::nt::SetServer(client1, "127.0.0.1", 10000); + wpi::nt::StartClient(client2, "client2"); + wpi::nt::SetServer(client2, "127.0.0.1", 10000); using namespace std::chrono_literals; std::this_thread::sleep_for(1s); // create publishers and subscribers auto pub = - nt::Publish(nt::GetTopic(client1, "highrate"), NT_DOUBLE, "double"); - nt::SubscribeMultiple(server, {{std::string_view{}}}); + wpi::nt::Publish(wpi::nt::GetTopic(client1, "highrate"), NT_DOUBLE, "double"); + wpi::nt::SubscribeMultiple(server, {{std::string_view{}}}); auto sub = - nt::Subscribe(nt::GetTopic(server, "highrate"), NT_DOUBLE, "double"); + wpi::nt::Subscribe(wpi::nt::GetTopic(server, "highrate"), NT_DOUBLE, "double"); auto sub2 = - nt::Subscribe(nt::GetTopic(client2, "highrate"), NT_DOUBLE, "double"); + wpi::nt::Subscribe(wpi::nt::GetTopic(client2, "highrate"), NT_DOUBLE, "double"); std::this_thread::sleep_for(1s); - nt::SetDouble(pub, 0); + wpi::nt::SetDouble(pub, 0); #if 0 // warm up for (int i = 1; i <= 10000; ++i) { - nt::SetDouble(pub, i * 0.01); + wpi::nt::SetDouble(pub, i * 0.01); if (i % 2000 == 0) { std::this_thread::sleep_for(0.02s); } @@ -374,26 +374,26 @@ void latency() { // benchmark client to server for (int i = 1; i <= 1000; ++i) { - int64_t sendTime = nt::Now(); - nt::SetDouble(pub, i, sendTime); - nt::Flush(client1); - while (nt::GetDouble(sub, 0) != i) { - wpi::WaitForObject(sub); + int64_t sendTime = wpi::nt::Now(); + wpi::nt::SetDouble(pub, i, sendTime); + wpi::nt::Flush(client1); + while (wpi::nt::GetDouble(sub, 0) != i) { + wpi::util::WaitForObject(sub); } - times.emplace_back(nt::Now() - sendTime); + times.emplace_back(wpi::nt::Now() - sendTime); } PrintTimes(times); // benchmark client to client times.resize(0); for (int i = 2001; i <= 3000; ++i) { - int64_t sendTime = nt::Now(); - nt::SetDouble(pub, i, sendTime); - nt::Flush(client1); - while (nt::GetDouble(sub2, 0) != i) { - wpi::WaitForObject(sub2); + int64_t sendTime = wpi::nt::Now(); + wpi::nt::SetDouble(pub, i, sendTime); + wpi::nt::Flush(client1); + while (wpi::nt::GetDouble(sub2, 0) != i) { + wpi::util::WaitForObject(sub2); } - times.emplace_back(nt::Now() - sendTime); + times.emplace_back(wpi::nt::Now() - sendTime); } PrintTimes(times); diff --git a/ntcore/src/generate/main/native/cpp/jni/types_jni.cpp.jinja b/ntcore/src/generate/main/native/cpp/jni/types_jni.cpp.jinja index cca55764ba..42cec20db6 100644 --- a/ntcore/src/generate/main/native/cpp/jni/types_jni.cpp.jinja +++ b/ntcore/src/generate/main/native/cpp/jni/types_jni.cpp.jinja @@ -11,7 +11,7 @@ #include "org_wpilib_networktables_NetworkTablesJNI.h" #include "wpi/nt/ntcore.h" -using namespace wpi::java; +using namespace wpi::util::java; // // Globals and load/unload @@ -45,7 +45,7 @@ static const JExceptionInit exceptions[] = { {"java/lang/NullPointerException", &nullPointerEx}, }; -namespace nt { +namespace wpi::nt { bool JNI_LoadTypes(JNIEnv* env) { // Cache references to classes @@ -76,7 +76,7 @@ void JNI_UnloadTypes(JNIEnv* env) { } } -} // namespace nt +} // namespace wpi::nt static std::vector FromJavaBooleanArray(JNIEnv* env, jbooleanArray jarr) { CriticalJSpan ref{env, jarr}; @@ -109,7 +109,7 @@ static std::vector FromJavaStringArray(JNIEnv* env, jobjectArray ja } {% for t in types %} -static jobject MakeJObject(JNIEnv* env, nt::Timestamped{{ t.TypeName }} value) { +static jobject MakeJObject(JNIEnv* env, wpi::nt::Timestamped{{ t.TypeName }} value) { static jmethodID constructor = env->GetMethodID( timestamped{{ t.TypeName }}Cls, "", "(JJ{{ t.jni.jtypestr }})V"); {%- if t.jni.JavaObject %} @@ -127,7 +127,7 @@ static jobject MakeJObject(JNIEnv* env, nt::Timestamped{{ t.TypeName }} value) { {% endfor %} {%- for t in types %} static jobjectArray MakeJObject(JNIEnv* env, - std::span arr) { + std::span arr) { jobjectArray jarr = env->NewObjectArray(arr.size(), timestamped{{ t.TypeName }}Cls, nullptr); if (!jarr) { @@ -168,7 +168,7 @@ JNIEXPORT jobject JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_getAtomic{{ t.TypeName }} (JNIEnv* env, jclass, jint subentry, {{ t.jni.jtype }} defaultValue) { - return MakeJObject(env, nt::GetAtomic{{ t.TypeName }}(subentry, {{ t.jni.FromJavaBegin }}defaultValue{{ t.jni.FromJavaEnd }})); + return MakeJObject(env, wpi::nt::GetAtomic{{ t.TypeName }}(subentry, {{ t.jni.FromJavaBegin }}defaultValue{{ t.jni.FromJavaEnd }})); } /* @@ -180,7 +180,7 @@ JNIEXPORT jobjectArray JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_readQueue{{ t.TypeName }} (JNIEnv* env, jclass, jint subentry) { - return MakeJObject(env, nt::ReadQueue{{ t.TypeName }}(subentry)); + return MakeJObject(env, wpi::nt::ReadQueue{{ t.TypeName }}(subentry)); } /* @@ -192,7 +192,7 @@ JNIEXPORT {% if t.jni.JavaObject %}jobject{% else %}{{ t.jni.jtype }}{% endif %} Java_org_wpilib_networktables_NetworkTablesJNI_readQueueValues{{ t.TypeName }} (JNIEnv* env, jclass, jint subentry) { - return {{ t.jni.ToJavaArray }}(env, nt::ReadQueueValues{{ t.TypeName }}(subentry)); + return {{ t.jni.ToJavaArray }}(env, wpi::nt::ReadQueueValues{{ t.TypeName }}(subentry)); } {% if t.TypeName == "Raw" %} /* @@ -221,7 +221,7 @@ Java_org_wpilib_networktables_NetworkTablesJNI_setRaw indexOobEx.Throw(env, "start + len must be smaller than array length"); return false; } - return nt::SetRaw(entry, cvalue.uarray().subspan(start, len), time); + return wpi::nt::SetRaw(entry, cvalue.uarray().subspan(start, len), time); } /* @@ -250,7 +250,7 @@ Java_org_wpilib_networktables_NetworkTablesJNI_setRawBuffer illegalArgEx.Throw(env, "value must be a native ByteBuffer"); return false; } - return nt::SetRaw(entry, cvalue.uarray().subspan(start, len), time); + return wpi::nt::SetRaw(entry, cvalue.uarray().subspan(start, len), time); } {% else %} /* @@ -268,7 +268,7 @@ Java_org_wpilib_networktables_NetworkTablesJNI_set{{ t.TypeName }} return false; } {%- endif %} - return nt::Set{{ t.TypeName }}(entry, {{ t.jni.FromJavaBegin }}value{{ t.jni.FromJavaEnd }}, time); + return wpi::nt::Set{{ t.TypeName }}(entry, {{ t.jni.FromJavaBegin }}value{{ t.jni.FromJavaEnd }}, time); } {% endif %} /* @@ -281,13 +281,13 @@ Java_org_wpilib_networktables_NetworkTablesJNI_get{{ t.TypeName }} (JNIEnv*{% if t.jni.JavaObject %} env{% endif %}, jclass, jint entry, {{ t.jni.jtype }} defaultValue) { {%- if t.jni.JavaObject %} - auto val = nt::GetEntryValue(entry); + auto val = wpi::nt::GetEntryValue(entry); if (!val || !val.Is{{ t.TypeName }}()) { return defaultValue; } return {{ t.jni.ToJavaBegin }}val.Get{{ t.TypeName }}(){{ t.jni.ToJavaEnd }}; {%- else %} - return nt::Get{{ t.TypeName }}(entry, defaultValue); + return wpi::nt::Get{{ t.TypeName }}(entry, defaultValue); {%- endif %} } {% if t.TypeName == "Raw" %} @@ -317,7 +317,7 @@ Java_org_wpilib_networktables_NetworkTablesJNI_setDefaultRaw indexOobEx.Throw(env, "start + len must be smaller than array length"); return false; } - return nt::SetDefaultRaw(entry, cvalue.uarray().subspan(start, len)); + return wpi::nt::SetDefaultRaw(entry, cvalue.uarray().subspan(start, len)); } /* @@ -346,7 +346,7 @@ Java_org_wpilib_networktables_NetworkTablesJNI_setDefaultRawBuffer illegalArgEx.Throw(env, "value must be a native ByteBuffer"); return false; } - return nt::SetDefaultRaw(entry, cvalue.uarray().subspan(start, len)); + return wpi::nt::SetDefaultRaw(entry, cvalue.uarray().subspan(start, len)); } {% else %} /* @@ -364,7 +364,7 @@ Java_org_wpilib_networktables_NetworkTablesJNI_setDefault{{ t.TypeName }} return false; } {%- endif %} - return nt::SetDefault{{ t.TypeName }}(entry, {{ t.jni.FromJavaBegin }}defaultValue{{ t.jni.FromJavaEnd }}); + return wpi::nt::SetDefault{{ t.TypeName }}(entry, {{ t.jni.FromJavaBegin }}defaultValue{{ t.jni.FromJavaEnd }}); } {% endif %} {% endfor %} diff --git a/ntcore/src/generate/main/native/cpp/ntcore_c_types.cpp.jinja b/ntcore/src/generate/main/native/cpp/ntcore_c_types.cpp.jinja index 0b421bcdc0..d03030a90d 100644 --- a/ntcore/src/generate/main/native/cpp/ntcore_c_types.cpp.jinja +++ b/ntcore/src/generate/main/native/cpp/ntcore_c_types.cpp.jinja @@ -9,7 +9,7 @@ #include "Value_internal.hpp" #include "wpi/nt/ntcore_cpp.hpp" -using namespace nt; +using namespace wpi::nt; template static inline std::span ConvertFromC(const T* arr, size_t size) { @@ -17,7 +17,7 @@ static inline std::span ConvertFromC(const T* arr, size_t size) { } static inline std::string_view ConvertFromC(const struct WPI_String* str) { - return wpi::to_string_view(str); + return wpi::util::to_string_view(str); } static std::vector ConvertFromC(const struct WPI_String* arr, size_t size) { @@ -30,7 +30,7 @@ static std::vector ConvertFromC(const struct WPI_String* arr, size_ } {% for t in types %} -static void ConvertToC(const nt::Timestamped{{ t.TypeName }}& in, NT_Timestamped{{ t.TypeName }}* out) { +static void ConvertToC(const wpi::nt::Timestamped{{ t.TypeName }}& in, NT_Timestamped{{ t.TypeName }}* out) { out->time = in.time; out->serverTime = in.serverTime; {%- if t.c.IsArray %} @@ -47,49 +47,49 @@ extern "C" { {% for t in types %} NT_Bool NT_Set{{ t.TypeName }}(NT_Handle pubentry, int64_t time, {{ t.c.ParamType }} value{% if t.c.IsArray %}, size_t len{% endif %}) { {%- if t.c.IsArray %} - return nt::Set{{ t.TypeName }}(pubentry, ConvertFromC(value, len), time); + return wpi::nt::Set{{ t.TypeName }}(pubentry, ConvertFromC(value, len), time); {%- elif t.c.ValueInline %} - return nt::Set{{ t.TypeName }}(pubentry, ConvertFromC(value), time); + return wpi::nt::Set{{ t.TypeName }}(pubentry, ConvertFromC(value), time); {%- else %} - return nt::Set{{ t.TypeName }}(pubentry, value, time); + return wpi::nt::Set{{ t.TypeName }}(pubentry, value, time); {%- endif %} } NT_Bool NT_SetDefault{{ t.TypeName }}(NT_Handle pubentry, {{ t.c.ParamType }} defaultValue{% if t.c.IsArray %}, size_t defaultValueLen{% endif %}) { {%- if t.c.IsArray %} - return nt::SetDefault{{ t.TypeName }}(pubentry, ConvertFromC(defaultValue, defaultValueLen)); + return wpi::nt::SetDefault{{ t.TypeName }}(pubentry, ConvertFromC(defaultValue, defaultValueLen)); {%- elif t.c.ValueInline %} - return nt::SetDefault{{ t.TypeName }}(pubentry, ConvertFromC(defaultValue)); + return wpi::nt::SetDefault{{ t.TypeName }}(pubentry, ConvertFromC(defaultValue)); {%- else %} - return nt::SetDefault{{ t.TypeName }}(pubentry, defaultValue); + return wpi::nt::SetDefault{{ t.TypeName }}(pubentry, defaultValue); {%- endif %} } {%- if t.c.ValueInline %} void NT_Get{{ t.TypeName }}(NT_Handle subentry, {{ t.c.ParamType }} defaultValue, {{ t.c.ValueType }} value) { - auto cppValue = nt::Get{{ t.TypeName }}(subentry, ConvertFromC(defaultValue)); + auto cppValue = wpi::nt::Get{{ t.TypeName }}(subentry, ConvertFromC(defaultValue)); ConvertToC(cppValue, value); } {%- else %} {{ t.c.ValueType }} NT_Get{{ t.TypeName }}(NT_Handle subentry, {{ t.c.ParamType }} defaultValue{% if t.c.IsArray %}, size_t defaultValueLen, size_t* len{% endif %}) { {%- if t.c.IsArray %} - auto cppValue = nt::Get{{ t.TypeName }}(subentry, ConvertFromC(defaultValue, defaultValueLen)); + auto cppValue = wpi::nt::Get{{ t.TypeName }}(subentry, ConvertFromC(defaultValue, defaultValueLen)); return ConvertToC<{{ t.c.ValueType[:-1] }}>(cppValue, len); {%- else %} - return nt::Get{{ t.TypeName }}(subentry, defaultValue); + return wpi::nt::Get{{ t.TypeName }}(subentry, defaultValue); {%- endif %} } {%- endif %} void NT_GetAtomic{{ t.TypeName }}(NT_Handle subentry, {{ t.c.ParamType }} defaultValue{% if t.c.IsArray %}, size_t defaultValueLen{% endif %}, struct NT_Timestamped{{ t.TypeName }}* value) { {%- if t.c.IsArray %} - auto cppValue = nt::GetAtomic{{ t.TypeName }}(subentry, ConvertFromC(defaultValue, defaultValueLen)); + auto cppValue = wpi::nt::GetAtomic{{ t.TypeName }}(subentry, ConvertFromC(defaultValue, defaultValueLen)); {%- elif t.c.ValueInline %} - auto cppValue = nt::GetAtomic{{ t.TypeName }}(subentry, ConvertFromC(defaultValue)); + auto cppValue = wpi::nt::GetAtomic{{ t.TypeName }}(subentry, ConvertFromC(defaultValue)); {%- else %} - auto cppValue = nt::GetAtomic{{ t.TypeName }}(subentry, defaultValue); + auto cppValue = wpi::nt::GetAtomic{{ t.TypeName }}(subentry, defaultValue); {%- endif %} ConvertToC(cppValue, value); } @@ -105,7 +105,7 @@ void NT_DisposeTimestamped{{ t.TypeName }}(struct NT_Timestamped{{ t.TypeName }} } struct NT_Timestamped{{ t.TypeName }}* NT_ReadQueue{{ t.TypeName }}(NT_Handle subentry, size_t* len) { - auto arr = nt::ReadQueue{{ t.TypeName }}(subentry); + auto arr = wpi::nt::ReadQueue{{ t.TypeName }}(subentry); return ConvertToC(arr, len); } @@ -118,7 +118,7 @@ void NT_FreeQueue{{ t.TypeName }}(struct NT_Timestamped{{ t.TypeName }}* arr, si {%- if not t.c.IsArray and not t.c.ValueInline %} {{ t.c.ValueType }}* NT_ReadQueueValues{{ t.TypeName }}(NT_Handle subentry, size_t* len) { - auto arr = nt::ReadQueueValues{{ t.TypeName }}(subentry); + auto arr = wpi::nt::ReadQueueValues{{ t.TypeName }}(subentry); return ConvertToC<{{ t.c.ValueType }}>(arr, len); } {%- endif %} diff --git a/ntcore/src/generate/main/native/cpp/ntcore_cpp_types.cpp.jinja b/ntcore/src/generate/main/native/cpp/ntcore_cpp_types.cpp.jinja index c627e52786..bdf01ad3cc 100644 --- a/ntcore/src/generate/main/native/cpp/ntcore_cpp_types.cpp.jinja +++ b/ntcore/src/generate/main/native/cpp/ntcore_cpp_types.cpp.jinja @@ -10,10 +10,10 @@ #include "InstanceImpl.hpp" namespace { -template +template struct ValuesType { using Vector = - std::vector>::Value>; + std::vector>::Value>; }; template <> @@ -22,7 +22,7 @@ struct ValuesType { }; } // namespace -namespace nt { +namespace wpi::nt { template static inline bool Set(NT_Handle pubentry, typename TypeInfo::View value, @@ -59,7 +59,7 @@ static inline Timestamped::Value> GetAtomic( template inline Timestamped::SmallRet> GetAtomic( NT_Handle subentry, - wpi::SmallVectorImpl::SmallElem>& buf, + wpi::util::SmallVectorImpl::SmallElem>& buf, typename TypeInfo::View defaultValue) { if (auto ii = InstanceImpl::Get(Handle{subentry}.GetInst())) { return ii->localStorage.GetAtomic(subentry, buf, defaultValue); @@ -117,18 +117,18 @@ std::vector<{% if t.cpp.ValueType == "bool" %}int{% else %}{{ t.cpp.ValueType }} {% if t.cpp.SmallRetType and t.cpp.SmallElemType %} {{ t.cpp.SmallRetType }} Get{{ t.TypeName }}( NT_Handle subentry, - wpi::SmallVectorImpl<{{ t.cpp.SmallElemType }}>& buf, + wpi::util::SmallVectorImpl<{{ t.cpp.SmallElemType }}>& buf, {{ t.cpp.ParamType }} defaultValue) { return GetAtomic<{{ t.cpp.TemplateType }}>(subentry, buf, defaultValue).value; } Timestamped{{ t.TypeName }}View GetAtomic{{ t.TypeName }}( NT_Handle subentry, - wpi::SmallVectorImpl<{{ t.cpp.SmallElemType }}>& buf, + wpi::util::SmallVectorImpl<{{ t.cpp.SmallElemType }}>& buf, {{ t.cpp.ParamType }} defaultValue) { return GetAtomic<{{ t.cpp.TemplateType }}>(subentry, buf, defaultValue); } {% endif %} {% endfor %} -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/generate/main/native/include/ntcore_cpp_types.hpp.jinja b/ntcore/src/generate/main/native/include/ntcore_cpp_types.hpp.jinja index b45152293d..5a00b092a9 100644 --- a/ntcore/src/generate/main/native/include/ntcore_cpp_types.hpp.jinja +++ b/ntcore/src/generate/main/native/include/ntcore_cpp_types.hpp.jinja @@ -16,12 +16,12 @@ #include "wpi/nt/ntcore_c.h" -namespace wpi { +namespace wpi::util { template class SmallVectorImpl; } // namespace wpi -namespace nt { +namespace wpi::nt { /** * Timestamped value. * @ingroup ntcore_cpp_handle_api @@ -55,7 +55,7 @@ struct Timestamped { using Timestamped{{ t.TypeName }} = Timestamped<{{ t.cpp.ValueType }}>; {% if t.cpp.SmallRetType %} /** - * Timestamped {{ t.TypeName }} view (for SmallVector-taking functions). + * Timestamped {{ t.TypeName }} view (for wpi::util::SmallVector-taking functions). * @ingroup ntcore_cpp_handle_api */ using Timestamped{{ t.TypeName }}View = Timestamped<{{ t.cpp.SmallRetType }}>; @@ -131,14 +131,14 @@ std::vector ReadQueue{{ t.TypeName }}(NT_Handle sub */ std::vector<{% if t.cpp.ValueType == "bool" %}int{% else %}{{ t.cpp.ValueType }}{% endif %}> ReadQueueValues{{ t.TypeName }}(NT_Handle subentry); {% if t.cpp.SmallRetType and t.cpp.SmallElemType %} -{{ t.cpp.SmallRetType }} Get{{ t.TypeName }}(NT_Handle subentry, wpi::SmallVectorImpl<{{ t.cpp.SmallElemType }}>& buf, {{ t.cpp.ParamType }} defaultValue); +{{ t.cpp.SmallRetType }} Get{{ t.TypeName }}(NT_Handle subentry, wpi::util::SmallVectorImpl<{{ t.cpp.SmallElemType }}>& buf, {{ t.cpp.ParamType }} defaultValue); Timestamped{{ t.TypeName }}View GetAtomic{{ t.TypeName }}( NT_Handle subentry, - wpi::SmallVectorImpl<{{ t.cpp.SmallElemType }}>& buf, + wpi::util::SmallVectorImpl<{{ t.cpp.SmallElemType }}>& buf, {{ t.cpp.ParamType }} defaultValue); {% endif %} /** @} */ {% endfor %} -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/generate/main/native/include/wpi/nt/Topic.hpp.jinja b/ntcore/src/generate/main/native/include/wpi/nt/Topic.hpp.jinja index 74f19ed5ac..581a12e07b 100644 --- a/ntcore/src/generate/main/native/include/wpi/nt/Topic.hpp.jinja +++ b/ntcore/src/generate/main/native/include/wpi/nt/Topic.hpp.jinja @@ -19,12 +19,12 @@ #include "wpi/nt/Topic.hpp" #include "wpi/nt/ntcore_cpp.hpp" -namespace wpi { +namespace wpi::util { template class SmallVectorImpl; } // namespace wpi -namespace nt { +namespace wpi::nt { class {{ TypeName }}Topic; @@ -74,7 +74,7 @@ class {{ TypeName }}Subscriber : public Subscriber { * @return value */ ValueType Get(ParamType defaultValue) const { - return ::nt::Get{{ TypeName }}(m_subHandle, defaultValue); + return ::wpi::nt::Get{{ TypeName }}(m_subHandle, defaultValue); } {% if cpp.SmallRetType and cpp.SmallElemType %} /** @@ -84,7 +84,7 @@ class {{ TypeName }}Subscriber : public Subscriber { * @param buf storage for returned value * @return value */ - SmallRetType Get(wpi::SmallVectorImpl& buf) const { + SmallRetType Get(wpi::util::SmallVectorImpl& buf) const { return Get(buf, m_defaultValue); } @@ -96,8 +96,8 @@ class {{ TypeName }}Subscriber : public Subscriber { * @param defaultValue default value to return if no value has been published * @return value */ - SmallRetType Get(wpi::SmallVectorImpl& buf, ParamType defaultValue) const { - return nt::Get{{ TypeName }}(m_subHandle, buf, defaultValue); + SmallRetType Get(wpi::util::SmallVectorImpl& buf, ParamType defaultValue) const { + return wpi::nt::Get{{ TypeName }}(m_subHandle, buf, defaultValue); } {% endif %} /** @@ -120,7 +120,7 @@ class {{ TypeName }}Subscriber : public Subscriber { * @return timestamped value */ TimestampedValueType GetAtomic(ParamType defaultValue) const { - return ::nt::GetAtomic{{ TypeName }}(m_subHandle, defaultValue); + return ::wpi::nt::GetAtomic{{ TypeName }}(m_subHandle, defaultValue); } {% if cpp.SmallRetType and cpp.SmallElemType %} /** @@ -132,7 +132,7 @@ class {{ TypeName }}Subscriber : public Subscriber { * @return timestamped value */ TimestampedValueViewType GetAtomic( - wpi::SmallVectorImpl& buf) const { + wpi::util::SmallVectorImpl& buf) const { return GetAtomic(buf, m_defaultValue); } @@ -146,9 +146,9 @@ class {{ TypeName }}Subscriber : public Subscriber { * @return timestamped value */ TimestampedValueViewType GetAtomic( - wpi::SmallVectorImpl& buf, + wpi::util::SmallVectorImpl& buf, ParamType defaultValue) const { - return nt::GetAtomic{{ TypeName }}(m_subHandle, buf, defaultValue); + return wpi::nt::GetAtomic{{ TypeName }}(m_subHandle, buf, defaultValue); } {% endif %} /** @@ -162,7 +162,7 @@ class {{ TypeName }}Subscriber : public Subscriber { * been published since the previous call. */ std::vector ReadQueue() { - return ::nt::ReadQueue{{ TypeName }}(m_subHandle); + return ::wpi::nt::ReadQueue{{ TypeName }}(m_subHandle); } /** @@ -207,7 +207,7 @@ class {{ TypeName }}Publisher : public Publisher { * @param time timestamp; 0 indicates current NT time should be used */ void Set(ParamType value, int64_t time = 0) { - ::nt::Set{{ TypeName }}(m_pubHandle, value, time); + ::wpi::nt::Set{{ TypeName }}(m_pubHandle, value, time); } /** @@ -218,7 +218,7 @@ class {{ TypeName }}Publisher : public Publisher { * @param value value */ void SetDefault(ParamType value) { - ::nt::SetDefault{{ TypeName }}(m_pubHandle, value); + ::wpi::nt::SetDefault{{ TypeName }}(m_pubHandle, value); } /** @@ -286,7 +286,7 @@ class {{ TypeName }}Entry final : public {{ TypeName }}Subscriber, * Stops publishing the entry if it's published. */ void Unpublish() { - ::nt::Unpublish(m_pubHandle); + ::wpi::nt::Unpublish(m_pubHandle); } }; @@ -346,7 +346,7 @@ class {{ TypeName }}Topic final : public Topic { {% if not TypeString %}std::string_view typeString, {% endif %}ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return {{ TypeName }}Subscriber{ - ::nt::Subscribe(m_handle, NT_{{ cpp.TYPE_NAME }}, {{ TypeString|default('typeString') }}, options), + ::wpi::nt::Subscribe(m_handle, NT_{{ cpp.TYPE_NAME }}, {{ TypeString|default('typeString') }}, options), defaultValue}; } {%- if TypeString %} @@ -371,7 +371,7 @@ class {{ TypeName }}Topic final : public Topic { std::string_view typeString, ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return {{ TypeName }}Subscriber{ - ::nt::Subscribe(m_handle, NT_{{ cpp.TYPE_NAME }}, typeString, options), + ::wpi::nt::Subscribe(m_handle, NT_{{ cpp.TYPE_NAME }}, typeString, options), defaultValue}; } {% endif %} @@ -396,7 +396,7 @@ class {{ TypeName }}Topic final : public Topic { [[nodiscard]] PublisherType Publish({% if not TypeString %}std::string_view typeString, {% endif %}const PubSubOptions& options = kDefaultPubSubOptions) { return {{ TypeName }}Publisher{ - ::nt::Publish(m_handle, NT_{{ cpp.TYPE_NAME }}, {{ TypeString|default('typeString') }}, options)}; + ::wpi::nt::Publish(m_handle, NT_{{ cpp.TYPE_NAME }}, {{ TypeString|default('typeString') }}, options)}; } /** @@ -419,9 +419,9 @@ class {{ TypeName }}Topic final : public Topic { */ [[nodiscard]] PublisherType PublishEx(std::string_view typeString, - const wpi::json& properties, const PubSubOptions& options = kDefaultPubSubOptions) { + const wpi::util::json& properties, const PubSubOptions& options = kDefaultPubSubOptions) { return {{ TypeName }}Publisher{ - ::nt::PublishEx(m_handle, NT_{{ cpp.TYPE_NAME }}, typeString, properties, options)}; + ::wpi::nt::PublishEx(m_handle, NT_{{ cpp.TYPE_NAME }}, typeString, properties, options)}; } /** @@ -451,7 +451,7 @@ class {{ TypeName }}Topic final : public Topic { EntryType GetEntry({% if not TypeString %}std::string_view typeString, {% endif %}ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return {{ TypeName }}Entry{ - ::nt::GetEntry(m_handle, NT_{{ cpp.TYPE_NAME }}, {{ TypeString|default('typeString') }}, options), + ::wpi::nt::GetEntry(m_handle, NT_{{ cpp.TYPE_NAME }}, {{ TypeString|default('typeString') }}, options), defaultValue}; } {%- if TypeString %} @@ -480,23 +480,23 @@ class {{ TypeName }}Topic final : public Topic { EntryType GetEntryEx(std::string_view typeString, ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return {{ TypeName }}Entry{ - ::nt::GetEntry(m_handle, NT_{{ cpp.TYPE_NAME }}, typeString, options), + ::wpi::nt::GetEntry(m_handle, NT_{{ cpp.TYPE_NAME }}, typeString, options), defaultValue}; } {% endif %} }; inline {{ TypeName }}Topic {{ TypeName }}Subscriber::GetTopic() const { - return {{ TypeName }}Topic{::nt::GetTopicFromHandle(m_subHandle)}; + return {{ TypeName }}Topic{::wpi::nt::GetTopicFromHandle(m_subHandle)}; } inline {{ TypeName }}Topic {{ TypeName }}Publisher::GetTopic() const { - return {{ TypeName }}Topic{::nt::GetTopicFromHandle(m_pubHandle)}; + return {{ TypeName }}Topic{::wpi::nt::GetTopicFromHandle(m_pubHandle)}; } inline {{ TypeName }}Topic {{ TypeName }}Entry::GetTopic() const { - return {{ TypeName }}Topic{::nt::GetTopicFromHandle(m_subHandle)}; + return {{ TypeName }}Topic{::wpi::nt::GetTopicFromHandle(m_subHandle)}; } -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/generated/main/native/cpp/jni/types_jni.cpp b/ntcore/src/generated/main/native/cpp/jni/types_jni.cpp index f561f3e4dc..51cdefe9db 100644 --- a/ntcore/src/generated/main/native/cpp/jni/types_jni.cpp +++ b/ntcore/src/generated/main/native/cpp/jni/types_jni.cpp @@ -11,7 +11,7 @@ #include "org_wpilib_networktables_NetworkTablesJNI.h" #include "wpi/nt/ntcore.h" -using namespace wpi::java; +using namespace wpi::util::java; // // Globals and load/unload @@ -64,7 +64,7 @@ static const JExceptionInit exceptions[] = { {"java/lang/NullPointerException", &nullPointerEx}, }; -namespace nt { +namespace wpi::nt { bool JNI_LoadTypes(JNIEnv* env) { // Cache references to classes @@ -95,7 +95,7 @@ void JNI_UnloadTypes(JNIEnv* env) { } } -} // namespace nt +} // namespace wpi::nt static std::vector FromJavaBooleanArray(JNIEnv* env, jbooleanArray jarr) { CriticalJSpan ref{env, jarr}; @@ -128,7 +128,7 @@ static std::vector FromJavaStringArray(JNIEnv* env, jobjectArray ja } -static jobject MakeJObject(JNIEnv* env, nt::TimestampedBoolean value) { +static jobject MakeJObject(JNIEnv* env, wpi::nt::TimestampedBoolean value) { static jmethodID constructor = env->GetMethodID( timestampedBooleanCls, "", "(JJZ)V"); return env->NewObject(timestampedBooleanCls, constructor, @@ -137,7 +137,7 @@ static jobject MakeJObject(JNIEnv* env, nt::TimestampedBoolean value) { static_cast(value.value)); } -static jobject MakeJObject(JNIEnv* env, nt::TimestampedInteger value) { +static jobject MakeJObject(JNIEnv* env, wpi::nt::TimestampedInteger value) { static jmethodID constructor = env->GetMethodID( timestampedIntegerCls, "", "(JJJ)V"); return env->NewObject(timestampedIntegerCls, constructor, @@ -146,7 +146,7 @@ static jobject MakeJObject(JNIEnv* env, nt::TimestampedInteger value) { static_cast(value.value)); } -static jobject MakeJObject(JNIEnv* env, nt::TimestampedFloat value) { +static jobject MakeJObject(JNIEnv* env, wpi::nt::TimestampedFloat value) { static jmethodID constructor = env->GetMethodID( timestampedFloatCls, "", "(JJF)V"); return env->NewObject(timestampedFloatCls, constructor, @@ -155,7 +155,7 @@ static jobject MakeJObject(JNIEnv* env, nt::TimestampedFloat value) { static_cast(value.value)); } -static jobject MakeJObject(JNIEnv* env, nt::TimestampedDouble value) { +static jobject MakeJObject(JNIEnv* env, wpi::nt::TimestampedDouble value) { static jmethodID constructor = env->GetMethodID( timestampedDoubleCls, "", "(JJD)V"); return env->NewObject(timestampedDoubleCls, constructor, @@ -164,7 +164,7 @@ static jobject MakeJObject(JNIEnv* env, nt::TimestampedDouble value) { static_cast(value.value)); } -static jobject MakeJObject(JNIEnv* env, nt::TimestampedString value) { +static jobject MakeJObject(JNIEnv* env, wpi::nt::TimestampedString value) { static jmethodID constructor = env->GetMethodID( timestampedStringCls, "", "(JJLjava/lang/String;)V"); JLocal val{env, MakeJString(env, value.value)}; @@ -173,7 +173,7 @@ static jobject MakeJObject(JNIEnv* env, nt::TimestampedString value) { static_cast(value.serverTime), val.obj()); } -static jobject MakeJObject(JNIEnv* env, nt::TimestampedRaw value) { +static jobject MakeJObject(JNIEnv* env, wpi::nt::TimestampedRaw value) { static jmethodID constructor = env->GetMethodID( timestampedRawCls, "", "(JJ[B)V"); JLocal val{env, MakeJByteArray(env, value.value)}; @@ -182,7 +182,7 @@ static jobject MakeJObject(JNIEnv* env, nt::TimestampedRaw value) { static_cast(value.serverTime), val.obj()); } -static jobject MakeJObject(JNIEnv* env, nt::TimestampedBooleanArray value) { +static jobject MakeJObject(JNIEnv* env, wpi::nt::TimestampedBooleanArray value) { static jmethodID constructor = env->GetMethodID( timestampedBooleanArrayCls, "", "(JJ[Z)V"); JLocal val{env, MakeJBooleanArray(env, value.value)}; @@ -191,7 +191,7 @@ static jobject MakeJObject(JNIEnv* env, nt::TimestampedBooleanArray value) { static_cast(value.serverTime), val.obj()); } -static jobject MakeJObject(JNIEnv* env, nt::TimestampedIntegerArray value) { +static jobject MakeJObject(JNIEnv* env, wpi::nt::TimestampedIntegerArray value) { static jmethodID constructor = env->GetMethodID( timestampedIntegerArrayCls, "", "(JJ[J)V"); JLocal val{env, MakeJLongArray(env, value.value)}; @@ -200,7 +200,7 @@ static jobject MakeJObject(JNIEnv* env, nt::TimestampedIntegerArray value) { static_cast(value.serverTime), val.obj()); } -static jobject MakeJObject(JNIEnv* env, nt::TimestampedFloatArray value) { +static jobject MakeJObject(JNIEnv* env, wpi::nt::TimestampedFloatArray value) { static jmethodID constructor = env->GetMethodID( timestampedFloatArrayCls, "", "(JJ[F)V"); JLocal val{env, MakeJFloatArray(env, value.value)}; @@ -209,7 +209,7 @@ static jobject MakeJObject(JNIEnv* env, nt::TimestampedFloatArray value) { static_cast(value.serverTime), val.obj()); } -static jobject MakeJObject(JNIEnv* env, nt::TimestampedDoubleArray value) { +static jobject MakeJObject(JNIEnv* env, wpi::nt::TimestampedDoubleArray value) { static jmethodID constructor = env->GetMethodID( timestampedDoubleArrayCls, "", "(JJ[D)V"); JLocal val{env, MakeJDoubleArray(env, value.value)}; @@ -218,7 +218,7 @@ static jobject MakeJObject(JNIEnv* env, nt::TimestampedDoubleArray value) { static_cast(value.serverTime), val.obj()); } -static jobject MakeJObject(JNIEnv* env, nt::TimestampedStringArray value) { +static jobject MakeJObject(JNIEnv* env, wpi::nt::TimestampedStringArray value) { static jmethodID constructor = env->GetMethodID( timestampedStringArrayCls, "", "(JJ[Ljava/lang/Object;)V"); JLocal val{env, MakeJStringArray(env, value.value)}; @@ -228,7 +228,7 @@ static jobject MakeJObject(JNIEnv* env, nt::TimestampedStringArray value) { } static jobjectArray MakeJObject(JNIEnv* env, - std::span arr) { + std::span arr) { jobjectArray jarr = env->NewObjectArray(arr.size(), timestampedBooleanCls, nullptr); if (!jarr) { @@ -242,7 +242,7 @@ static jobjectArray MakeJObject(JNIEnv* env, } static jobjectArray MakeJObject(JNIEnv* env, - std::span arr) { + std::span arr) { jobjectArray jarr = env->NewObjectArray(arr.size(), timestampedIntegerCls, nullptr); if (!jarr) { @@ -256,7 +256,7 @@ static jobjectArray MakeJObject(JNIEnv* env, } static jobjectArray MakeJObject(JNIEnv* env, - std::span arr) { + std::span arr) { jobjectArray jarr = env->NewObjectArray(arr.size(), timestampedFloatCls, nullptr); if (!jarr) { @@ -270,7 +270,7 @@ static jobjectArray MakeJObject(JNIEnv* env, } static jobjectArray MakeJObject(JNIEnv* env, - std::span arr) { + std::span arr) { jobjectArray jarr = env->NewObjectArray(arr.size(), timestampedDoubleCls, nullptr); if (!jarr) { @@ -284,7 +284,7 @@ static jobjectArray MakeJObject(JNIEnv* env, } static jobjectArray MakeJObject(JNIEnv* env, - std::span arr) { + std::span arr) { jobjectArray jarr = env->NewObjectArray(arr.size(), timestampedStringCls, nullptr); if (!jarr) { @@ -298,7 +298,7 @@ static jobjectArray MakeJObject(JNIEnv* env, } static jobjectArray MakeJObject(JNIEnv* env, - std::span arr) { + std::span arr) { jobjectArray jarr = env->NewObjectArray(arr.size(), timestampedRawCls, nullptr); if (!jarr) { @@ -312,7 +312,7 @@ static jobjectArray MakeJObject(JNIEnv* env, } static jobjectArray MakeJObject(JNIEnv* env, - std::span arr) { + std::span arr) { jobjectArray jarr = env->NewObjectArray(arr.size(), timestampedBooleanArrayCls, nullptr); if (!jarr) { @@ -326,7 +326,7 @@ static jobjectArray MakeJObject(JNIEnv* env, } static jobjectArray MakeJObject(JNIEnv* env, - std::span arr) { + std::span arr) { jobjectArray jarr = env->NewObjectArray(arr.size(), timestampedIntegerArrayCls, nullptr); if (!jarr) { @@ -340,7 +340,7 @@ static jobjectArray MakeJObject(JNIEnv* env, } static jobjectArray MakeJObject(JNIEnv* env, - std::span arr) { + std::span arr) { jobjectArray jarr = env->NewObjectArray(arr.size(), timestampedFloatArrayCls, nullptr); if (!jarr) { @@ -354,7 +354,7 @@ static jobjectArray MakeJObject(JNIEnv* env, } static jobjectArray MakeJObject(JNIEnv* env, - std::span arr) { + std::span arr) { jobjectArray jarr = env->NewObjectArray(arr.size(), timestampedDoubleArrayCls, nullptr); if (!jarr) { @@ -368,7 +368,7 @@ static jobjectArray MakeJObject(JNIEnv* env, } static jobjectArray MakeJObject(JNIEnv* env, - std::span arr) { + std::span arr) { jobjectArray jarr = env->NewObjectArray(arr.size(), timestampedStringArrayCls, nullptr); if (!jarr) { @@ -471,7 +471,7 @@ JNIEXPORT jobject JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_getAtomicBoolean (JNIEnv* env, jclass, jint subentry, jboolean defaultValue) { - return MakeJObject(env, nt::GetAtomicBoolean(subentry, defaultValue != JNI_FALSE)); + return MakeJObject(env, wpi::nt::GetAtomicBoolean(subentry, defaultValue != JNI_FALSE)); } /* @@ -483,7 +483,7 @@ JNIEXPORT jobjectArray JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_readQueueBoolean (JNIEnv* env, jclass, jint subentry) { - return MakeJObject(env, nt::ReadQueueBoolean(subentry)); + return MakeJObject(env, wpi::nt::ReadQueueBoolean(subentry)); } /* @@ -495,7 +495,7 @@ JNIEXPORT jbooleanArray JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_readQueueValuesBoolean (JNIEnv* env, jclass, jint subentry) { - return MakeJBooleanArray(env, nt::ReadQueueValuesBoolean(subentry)); + return MakeJBooleanArray(env, wpi::nt::ReadQueueValuesBoolean(subentry)); } /* @@ -507,7 +507,7 @@ JNIEXPORT jboolean JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_setBoolean (JNIEnv*, jclass, jint entry, jlong time, jboolean value) { - return nt::SetBoolean(entry, value != JNI_FALSE, time); + return wpi::nt::SetBoolean(entry, value != JNI_FALSE, time); } /* @@ -519,7 +519,7 @@ JNIEXPORT jboolean JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_getBoolean (JNIEnv*, jclass, jint entry, jboolean defaultValue) { - return nt::GetBoolean(entry, defaultValue); + return wpi::nt::GetBoolean(entry, defaultValue); } /* @@ -531,7 +531,7 @@ JNIEXPORT jboolean JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_setDefaultBoolean (JNIEnv*, jclass, jint entry, jlong, jboolean defaultValue) { - return nt::SetDefaultBoolean(entry, defaultValue != JNI_FALSE); + return wpi::nt::SetDefaultBoolean(entry, defaultValue != JNI_FALSE); } @@ -544,7 +544,7 @@ JNIEXPORT jobject JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_getAtomicInteger (JNIEnv* env, jclass, jint subentry, jlong defaultValue) { - return MakeJObject(env, nt::GetAtomicInteger(subentry, defaultValue)); + return MakeJObject(env, wpi::nt::GetAtomicInteger(subentry, defaultValue)); } /* @@ -556,7 +556,7 @@ JNIEXPORT jobjectArray JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_readQueueInteger (JNIEnv* env, jclass, jint subentry) { - return MakeJObject(env, nt::ReadQueueInteger(subentry)); + return MakeJObject(env, wpi::nt::ReadQueueInteger(subentry)); } /* @@ -568,7 +568,7 @@ JNIEXPORT jlongArray JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_readQueueValuesInteger (JNIEnv* env, jclass, jint subentry) { - return MakeJLongArray(env, nt::ReadQueueValuesInteger(subentry)); + return MakeJLongArray(env, wpi::nt::ReadQueueValuesInteger(subentry)); } /* @@ -580,7 +580,7 @@ JNIEXPORT jboolean JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_setInteger (JNIEnv*, jclass, jint entry, jlong time, jlong value) { - return nt::SetInteger(entry, value, time); + return wpi::nt::SetInteger(entry, value, time); } /* @@ -592,7 +592,7 @@ JNIEXPORT jlong JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_getInteger (JNIEnv*, jclass, jint entry, jlong defaultValue) { - return nt::GetInteger(entry, defaultValue); + return wpi::nt::GetInteger(entry, defaultValue); } /* @@ -604,7 +604,7 @@ JNIEXPORT jboolean JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_setDefaultInteger (JNIEnv*, jclass, jint entry, jlong, jlong defaultValue) { - return nt::SetDefaultInteger(entry, defaultValue); + return wpi::nt::SetDefaultInteger(entry, defaultValue); } @@ -617,7 +617,7 @@ JNIEXPORT jobject JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_getAtomicFloat (JNIEnv* env, jclass, jint subentry, jfloat defaultValue) { - return MakeJObject(env, nt::GetAtomicFloat(subentry, defaultValue)); + return MakeJObject(env, wpi::nt::GetAtomicFloat(subentry, defaultValue)); } /* @@ -629,7 +629,7 @@ JNIEXPORT jobjectArray JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_readQueueFloat (JNIEnv* env, jclass, jint subentry) { - return MakeJObject(env, nt::ReadQueueFloat(subentry)); + return MakeJObject(env, wpi::nt::ReadQueueFloat(subentry)); } /* @@ -641,7 +641,7 @@ JNIEXPORT jfloatArray JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_readQueueValuesFloat (JNIEnv* env, jclass, jint subentry) { - return MakeJFloatArray(env, nt::ReadQueueValuesFloat(subentry)); + return MakeJFloatArray(env, wpi::nt::ReadQueueValuesFloat(subentry)); } /* @@ -653,7 +653,7 @@ JNIEXPORT jboolean JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_setFloat (JNIEnv*, jclass, jint entry, jlong time, jfloat value) { - return nt::SetFloat(entry, value, time); + return wpi::nt::SetFloat(entry, value, time); } /* @@ -665,7 +665,7 @@ JNIEXPORT jfloat JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_getFloat (JNIEnv*, jclass, jint entry, jfloat defaultValue) { - return nt::GetFloat(entry, defaultValue); + return wpi::nt::GetFloat(entry, defaultValue); } /* @@ -677,7 +677,7 @@ JNIEXPORT jboolean JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_setDefaultFloat (JNIEnv*, jclass, jint entry, jlong, jfloat defaultValue) { - return nt::SetDefaultFloat(entry, defaultValue); + return wpi::nt::SetDefaultFloat(entry, defaultValue); } @@ -690,7 +690,7 @@ JNIEXPORT jobject JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_getAtomicDouble (JNIEnv* env, jclass, jint subentry, jdouble defaultValue) { - return MakeJObject(env, nt::GetAtomicDouble(subentry, defaultValue)); + return MakeJObject(env, wpi::nt::GetAtomicDouble(subentry, defaultValue)); } /* @@ -702,7 +702,7 @@ JNIEXPORT jobjectArray JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_readQueueDouble (JNIEnv* env, jclass, jint subentry) { - return MakeJObject(env, nt::ReadQueueDouble(subentry)); + return MakeJObject(env, wpi::nt::ReadQueueDouble(subentry)); } /* @@ -714,7 +714,7 @@ JNIEXPORT jdoubleArray JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_readQueueValuesDouble (JNIEnv* env, jclass, jint subentry) { - return MakeJDoubleArray(env, nt::ReadQueueValuesDouble(subentry)); + return MakeJDoubleArray(env, wpi::nt::ReadQueueValuesDouble(subentry)); } /* @@ -726,7 +726,7 @@ JNIEXPORT jboolean JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_setDouble (JNIEnv*, jclass, jint entry, jlong time, jdouble value) { - return nt::SetDouble(entry, value, time); + return wpi::nt::SetDouble(entry, value, time); } /* @@ -738,7 +738,7 @@ JNIEXPORT jdouble JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_getDouble (JNIEnv*, jclass, jint entry, jdouble defaultValue) { - return nt::GetDouble(entry, defaultValue); + return wpi::nt::GetDouble(entry, defaultValue); } /* @@ -750,7 +750,7 @@ JNIEXPORT jboolean JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_setDefaultDouble (JNIEnv*, jclass, jint entry, jlong, jdouble defaultValue) { - return nt::SetDefaultDouble(entry, defaultValue); + return wpi::nt::SetDefaultDouble(entry, defaultValue); } @@ -763,7 +763,7 @@ JNIEXPORT jobject JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_getAtomicString (JNIEnv* env, jclass, jint subentry, jstring defaultValue) { - return MakeJObject(env, nt::GetAtomicString(subentry, JStringRef{env, defaultValue})); + return MakeJObject(env, wpi::nt::GetAtomicString(subentry, JStringRef{env, defaultValue})); } /* @@ -775,7 +775,7 @@ JNIEXPORT jobjectArray JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_readQueueString (JNIEnv* env, jclass, jint subentry) { - return MakeJObject(env, nt::ReadQueueString(subentry)); + return MakeJObject(env, wpi::nt::ReadQueueString(subentry)); } /* @@ -787,7 +787,7 @@ JNIEXPORT jobjectArray JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_readQueueValuesString (JNIEnv* env, jclass, jint subentry) { - return MakeJStringArray(env, nt::ReadQueueValuesString(subentry)); + return MakeJStringArray(env, wpi::nt::ReadQueueValuesString(subentry)); } /* @@ -803,7 +803,7 @@ Java_org_wpilib_networktables_NetworkTablesJNI_setString nullPointerEx.Throw(env, "value cannot be null"); return false; } - return nt::SetString(entry, JStringRef{env, value}, time); + return wpi::nt::SetString(entry, JStringRef{env, value}, time); } /* @@ -815,7 +815,7 @@ JNIEXPORT jstring JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_getString (JNIEnv* env, jclass, jint entry, jstring defaultValue) { - auto val = nt::GetEntryValue(entry); + auto val = wpi::nt::GetEntryValue(entry); if (!val || !val.IsString()) { return defaultValue; } @@ -835,7 +835,7 @@ Java_org_wpilib_networktables_NetworkTablesJNI_setDefaultString nullPointerEx.Throw(env, "defaultValue cannot be null"); return false; } - return nt::SetDefaultString(entry, JStringRef{env, defaultValue}); + return wpi::nt::SetDefaultString(entry, JStringRef{env, defaultValue}); } @@ -848,7 +848,7 @@ JNIEXPORT jobject JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_getAtomicRaw (JNIEnv* env, jclass, jint subentry, jbyteArray defaultValue) { - return MakeJObject(env, nt::GetAtomicRaw(subentry, CriticalJSpan{env, defaultValue}.uarray())); + return MakeJObject(env, wpi::nt::GetAtomicRaw(subentry, CriticalJSpan{env, defaultValue}.uarray())); } /* @@ -860,7 +860,7 @@ JNIEXPORT jobjectArray JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_readQueueRaw (JNIEnv* env, jclass, jint subentry) { - return MakeJObject(env, nt::ReadQueueRaw(subentry)); + return MakeJObject(env, wpi::nt::ReadQueueRaw(subentry)); } /* @@ -872,7 +872,7 @@ JNIEXPORT jobjectArray JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_readQueueValuesRaw (JNIEnv* env, jclass, jint subentry) { - return MakeJObjectArray(env, nt::ReadQueueValuesRaw(subentry)); + return MakeJObjectArray(env, wpi::nt::ReadQueueValuesRaw(subentry)); } /* @@ -901,7 +901,7 @@ Java_org_wpilib_networktables_NetworkTablesJNI_setRaw indexOobEx.Throw(env, "start + len must be smaller than array length"); return false; } - return nt::SetRaw(entry, cvalue.uarray().subspan(start, len), time); + return wpi::nt::SetRaw(entry, cvalue.uarray().subspan(start, len), time); } /* @@ -930,7 +930,7 @@ Java_org_wpilib_networktables_NetworkTablesJNI_setRawBuffer illegalArgEx.Throw(env, "value must be a native ByteBuffer"); return false; } - return nt::SetRaw(entry, cvalue.uarray().subspan(start, len), time); + return wpi::nt::SetRaw(entry, cvalue.uarray().subspan(start, len), time); } /* @@ -942,7 +942,7 @@ JNIEXPORT jbyteArray JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_getRaw (JNIEnv* env, jclass, jint entry, jbyteArray defaultValue) { - auto val = nt::GetEntryValue(entry); + auto val = wpi::nt::GetEntryValue(entry); if (!val || !val.IsRaw()) { return defaultValue; } @@ -975,7 +975,7 @@ Java_org_wpilib_networktables_NetworkTablesJNI_setDefaultRaw indexOobEx.Throw(env, "start + len must be smaller than array length"); return false; } - return nt::SetDefaultRaw(entry, cvalue.uarray().subspan(start, len)); + return wpi::nt::SetDefaultRaw(entry, cvalue.uarray().subspan(start, len)); } /* @@ -1004,7 +1004,7 @@ Java_org_wpilib_networktables_NetworkTablesJNI_setDefaultRawBuffer illegalArgEx.Throw(env, "value must be a native ByteBuffer"); return false; } - return nt::SetDefaultRaw(entry, cvalue.uarray().subspan(start, len)); + return wpi::nt::SetDefaultRaw(entry, cvalue.uarray().subspan(start, len)); } @@ -1017,7 +1017,7 @@ JNIEXPORT jobject JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_getAtomicBooleanArray (JNIEnv* env, jclass, jint subentry, jbooleanArray defaultValue) { - return MakeJObject(env, nt::GetAtomicBooleanArray(subentry, FromJavaBooleanArray(env, defaultValue))); + return MakeJObject(env, wpi::nt::GetAtomicBooleanArray(subentry, FromJavaBooleanArray(env, defaultValue))); } /* @@ -1029,7 +1029,7 @@ JNIEXPORT jobjectArray JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_readQueueBooleanArray (JNIEnv* env, jclass, jint subentry) { - return MakeJObject(env, nt::ReadQueueBooleanArray(subentry)); + return MakeJObject(env, wpi::nt::ReadQueueBooleanArray(subentry)); } /* @@ -1041,7 +1041,7 @@ JNIEXPORT jobjectArray JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_readQueueValuesBooleanArray (JNIEnv* env, jclass, jint subentry) { - return MakeJObjectArray(env, nt::ReadQueueValuesBooleanArray(subentry)); + return MakeJObjectArray(env, wpi::nt::ReadQueueValuesBooleanArray(subentry)); } /* @@ -1057,7 +1057,7 @@ Java_org_wpilib_networktables_NetworkTablesJNI_setBooleanArray nullPointerEx.Throw(env, "value cannot be null"); return false; } - return nt::SetBooleanArray(entry, FromJavaBooleanArray(env, value), time); + return wpi::nt::SetBooleanArray(entry, FromJavaBooleanArray(env, value), time); } /* @@ -1069,7 +1069,7 @@ JNIEXPORT jbooleanArray JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_getBooleanArray (JNIEnv* env, jclass, jint entry, jbooleanArray defaultValue) { - auto val = nt::GetEntryValue(entry); + auto val = wpi::nt::GetEntryValue(entry); if (!val || !val.IsBooleanArray()) { return defaultValue; } @@ -1089,7 +1089,7 @@ Java_org_wpilib_networktables_NetworkTablesJNI_setDefaultBooleanArray nullPointerEx.Throw(env, "defaultValue cannot be null"); return false; } - return nt::SetDefaultBooleanArray(entry, FromJavaBooleanArray(env, defaultValue)); + return wpi::nt::SetDefaultBooleanArray(entry, FromJavaBooleanArray(env, defaultValue)); } @@ -1102,7 +1102,7 @@ JNIEXPORT jobject JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_getAtomicIntegerArray (JNIEnv* env, jclass, jint subentry, jlongArray defaultValue) { - return MakeJObject(env, nt::GetAtomicIntegerArray(subentry, CriticalJSpan{env, defaultValue})); + return MakeJObject(env, wpi::nt::GetAtomicIntegerArray(subentry, CriticalJSpan{env, defaultValue})); } /* @@ -1114,7 +1114,7 @@ JNIEXPORT jobjectArray JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_readQueueIntegerArray (JNIEnv* env, jclass, jint subentry) { - return MakeJObject(env, nt::ReadQueueIntegerArray(subentry)); + return MakeJObject(env, wpi::nt::ReadQueueIntegerArray(subentry)); } /* @@ -1126,7 +1126,7 @@ JNIEXPORT jobjectArray JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_readQueueValuesIntegerArray (JNIEnv* env, jclass, jint subentry) { - return MakeJObjectArray(env, nt::ReadQueueValuesIntegerArray(subentry)); + return MakeJObjectArray(env, wpi::nt::ReadQueueValuesIntegerArray(subentry)); } /* @@ -1142,7 +1142,7 @@ Java_org_wpilib_networktables_NetworkTablesJNI_setIntegerArray nullPointerEx.Throw(env, "value cannot be null"); return false; } - return nt::SetIntegerArray(entry, CriticalJSpan{env, value}, time); + return wpi::nt::SetIntegerArray(entry, CriticalJSpan{env, value}, time); } /* @@ -1154,7 +1154,7 @@ JNIEXPORT jlongArray JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_getIntegerArray (JNIEnv* env, jclass, jint entry, jlongArray defaultValue) { - auto val = nt::GetEntryValue(entry); + auto val = wpi::nt::GetEntryValue(entry); if (!val || !val.IsIntegerArray()) { return defaultValue; } @@ -1174,7 +1174,7 @@ Java_org_wpilib_networktables_NetworkTablesJNI_setDefaultIntegerArray nullPointerEx.Throw(env, "defaultValue cannot be null"); return false; } - return nt::SetDefaultIntegerArray(entry, CriticalJSpan{env, defaultValue}); + return wpi::nt::SetDefaultIntegerArray(entry, CriticalJSpan{env, defaultValue}); } @@ -1187,7 +1187,7 @@ JNIEXPORT jobject JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_getAtomicFloatArray (JNIEnv* env, jclass, jint subentry, jfloatArray defaultValue) { - return MakeJObject(env, nt::GetAtomicFloatArray(subentry, CriticalJSpan{env, defaultValue})); + return MakeJObject(env, wpi::nt::GetAtomicFloatArray(subentry, CriticalJSpan{env, defaultValue})); } /* @@ -1199,7 +1199,7 @@ JNIEXPORT jobjectArray JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_readQueueFloatArray (JNIEnv* env, jclass, jint subentry) { - return MakeJObject(env, nt::ReadQueueFloatArray(subentry)); + return MakeJObject(env, wpi::nt::ReadQueueFloatArray(subentry)); } /* @@ -1211,7 +1211,7 @@ JNIEXPORT jobjectArray JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_readQueueValuesFloatArray (JNIEnv* env, jclass, jint subentry) { - return MakeJObjectArray(env, nt::ReadQueueValuesFloatArray(subentry)); + return MakeJObjectArray(env, wpi::nt::ReadQueueValuesFloatArray(subentry)); } /* @@ -1227,7 +1227,7 @@ Java_org_wpilib_networktables_NetworkTablesJNI_setFloatArray nullPointerEx.Throw(env, "value cannot be null"); return false; } - return nt::SetFloatArray(entry, CriticalJSpan{env, value}, time); + return wpi::nt::SetFloatArray(entry, CriticalJSpan{env, value}, time); } /* @@ -1239,7 +1239,7 @@ JNIEXPORT jfloatArray JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_getFloatArray (JNIEnv* env, jclass, jint entry, jfloatArray defaultValue) { - auto val = nt::GetEntryValue(entry); + auto val = wpi::nt::GetEntryValue(entry); if (!val || !val.IsFloatArray()) { return defaultValue; } @@ -1259,7 +1259,7 @@ Java_org_wpilib_networktables_NetworkTablesJNI_setDefaultFloatArray nullPointerEx.Throw(env, "defaultValue cannot be null"); return false; } - return nt::SetDefaultFloatArray(entry, CriticalJSpan{env, defaultValue}); + return wpi::nt::SetDefaultFloatArray(entry, CriticalJSpan{env, defaultValue}); } @@ -1272,7 +1272,7 @@ JNIEXPORT jobject JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_getAtomicDoubleArray (JNIEnv* env, jclass, jint subentry, jdoubleArray defaultValue) { - return MakeJObject(env, nt::GetAtomicDoubleArray(subentry, CriticalJSpan{env, defaultValue})); + return MakeJObject(env, wpi::nt::GetAtomicDoubleArray(subentry, CriticalJSpan{env, defaultValue})); } /* @@ -1284,7 +1284,7 @@ JNIEXPORT jobjectArray JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_readQueueDoubleArray (JNIEnv* env, jclass, jint subentry) { - return MakeJObject(env, nt::ReadQueueDoubleArray(subentry)); + return MakeJObject(env, wpi::nt::ReadQueueDoubleArray(subentry)); } /* @@ -1296,7 +1296,7 @@ JNIEXPORT jobjectArray JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_readQueueValuesDoubleArray (JNIEnv* env, jclass, jint subentry) { - return MakeJObjectArray(env, nt::ReadQueueValuesDoubleArray(subentry)); + return MakeJObjectArray(env, wpi::nt::ReadQueueValuesDoubleArray(subentry)); } /* @@ -1312,7 +1312,7 @@ Java_org_wpilib_networktables_NetworkTablesJNI_setDoubleArray nullPointerEx.Throw(env, "value cannot be null"); return false; } - return nt::SetDoubleArray(entry, CriticalJSpan{env, value}, time); + return wpi::nt::SetDoubleArray(entry, CriticalJSpan{env, value}, time); } /* @@ -1324,7 +1324,7 @@ JNIEXPORT jdoubleArray JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_getDoubleArray (JNIEnv* env, jclass, jint entry, jdoubleArray defaultValue) { - auto val = nt::GetEntryValue(entry); + auto val = wpi::nt::GetEntryValue(entry); if (!val || !val.IsDoubleArray()) { return defaultValue; } @@ -1344,7 +1344,7 @@ Java_org_wpilib_networktables_NetworkTablesJNI_setDefaultDoubleArray nullPointerEx.Throw(env, "defaultValue cannot be null"); return false; } - return nt::SetDefaultDoubleArray(entry, CriticalJSpan{env, defaultValue}); + return wpi::nt::SetDefaultDoubleArray(entry, CriticalJSpan{env, defaultValue}); } @@ -1357,7 +1357,7 @@ JNIEXPORT jobject JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_getAtomicStringArray (JNIEnv* env, jclass, jint subentry, jobjectArray defaultValue) { - return MakeJObject(env, nt::GetAtomicStringArray(subentry, FromJavaStringArray(env, defaultValue))); + return MakeJObject(env, wpi::nt::GetAtomicStringArray(subentry, FromJavaStringArray(env, defaultValue))); } /* @@ -1369,7 +1369,7 @@ JNIEXPORT jobjectArray JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_readQueueStringArray (JNIEnv* env, jclass, jint subentry) { - return MakeJObject(env, nt::ReadQueueStringArray(subentry)); + return MakeJObject(env, wpi::nt::ReadQueueStringArray(subentry)); } /* @@ -1381,7 +1381,7 @@ JNIEXPORT jobjectArray JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_readQueueValuesStringArray (JNIEnv* env, jclass, jint subentry) { - return MakeJObjectArray(env, nt::ReadQueueValuesStringArray(subentry)); + return MakeJObjectArray(env, wpi::nt::ReadQueueValuesStringArray(subentry)); } /* @@ -1397,7 +1397,7 @@ Java_org_wpilib_networktables_NetworkTablesJNI_setStringArray nullPointerEx.Throw(env, "value cannot be null"); return false; } - return nt::SetStringArray(entry, FromJavaStringArray(env, value), time); + return wpi::nt::SetStringArray(entry, FromJavaStringArray(env, value), time); } /* @@ -1409,7 +1409,7 @@ JNIEXPORT jobjectArray JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_getStringArray (JNIEnv* env, jclass, jint entry, jobjectArray defaultValue) { - auto val = nt::GetEntryValue(entry); + auto val = wpi::nt::GetEntryValue(entry); if (!val || !val.IsStringArray()) { return defaultValue; } @@ -1429,7 +1429,7 @@ Java_org_wpilib_networktables_NetworkTablesJNI_setDefaultStringArray nullPointerEx.Throw(env, "defaultValue cannot be null"); return false; } - return nt::SetDefaultStringArray(entry, FromJavaStringArray(env, defaultValue)); + return wpi::nt::SetDefaultStringArray(entry, FromJavaStringArray(env, defaultValue)); } diff --git a/ntcore/src/generated/main/native/cpp/ntcore_c_types.cpp b/ntcore/src/generated/main/native/cpp/ntcore_c_types.cpp index 6d9dfade79..202f8b909c 100644 --- a/ntcore/src/generated/main/native/cpp/ntcore_c_types.cpp +++ b/ntcore/src/generated/main/native/cpp/ntcore_c_types.cpp @@ -9,7 +9,7 @@ #include "Value_internal.hpp" #include "wpi/nt/ntcore_cpp.hpp" -using namespace nt; +using namespace wpi::nt; template static inline std::span ConvertFromC(const T* arr, size_t size) { @@ -17,7 +17,7 @@ static inline std::span ConvertFromC(const T* arr, size_t size) { } static inline std::string_view ConvertFromC(const struct WPI_String* str) { - return wpi::to_string_view(str); + return wpi::util::to_string_view(str); } static std::vector ConvertFromC(const struct WPI_String* arr, size_t size) { @@ -30,67 +30,67 @@ static std::vector ConvertFromC(const struct WPI_String* arr, size_ } -static void ConvertToC(const nt::TimestampedBoolean& in, NT_TimestampedBoolean* out) { +static void ConvertToC(const wpi::nt::TimestampedBoolean& in, NT_TimestampedBoolean* out) { out->time = in.time; out->serverTime = in.serverTime; out->value = in.value; } -static void ConvertToC(const nt::TimestampedInteger& in, NT_TimestampedInteger* out) { +static void ConvertToC(const wpi::nt::TimestampedInteger& in, NT_TimestampedInteger* out) { out->time = in.time; out->serverTime = in.serverTime; out->value = in.value; } -static void ConvertToC(const nt::TimestampedFloat& in, NT_TimestampedFloat* out) { +static void ConvertToC(const wpi::nt::TimestampedFloat& in, NT_TimestampedFloat* out) { out->time = in.time; out->serverTime = in.serverTime; out->value = in.value; } -static void ConvertToC(const nt::TimestampedDouble& in, NT_TimestampedDouble* out) { +static void ConvertToC(const wpi::nt::TimestampedDouble& in, NT_TimestampedDouble* out) { out->time = in.time; out->serverTime = in.serverTime; out->value = in.value; } -static void ConvertToC(const nt::TimestampedString& in, NT_TimestampedString* out) { +static void ConvertToC(const wpi::nt::TimestampedString& in, NT_TimestampedString* out) { out->time = in.time; out->serverTime = in.serverTime; ConvertToC(in.value, &out->value); } -static void ConvertToC(const nt::TimestampedRaw& in, NT_TimestampedRaw* out) { +static void ConvertToC(const wpi::nt::TimestampedRaw& in, NT_TimestampedRaw* out) { out->time = in.time; out->serverTime = in.serverTime; out->value = ConvertToC(in.value, &out->len); } -static void ConvertToC(const nt::TimestampedBooleanArray& in, NT_TimestampedBooleanArray* out) { +static void ConvertToC(const wpi::nt::TimestampedBooleanArray& in, NT_TimestampedBooleanArray* out) { out->time = in.time; out->serverTime = in.serverTime; out->value = ConvertToC(in.value, &out->len); } -static void ConvertToC(const nt::TimestampedIntegerArray& in, NT_TimestampedIntegerArray* out) { +static void ConvertToC(const wpi::nt::TimestampedIntegerArray& in, NT_TimestampedIntegerArray* out) { out->time = in.time; out->serverTime = in.serverTime; out->value = ConvertToC(in.value, &out->len); } -static void ConvertToC(const nt::TimestampedFloatArray& in, NT_TimestampedFloatArray* out) { +static void ConvertToC(const wpi::nt::TimestampedFloatArray& in, NT_TimestampedFloatArray* out) { out->time = in.time; out->serverTime = in.serverTime; out->value = ConvertToC(in.value, &out->len); } -static void ConvertToC(const nt::TimestampedDoubleArray& in, NT_TimestampedDoubleArray* out) { +static void ConvertToC(const wpi::nt::TimestampedDoubleArray& in, NT_TimestampedDoubleArray* out) { out->time = in.time; out->serverTime = in.serverTime; out->value = ConvertToC(in.value, &out->len); } -static void ConvertToC(const nt::TimestampedStringArray& in, NT_TimestampedStringArray* out) { +static void ConvertToC(const wpi::nt::TimestampedStringArray& in, NT_TimestampedStringArray* out) { out->time = in.time; out->serverTime = in.serverTime; out->value = ConvertToC(in.value, &out->len); @@ -100,19 +100,19 @@ static void ConvertToC(const nt::TimestampedStringArray& in, NT_TimestampedStrin extern "C" { NT_Bool NT_SetBoolean(NT_Handle pubentry, int64_t time, NT_Bool value) { - return nt::SetBoolean(pubentry, value, time); + return wpi::nt::SetBoolean(pubentry, value, time); } NT_Bool NT_SetDefaultBoolean(NT_Handle pubentry, NT_Bool defaultValue) { - return nt::SetDefaultBoolean(pubentry, defaultValue); + return wpi::nt::SetDefaultBoolean(pubentry, defaultValue); } NT_Bool NT_GetBoolean(NT_Handle subentry, NT_Bool defaultValue) { - return nt::GetBoolean(subentry, defaultValue); + return wpi::nt::GetBoolean(subentry, defaultValue); } void NT_GetAtomicBoolean(NT_Handle subentry, NT_Bool defaultValue, struct NT_TimestampedBoolean* value) { - auto cppValue = nt::GetAtomicBoolean(subentry, defaultValue); + auto cppValue = wpi::nt::GetAtomicBoolean(subentry, defaultValue); ConvertToC(cppValue, value); } @@ -120,7 +120,7 @@ void NT_DisposeTimestampedBoolean(struct NT_TimestampedBoolean* value) { } struct NT_TimestampedBoolean* NT_ReadQueueBoolean(NT_Handle subentry, size_t* len) { - auto arr = nt::ReadQueueBoolean(subentry); + auto arr = wpi::nt::ReadQueueBoolean(subentry); return ConvertToC(arr, len); } @@ -131,25 +131,25 @@ void NT_FreeQueueBoolean(struct NT_TimestampedBoolean* arr, size_t len) { std::free(arr); } NT_Bool* NT_ReadQueueValuesBoolean(NT_Handle subentry, size_t* len) { - auto arr = nt::ReadQueueValuesBoolean(subentry); + auto arr = wpi::nt::ReadQueueValuesBoolean(subentry); return ConvertToC(arr, len); } NT_Bool NT_SetInteger(NT_Handle pubentry, int64_t time, int64_t value) { - return nt::SetInteger(pubentry, value, time); + return wpi::nt::SetInteger(pubentry, value, time); } NT_Bool NT_SetDefaultInteger(NT_Handle pubentry, int64_t defaultValue) { - return nt::SetDefaultInteger(pubentry, defaultValue); + return wpi::nt::SetDefaultInteger(pubentry, defaultValue); } int64_t NT_GetInteger(NT_Handle subentry, int64_t defaultValue) { - return nt::GetInteger(subentry, defaultValue); + return wpi::nt::GetInteger(subentry, defaultValue); } void NT_GetAtomicInteger(NT_Handle subentry, int64_t defaultValue, struct NT_TimestampedInteger* value) { - auto cppValue = nt::GetAtomicInteger(subentry, defaultValue); + auto cppValue = wpi::nt::GetAtomicInteger(subentry, defaultValue); ConvertToC(cppValue, value); } @@ -157,7 +157,7 @@ void NT_DisposeTimestampedInteger(struct NT_TimestampedInteger* value) { } struct NT_TimestampedInteger* NT_ReadQueueInteger(NT_Handle subentry, size_t* len) { - auto arr = nt::ReadQueueInteger(subentry); + auto arr = wpi::nt::ReadQueueInteger(subentry); return ConvertToC(arr, len); } @@ -168,25 +168,25 @@ void NT_FreeQueueInteger(struct NT_TimestampedInteger* arr, size_t len) { std::free(arr); } int64_t* NT_ReadQueueValuesInteger(NT_Handle subentry, size_t* len) { - auto arr = nt::ReadQueueValuesInteger(subentry); + auto arr = wpi::nt::ReadQueueValuesInteger(subentry); return ConvertToC(arr, len); } NT_Bool NT_SetFloat(NT_Handle pubentry, int64_t time, float value) { - return nt::SetFloat(pubentry, value, time); + return wpi::nt::SetFloat(pubentry, value, time); } NT_Bool NT_SetDefaultFloat(NT_Handle pubentry, float defaultValue) { - return nt::SetDefaultFloat(pubentry, defaultValue); + return wpi::nt::SetDefaultFloat(pubentry, defaultValue); } float NT_GetFloat(NT_Handle subentry, float defaultValue) { - return nt::GetFloat(subentry, defaultValue); + return wpi::nt::GetFloat(subentry, defaultValue); } void NT_GetAtomicFloat(NT_Handle subentry, float defaultValue, struct NT_TimestampedFloat* value) { - auto cppValue = nt::GetAtomicFloat(subentry, defaultValue); + auto cppValue = wpi::nt::GetAtomicFloat(subentry, defaultValue); ConvertToC(cppValue, value); } @@ -194,7 +194,7 @@ void NT_DisposeTimestampedFloat(struct NT_TimestampedFloat* value) { } struct NT_TimestampedFloat* NT_ReadQueueFloat(NT_Handle subentry, size_t* len) { - auto arr = nt::ReadQueueFloat(subentry); + auto arr = wpi::nt::ReadQueueFloat(subentry); return ConvertToC(arr, len); } @@ -205,25 +205,25 @@ void NT_FreeQueueFloat(struct NT_TimestampedFloat* arr, size_t len) { std::free(arr); } float* NT_ReadQueueValuesFloat(NT_Handle subentry, size_t* len) { - auto arr = nt::ReadQueueValuesFloat(subentry); + auto arr = wpi::nt::ReadQueueValuesFloat(subentry); return ConvertToC(arr, len); } NT_Bool NT_SetDouble(NT_Handle pubentry, int64_t time, double value) { - return nt::SetDouble(pubentry, value, time); + return wpi::nt::SetDouble(pubentry, value, time); } NT_Bool NT_SetDefaultDouble(NT_Handle pubentry, double defaultValue) { - return nt::SetDefaultDouble(pubentry, defaultValue); + return wpi::nt::SetDefaultDouble(pubentry, defaultValue); } double NT_GetDouble(NT_Handle subentry, double defaultValue) { - return nt::GetDouble(subentry, defaultValue); + return wpi::nt::GetDouble(subentry, defaultValue); } void NT_GetAtomicDouble(NT_Handle subentry, double defaultValue, struct NT_TimestampedDouble* value) { - auto cppValue = nt::GetAtomicDouble(subentry, defaultValue); + auto cppValue = wpi::nt::GetAtomicDouble(subentry, defaultValue); ConvertToC(cppValue, value); } @@ -231,7 +231,7 @@ void NT_DisposeTimestampedDouble(struct NT_TimestampedDouble* value) { } struct NT_TimestampedDouble* NT_ReadQueueDouble(NT_Handle subentry, size_t* len) { - auto arr = nt::ReadQueueDouble(subentry); + auto arr = wpi::nt::ReadQueueDouble(subentry); return ConvertToC(arr, len); } @@ -242,26 +242,26 @@ void NT_FreeQueueDouble(struct NT_TimestampedDouble* arr, size_t len) { std::free(arr); } double* NT_ReadQueueValuesDouble(NT_Handle subentry, size_t* len) { - auto arr = nt::ReadQueueValuesDouble(subentry); + auto arr = wpi::nt::ReadQueueValuesDouble(subentry); return ConvertToC(arr, len); } NT_Bool NT_SetString(NT_Handle pubentry, int64_t time, const struct WPI_String* value) { - return nt::SetString(pubentry, ConvertFromC(value), time); + return wpi::nt::SetString(pubentry, ConvertFromC(value), time); } NT_Bool NT_SetDefaultString(NT_Handle pubentry, const struct WPI_String* defaultValue) { - return nt::SetDefaultString(pubentry, ConvertFromC(defaultValue)); + return wpi::nt::SetDefaultString(pubentry, ConvertFromC(defaultValue)); } void NT_GetString(NT_Handle subentry, const struct WPI_String* defaultValue, struct WPI_String* value) { - auto cppValue = nt::GetString(subentry, ConvertFromC(defaultValue)); + auto cppValue = wpi::nt::GetString(subentry, ConvertFromC(defaultValue)); ConvertToC(cppValue, value); } void NT_GetAtomicString(NT_Handle subentry, const struct WPI_String* defaultValue, struct NT_TimestampedString* value) { - auto cppValue = nt::GetAtomicString(subentry, ConvertFromC(defaultValue)); + auto cppValue = wpi::nt::GetAtomicString(subentry, ConvertFromC(defaultValue)); ConvertToC(cppValue, value); } @@ -270,7 +270,7 @@ void NT_DisposeTimestampedString(struct NT_TimestampedString* value) { } struct NT_TimestampedString* NT_ReadQueueString(NT_Handle subentry, size_t* len) { - auto arr = nt::ReadQueueString(subentry); + auto arr = wpi::nt::ReadQueueString(subentry); return ConvertToC(arr, len); } @@ -283,20 +283,20 @@ void NT_FreeQueueString(struct NT_TimestampedString* arr, size_t len) { NT_Bool NT_SetRaw(NT_Handle pubentry, int64_t time, const uint8_t* value, size_t len) { - return nt::SetRaw(pubentry, ConvertFromC(value, len), time); + return wpi::nt::SetRaw(pubentry, ConvertFromC(value, len), time); } NT_Bool NT_SetDefaultRaw(NT_Handle pubentry, const uint8_t* defaultValue, size_t defaultValueLen) { - return nt::SetDefaultRaw(pubentry, ConvertFromC(defaultValue, defaultValueLen)); + return wpi::nt::SetDefaultRaw(pubentry, ConvertFromC(defaultValue, defaultValueLen)); } uint8_t* NT_GetRaw(NT_Handle subentry, const uint8_t* defaultValue, size_t defaultValueLen, size_t* len) { - auto cppValue = nt::GetRaw(subentry, ConvertFromC(defaultValue, defaultValueLen)); + auto cppValue = wpi::nt::GetRaw(subentry, ConvertFromC(defaultValue, defaultValueLen)); return ConvertToC(cppValue, len); } void NT_GetAtomicRaw(NT_Handle subentry, const uint8_t* defaultValue, size_t defaultValueLen, struct NT_TimestampedRaw* value) { - auto cppValue = nt::GetAtomicRaw(subentry, ConvertFromC(defaultValue, defaultValueLen)); + auto cppValue = wpi::nt::GetAtomicRaw(subentry, ConvertFromC(defaultValue, defaultValueLen)); ConvertToC(cppValue, value); } @@ -305,7 +305,7 @@ void NT_DisposeTimestampedRaw(struct NT_TimestampedRaw* value) { } struct NT_TimestampedRaw* NT_ReadQueueRaw(NT_Handle subentry, size_t* len) { - auto arr = nt::ReadQueueRaw(subentry); + auto arr = wpi::nt::ReadQueueRaw(subentry); return ConvertToC(arr, len); } @@ -318,20 +318,20 @@ void NT_FreeQueueRaw(struct NT_TimestampedRaw* arr, size_t len) { NT_Bool NT_SetBooleanArray(NT_Handle pubentry, int64_t time, const NT_Bool* value, size_t len) { - return nt::SetBooleanArray(pubentry, ConvertFromC(value, len), time); + return wpi::nt::SetBooleanArray(pubentry, ConvertFromC(value, len), time); } NT_Bool NT_SetDefaultBooleanArray(NT_Handle pubentry, const NT_Bool* defaultValue, size_t defaultValueLen) { - return nt::SetDefaultBooleanArray(pubentry, ConvertFromC(defaultValue, defaultValueLen)); + return wpi::nt::SetDefaultBooleanArray(pubentry, ConvertFromC(defaultValue, defaultValueLen)); } NT_Bool* NT_GetBooleanArray(NT_Handle subentry, const NT_Bool* defaultValue, size_t defaultValueLen, size_t* len) { - auto cppValue = nt::GetBooleanArray(subentry, ConvertFromC(defaultValue, defaultValueLen)); + auto cppValue = wpi::nt::GetBooleanArray(subentry, ConvertFromC(defaultValue, defaultValueLen)); return ConvertToC(cppValue, len); } void NT_GetAtomicBooleanArray(NT_Handle subentry, const NT_Bool* defaultValue, size_t defaultValueLen, struct NT_TimestampedBooleanArray* value) { - auto cppValue = nt::GetAtomicBooleanArray(subentry, ConvertFromC(defaultValue, defaultValueLen)); + auto cppValue = wpi::nt::GetAtomicBooleanArray(subentry, ConvertFromC(defaultValue, defaultValueLen)); ConvertToC(cppValue, value); } @@ -340,7 +340,7 @@ void NT_DisposeTimestampedBooleanArray(struct NT_TimestampedBooleanArray* value) } struct NT_TimestampedBooleanArray* NT_ReadQueueBooleanArray(NT_Handle subentry, size_t* len) { - auto arr = nt::ReadQueueBooleanArray(subentry); + auto arr = wpi::nt::ReadQueueBooleanArray(subentry); return ConvertToC(arr, len); } @@ -353,20 +353,20 @@ void NT_FreeQueueBooleanArray(struct NT_TimestampedBooleanArray* arr, size_t len NT_Bool NT_SetIntegerArray(NT_Handle pubentry, int64_t time, const int64_t* value, size_t len) { - return nt::SetIntegerArray(pubentry, ConvertFromC(value, len), time); + return wpi::nt::SetIntegerArray(pubentry, ConvertFromC(value, len), time); } NT_Bool NT_SetDefaultIntegerArray(NT_Handle pubentry, const int64_t* defaultValue, size_t defaultValueLen) { - return nt::SetDefaultIntegerArray(pubentry, ConvertFromC(defaultValue, defaultValueLen)); + return wpi::nt::SetDefaultIntegerArray(pubentry, ConvertFromC(defaultValue, defaultValueLen)); } int64_t* NT_GetIntegerArray(NT_Handle subentry, const int64_t* defaultValue, size_t defaultValueLen, size_t* len) { - auto cppValue = nt::GetIntegerArray(subentry, ConvertFromC(defaultValue, defaultValueLen)); + auto cppValue = wpi::nt::GetIntegerArray(subentry, ConvertFromC(defaultValue, defaultValueLen)); return ConvertToC(cppValue, len); } void NT_GetAtomicIntegerArray(NT_Handle subentry, const int64_t* defaultValue, size_t defaultValueLen, struct NT_TimestampedIntegerArray* value) { - auto cppValue = nt::GetAtomicIntegerArray(subentry, ConvertFromC(defaultValue, defaultValueLen)); + auto cppValue = wpi::nt::GetAtomicIntegerArray(subentry, ConvertFromC(defaultValue, defaultValueLen)); ConvertToC(cppValue, value); } @@ -375,7 +375,7 @@ void NT_DisposeTimestampedIntegerArray(struct NT_TimestampedIntegerArray* value) } struct NT_TimestampedIntegerArray* NT_ReadQueueIntegerArray(NT_Handle subentry, size_t* len) { - auto arr = nt::ReadQueueIntegerArray(subentry); + auto arr = wpi::nt::ReadQueueIntegerArray(subentry); return ConvertToC(arr, len); } @@ -388,20 +388,20 @@ void NT_FreeQueueIntegerArray(struct NT_TimestampedIntegerArray* arr, size_t len NT_Bool NT_SetFloatArray(NT_Handle pubentry, int64_t time, const float* value, size_t len) { - return nt::SetFloatArray(pubentry, ConvertFromC(value, len), time); + return wpi::nt::SetFloatArray(pubentry, ConvertFromC(value, len), time); } NT_Bool NT_SetDefaultFloatArray(NT_Handle pubentry, const float* defaultValue, size_t defaultValueLen) { - return nt::SetDefaultFloatArray(pubentry, ConvertFromC(defaultValue, defaultValueLen)); + return wpi::nt::SetDefaultFloatArray(pubentry, ConvertFromC(defaultValue, defaultValueLen)); } float* NT_GetFloatArray(NT_Handle subentry, const float* defaultValue, size_t defaultValueLen, size_t* len) { - auto cppValue = nt::GetFloatArray(subentry, ConvertFromC(defaultValue, defaultValueLen)); + auto cppValue = wpi::nt::GetFloatArray(subentry, ConvertFromC(defaultValue, defaultValueLen)); return ConvertToC(cppValue, len); } void NT_GetAtomicFloatArray(NT_Handle subentry, const float* defaultValue, size_t defaultValueLen, struct NT_TimestampedFloatArray* value) { - auto cppValue = nt::GetAtomicFloatArray(subentry, ConvertFromC(defaultValue, defaultValueLen)); + auto cppValue = wpi::nt::GetAtomicFloatArray(subentry, ConvertFromC(defaultValue, defaultValueLen)); ConvertToC(cppValue, value); } @@ -410,7 +410,7 @@ void NT_DisposeTimestampedFloatArray(struct NT_TimestampedFloatArray* value) { } struct NT_TimestampedFloatArray* NT_ReadQueueFloatArray(NT_Handle subentry, size_t* len) { - auto arr = nt::ReadQueueFloatArray(subentry); + auto arr = wpi::nt::ReadQueueFloatArray(subentry); return ConvertToC(arr, len); } @@ -423,20 +423,20 @@ void NT_FreeQueueFloatArray(struct NT_TimestampedFloatArray* arr, size_t len) { NT_Bool NT_SetDoubleArray(NT_Handle pubentry, int64_t time, const double* value, size_t len) { - return nt::SetDoubleArray(pubentry, ConvertFromC(value, len), time); + return wpi::nt::SetDoubleArray(pubentry, ConvertFromC(value, len), time); } NT_Bool NT_SetDefaultDoubleArray(NT_Handle pubentry, const double* defaultValue, size_t defaultValueLen) { - return nt::SetDefaultDoubleArray(pubentry, ConvertFromC(defaultValue, defaultValueLen)); + return wpi::nt::SetDefaultDoubleArray(pubentry, ConvertFromC(defaultValue, defaultValueLen)); } double* NT_GetDoubleArray(NT_Handle subentry, const double* defaultValue, size_t defaultValueLen, size_t* len) { - auto cppValue = nt::GetDoubleArray(subentry, ConvertFromC(defaultValue, defaultValueLen)); + auto cppValue = wpi::nt::GetDoubleArray(subentry, ConvertFromC(defaultValue, defaultValueLen)); return ConvertToC(cppValue, len); } void NT_GetAtomicDoubleArray(NT_Handle subentry, const double* defaultValue, size_t defaultValueLen, struct NT_TimestampedDoubleArray* value) { - auto cppValue = nt::GetAtomicDoubleArray(subentry, ConvertFromC(defaultValue, defaultValueLen)); + auto cppValue = wpi::nt::GetAtomicDoubleArray(subentry, ConvertFromC(defaultValue, defaultValueLen)); ConvertToC(cppValue, value); } @@ -445,7 +445,7 @@ void NT_DisposeTimestampedDoubleArray(struct NT_TimestampedDoubleArray* value) { } struct NT_TimestampedDoubleArray* NT_ReadQueueDoubleArray(NT_Handle subentry, size_t* len) { - auto arr = nt::ReadQueueDoubleArray(subentry); + auto arr = wpi::nt::ReadQueueDoubleArray(subentry); return ConvertToC(arr, len); } @@ -458,20 +458,20 @@ void NT_FreeQueueDoubleArray(struct NT_TimestampedDoubleArray* arr, size_t len) NT_Bool NT_SetStringArray(NT_Handle pubentry, int64_t time, const struct WPI_String* value, size_t len) { - return nt::SetStringArray(pubentry, ConvertFromC(value, len), time); + return wpi::nt::SetStringArray(pubentry, ConvertFromC(value, len), time); } NT_Bool NT_SetDefaultStringArray(NT_Handle pubentry, const struct WPI_String* defaultValue, size_t defaultValueLen) { - return nt::SetDefaultStringArray(pubentry, ConvertFromC(defaultValue, defaultValueLen)); + return wpi::nt::SetDefaultStringArray(pubentry, ConvertFromC(defaultValue, defaultValueLen)); } struct WPI_String* NT_GetStringArray(NT_Handle subentry, const struct WPI_String* defaultValue, size_t defaultValueLen, size_t* len) { - auto cppValue = nt::GetStringArray(subentry, ConvertFromC(defaultValue, defaultValueLen)); + auto cppValue = wpi::nt::GetStringArray(subentry, ConvertFromC(defaultValue, defaultValueLen)); return ConvertToC(cppValue, len); } void NT_GetAtomicStringArray(NT_Handle subentry, const struct WPI_String* defaultValue, size_t defaultValueLen, struct NT_TimestampedStringArray* value) { - auto cppValue = nt::GetAtomicStringArray(subentry, ConvertFromC(defaultValue, defaultValueLen)); + auto cppValue = wpi::nt::GetAtomicStringArray(subentry, ConvertFromC(defaultValue, defaultValueLen)); ConvertToC(cppValue, value); } @@ -480,7 +480,7 @@ void NT_DisposeTimestampedStringArray(struct NT_TimestampedStringArray* value) { } struct NT_TimestampedStringArray* NT_ReadQueueStringArray(NT_Handle subentry, size_t* len) { - auto arr = nt::ReadQueueStringArray(subentry); + auto arr = wpi::nt::ReadQueueStringArray(subentry); return ConvertToC(arr, len); } diff --git a/ntcore/src/generated/main/native/cpp/ntcore_cpp_types.cpp b/ntcore/src/generated/main/native/cpp/ntcore_cpp_types.cpp index 239a2a1a6f..5e9464fe6c 100644 --- a/ntcore/src/generated/main/native/cpp/ntcore_cpp_types.cpp +++ b/ntcore/src/generated/main/native/cpp/ntcore_cpp_types.cpp @@ -10,10 +10,10 @@ #include "InstanceImpl.hpp" namespace { -template +template struct ValuesType { using Vector = - std::vector>::Value>; + std::vector>::Value>; }; template <> @@ -22,7 +22,7 @@ struct ValuesType { }; } // namespace -namespace nt { +namespace wpi::nt { template static inline bool Set(NT_Handle pubentry, typename TypeInfo::View value, @@ -59,7 +59,7 @@ static inline Timestamped::Value> GetAtomic( template inline Timestamped::SmallRet> GetAtomic( NT_Handle subentry, - wpi::SmallVectorImpl::SmallElem>& buf, + wpi::util::SmallVectorImpl::SmallElem>& buf, typename TypeInfo::View defaultValue) { if (auto ii = InstanceImpl::Get(Handle{subentry}.GetInst())) { return ii->localStorage.GetAtomic(subentry, buf, defaultValue); @@ -221,14 +221,14 @@ std::vector ReadQueueValuesString(NT_Handle subentry) { std::string_view GetString( NT_Handle subentry, - wpi::SmallVectorImpl& buf, + wpi::util::SmallVectorImpl& buf, std::string_view defaultValue) { return GetAtomic(subentry, buf, defaultValue).value; } TimestampedStringView GetAtomicString( NT_Handle subentry, - wpi::SmallVectorImpl& buf, + wpi::util::SmallVectorImpl& buf, std::string_view defaultValue) { return GetAtomic(subentry, buf, defaultValue); } @@ -261,14 +261,14 @@ std::vector> ReadQueueValuesRaw(NT_Handle subentry) { std::span GetRaw( NT_Handle subentry, - wpi::SmallVectorImpl& buf, + wpi::util::SmallVectorImpl& buf, std::span defaultValue) { return GetAtomic(subentry, buf, defaultValue).value; } TimestampedRawView GetAtomicRaw( NT_Handle subentry, - wpi::SmallVectorImpl& buf, + wpi::util::SmallVectorImpl& buf, std::span defaultValue) { return GetAtomic(subentry, buf, defaultValue); } @@ -301,14 +301,14 @@ std::vector> ReadQueueValuesBooleanArray(NT_Handle subentry) { std::span GetBooleanArray( NT_Handle subentry, - wpi::SmallVectorImpl& buf, + wpi::util::SmallVectorImpl& buf, std::span defaultValue) { return GetAtomic(subentry, buf, defaultValue).value; } TimestampedBooleanArrayView GetAtomicBooleanArray( NT_Handle subentry, - wpi::SmallVectorImpl& buf, + wpi::util::SmallVectorImpl& buf, std::span defaultValue) { return GetAtomic(subentry, buf, defaultValue); } @@ -341,14 +341,14 @@ std::vector> ReadQueueValuesIntegerArray(NT_Handle subentry std::span GetIntegerArray( NT_Handle subentry, - wpi::SmallVectorImpl& buf, + wpi::util::SmallVectorImpl& buf, std::span defaultValue) { return GetAtomic(subentry, buf, defaultValue).value; } TimestampedIntegerArrayView GetAtomicIntegerArray( NT_Handle subentry, - wpi::SmallVectorImpl& buf, + wpi::util::SmallVectorImpl& buf, std::span defaultValue) { return GetAtomic(subentry, buf, defaultValue); } @@ -381,14 +381,14 @@ std::vector> ReadQueueValuesFloatArray(NT_Handle subentry) { std::span GetFloatArray( NT_Handle subentry, - wpi::SmallVectorImpl& buf, + wpi::util::SmallVectorImpl& buf, std::span defaultValue) { return GetAtomic(subentry, buf, defaultValue).value; } TimestampedFloatArrayView GetAtomicFloatArray( NT_Handle subentry, - wpi::SmallVectorImpl& buf, + wpi::util::SmallVectorImpl& buf, std::span defaultValue) { return GetAtomic(subentry, buf, defaultValue); } @@ -421,14 +421,14 @@ std::vector> ReadQueueValuesDoubleArray(NT_Handle subentry) std::span GetDoubleArray( NT_Handle subentry, - wpi::SmallVectorImpl& buf, + wpi::util::SmallVectorImpl& buf, std::span defaultValue) { return GetAtomic(subentry, buf, defaultValue).value; } TimestampedDoubleArrayView GetAtomicDoubleArray( NT_Handle subentry, - wpi::SmallVectorImpl& buf, + wpi::util::SmallVectorImpl& buf, std::span defaultValue) { return GetAtomic(subentry, buf, defaultValue); } @@ -460,4 +460,4 @@ std::vector> ReadQueueValuesStringArray(NT_Handle suben } -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/generated/main/native/include/wpi/nt/BooleanArrayTopic.hpp b/ntcore/src/generated/main/native/include/wpi/nt/BooleanArrayTopic.hpp index b5c972de3d..1cbfc5c1fa 100644 --- a/ntcore/src/generated/main/native/include/wpi/nt/BooleanArrayTopic.hpp +++ b/ntcore/src/generated/main/native/include/wpi/nt/BooleanArrayTopic.hpp @@ -19,12 +19,12 @@ #include "wpi/nt/Topic.hpp" #include "wpi/nt/ntcore_cpp.hpp" -namespace wpi { +namespace wpi::util { template class SmallVectorImpl; } // namespace wpi -namespace nt { +namespace wpi::nt { class BooleanArrayTopic; @@ -74,7 +74,7 @@ class BooleanArraySubscriber : public Subscriber { * @return value */ ValueType Get(ParamType defaultValue) const { - return ::nt::GetBooleanArray(m_subHandle, defaultValue); + return ::wpi::nt::GetBooleanArray(m_subHandle, defaultValue); } /** @@ -84,7 +84,7 @@ class BooleanArraySubscriber : public Subscriber { * @param buf storage for returned value * @return value */ - SmallRetType Get(wpi::SmallVectorImpl& buf) const { + SmallRetType Get(wpi::util::SmallVectorImpl& buf) const { return Get(buf, m_defaultValue); } @@ -96,8 +96,8 @@ class BooleanArraySubscriber : public Subscriber { * @param defaultValue default value to return if no value has been published * @return value */ - SmallRetType Get(wpi::SmallVectorImpl& buf, ParamType defaultValue) const { - return nt::GetBooleanArray(m_subHandle, buf, defaultValue); + SmallRetType Get(wpi::util::SmallVectorImpl& buf, ParamType defaultValue) const { + return wpi::nt::GetBooleanArray(m_subHandle, buf, defaultValue); } /** @@ -120,7 +120,7 @@ class BooleanArraySubscriber : public Subscriber { * @return timestamped value */ TimestampedValueType GetAtomic(ParamType defaultValue) const { - return ::nt::GetAtomicBooleanArray(m_subHandle, defaultValue); + return ::wpi::nt::GetAtomicBooleanArray(m_subHandle, defaultValue); } /** @@ -132,7 +132,7 @@ class BooleanArraySubscriber : public Subscriber { * @return timestamped value */ TimestampedValueViewType GetAtomic( - wpi::SmallVectorImpl& buf) const { + wpi::util::SmallVectorImpl& buf) const { return GetAtomic(buf, m_defaultValue); } @@ -146,9 +146,9 @@ class BooleanArraySubscriber : public Subscriber { * @return timestamped value */ TimestampedValueViewType GetAtomic( - wpi::SmallVectorImpl& buf, + wpi::util::SmallVectorImpl& buf, ParamType defaultValue) const { - return nt::GetAtomicBooleanArray(m_subHandle, buf, defaultValue); + return wpi::nt::GetAtomicBooleanArray(m_subHandle, buf, defaultValue); } /** @@ -162,7 +162,7 @@ class BooleanArraySubscriber : public Subscriber { * been published since the previous call. */ std::vector ReadQueue() { - return ::nt::ReadQueueBooleanArray(m_subHandle); + return ::wpi::nt::ReadQueueBooleanArray(m_subHandle); } /** @@ -207,7 +207,7 @@ class BooleanArrayPublisher : public Publisher { * @param time timestamp; 0 indicates current NT time should be used */ void Set(ParamType value, int64_t time = 0) { - ::nt::SetBooleanArray(m_pubHandle, value, time); + ::wpi::nt::SetBooleanArray(m_pubHandle, value, time); } /** @@ -218,7 +218,7 @@ class BooleanArrayPublisher : public Publisher { * @param value value */ void SetDefault(ParamType value) { - ::nt::SetDefaultBooleanArray(m_pubHandle, value); + ::wpi::nt::SetDefaultBooleanArray(m_pubHandle, value); } /** @@ -286,7 +286,7 @@ class BooleanArrayEntry final : public BooleanArraySubscriber, * Stops publishing the entry if it's published. */ void Unpublish() { - ::nt::Unpublish(m_pubHandle); + ::wpi::nt::Unpublish(m_pubHandle); } }; @@ -341,7 +341,7 @@ class BooleanArrayTopic final : public Topic { ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return BooleanArraySubscriber{ - ::nt::Subscribe(m_handle, NT_BOOLEAN_ARRAY, "boolean[]", options), + ::wpi::nt::Subscribe(m_handle, NT_BOOLEAN_ARRAY, "boolean[]", options), defaultValue}; } /** @@ -365,7 +365,7 @@ class BooleanArrayTopic final : public Topic { std::string_view typeString, ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return BooleanArraySubscriber{ - ::nt::Subscribe(m_handle, NT_BOOLEAN_ARRAY, typeString, options), + ::wpi::nt::Subscribe(m_handle, NT_BOOLEAN_ARRAY, typeString, options), defaultValue}; } @@ -387,7 +387,7 @@ class BooleanArrayTopic final : public Topic { [[nodiscard]] PublisherType Publish(const PubSubOptions& options = kDefaultPubSubOptions) { return BooleanArrayPublisher{ - ::nt::Publish(m_handle, NT_BOOLEAN_ARRAY, "boolean[]", options)}; + ::wpi::nt::Publish(m_handle, NT_BOOLEAN_ARRAY, "boolean[]", options)}; } /** @@ -410,9 +410,9 @@ class BooleanArrayTopic final : public Topic { */ [[nodiscard]] PublisherType PublishEx(std::string_view typeString, - const wpi::json& properties, const PubSubOptions& options = kDefaultPubSubOptions) { + const wpi::util::json& properties, const PubSubOptions& options = kDefaultPubSubOptions) { return BooleanArrayPublisher{ - ::nt::PublishEx(m_handle, NT_BOOLEAN_ARRAY, typeString, properties, options)}; + ::wpi::nt::PublishEx(m_handle, NT_BOOLEAN_ARRAY, typeString, properties, options)}; } /** @@ -439,7 +439,7 @@ class BooleanArrayTopic final : public Topic { EntryType GetEntry(ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return BooleanArrayEntry{ - ::nt::GetEntry(m_handle, NT_BOOLEAN_ARRAY, "boolean[]", options), + ::wpi::nt::GetEntry(m_handle, NT_BOOLEAN_ARRAY, "boolean[]", options), defaultValue}; } /** @@ -467,22 +467,22 @@ class BooleanArrayTopic final : public Topic { EntryType GetEntryEx(std::string_view typeString, ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return BooleanArrayEntry{ - ::nt::GetEntry(m_handle, NT_BOOLEAN_ARRAY, typeString, options), + ::wpi::nt::GetEntry(m_handle, NT_BOOLEAN_ARRAY, typeString, options), defaultValue}; } }; inline BooleanArrayTopic BooleanArraySubscriber::GetTopic() const { - return BooleanArrayTopic{::nt::GetTopicFromHandle(m_subHandle)}; + return BooleanArrayTopic{::wpi::nt::GetTopicFromHandle(m_subHandle)}; } inline BooleanArrayTopic BooleanArrayPublisher::GetTopic() const { - return BooleanArrayTopic{::nt::GetTopicFromHandle(m_pubHandle)}; + return BooleanArrayTopic{::wpi::nt::GetTopicFromHandle(m_pubHandle)}; } inline BooleanArrayTopic BooleanArrayEntry::GetTopic() const { - return BooleanArrayTopic{::nt::GetTopicFromHandle(m_subHandle)}; + return BooleanArrayTopic{::wpi::nt::GetTopicFromHandle(m_subHandle)}; } -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/generated/main/native/include/wpi/nt/BooleanTopic.hpp b/ntcore/src/generated/main/native/include/wpi/nt/BooleanTopic.hpp index 58c24d50a7..9c193fcaa7 100644 --- a/ntcore/src/generated/main/native/include/wpi/nt/BooleanTopic.hpp +++ b/ntcore/src/generated/main/native/include/wpi/nt/BooleanTopic.hpp @@ -19,12 +19,12 @@ #include "wpi/nt/Topic.hpp" #include "wpi/nt/ntcore_cpp.hpp" -namespace wpi { +namespace wpi::util { template class SmallVectorImpl; } // namespace wpi -namespace nt { +namespace wpi::nt { class BooleanTopic; @@ -70,7 +70,7 @@ class BooleanSubscriber : public Subscriber { * @return value */ ValueType Get(ParamType defaultValue) const { - return ::nt::GetBoolean(m_subHandle, defaultValue); + return ::wpi::nt::GetBoolean(m_subHandle, defaultValue); } /** @@ -93,7 +93,7 @@ class BooleanSubscriber : public Subscriber { * @return timestamped value */ TimestampedValueType GetAtomic(ParamType defaultValue) const { - return ::nt::GetAtomicBoolean(m_subHandle, defaultValue); + return ::wpi::nt::GetAtomicBoolean(m_subHandle, defaultValue); } /** @@ -107,7 +107,7 @@ class BooleanSubscriber : public Subscriber { * been published since the previous call. */ std::vector ReadQueue() { - return ::nt::ReadQueueBoolean(m_subHandle); + return ::wpi::nt::ReadQueueBoolean(m_subHandle); } /** @@ -149,7 +149,7 @@ class BooleanPublisher : public Publisher { * @param time timestamp; 0 indicates current NT time should be used */ void Set(ParamType value, int64_t time = 0) { - ::nt::SetBoolean(m_pubHandle, value, time); + ::wpi::nt::SetBoolean(m_pubHandle, value, time); } /** @@ -160,7 +160,7 @@ class BooleanPublisher : public Publisher { * @param value value */ void SetDefault(ParamType value) { - ::nt::SetDefaultBoolean(m_pubHandle, value); + ::wpi::nt::SetDefaultBoolean(m_pubHandle, value); } /** @@ -225,7 +225,7 @@ class BooleanEntry final : public BooleanSubscriber, * Stops publishing the entry if it's published. */ void Unpublish() { - ::nt::Unpublish(m_pubHandle); + ::wpi::nt::Unpublish(m_pubHandle); } }; @@ -280,7 +280,7 @@ class BooleanTopic final : public Topic { ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return BooleanSubscriber{ - ::nt::Subscribe(m_handle, NT_BOOLEAN, "boolean", options), + ::wpi::nt::Subscribe(m_handle, NT_BOOLEAN, "boolean", options), defaultValue}; } /** @@ -304,7 +304,7 @@ class BooleanTopic final : public Topic { std::string_view typeString, ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return BooleanSubscriber{ - ::nt::Subscribe(m_handle, NT_BOOLEAN, typeString, options), + ::wpi::nt::Subscribe(m_handle, NT_BOOLEAN, typeString, options), defaultValue}; } @@ -326,7 +326,7 @@ class BooleanTopic final : public Topic { [[nodiscard]] PublisherType Publish(const PubSubOptions& options = kDefaultPubSubOptions) { return BooleanPublisher{ - ::nt::Publish(m_handle, NT_BOOLEAN, "boolean", options)}; + ::wpi::nt::Publish(m_handle, NT_BOOLEAN, "boolean", options)}; } /** @@ -349,9 +349,9 @@ class BooleanTopic final : public Topic { */ [[nodiscard]] PublisherType PublishEx(std::string_view typeString, - const wpi::json& properties, const PubSubOptions& options = kDefaultPubSubOptions) { + const wpi::util::json& properties, const PubSubOptions& options = kDefaultPubSubOptions) { return BooleanPublisher{ - ::nt::PublishEx(m_handle, NT_BOOLEAN, typeString, properties, options)}; + ::wpi::nt::PublishEx(m_handle, NT_BOOLEAN, typeString, properties, options)}; } /** @@ -378,7 +378,7 @@ class BooleanTopic final : public Topic { EntryType GetEntry(ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return BooleanEntry{ - ::nt::GetEntry(m_handle, NT_BOOLEAN, "boolean", options), + ::wpi::nt::GetEntry(m_handle, NT_BOOLEAN, "boolean", options), defaultValue}; } /** @@ -406,22 +406,22 @@ class BooleanTopic final : public Topic { EntryType GetEntryEx(std::string_view typeString, ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return BooleanEntry{ - ::nt::GetEntry(m_handle, NT_BOOLEAN, typeString, options), + ::wpi::nt::GetEntry(m_handle, NT_BOOLEAN, typeString, options), defaultValue}; } }; inline BooleanTopic BooleanSubscriber::GetTopic() const { - return BooleanTopic{::nt::GetTopicFromHandle(m_subHandle)}; + return BooleanTopic{::wpi::nt::GetTopicFromHandle(m_subHandle)}; } inline BooleanTopic BooleanPublisher::GetTopic() const { - return BooleanTopic{::nt::GetTopicFromHandle(m_pubHandle)}; + return BooleanTopic{::wpi::nt::GetTopicFromHandle(m_pubHandle)}; } inline BooleanTopic BooleanEntry::GetTopic() const { - return BooleanTopic{::nt::GetTopicFromHandle(m_subHandle)}; + return BooleanTopic{::wpi::nt::GetTopicFromHandle(m_subHandle)}; } -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/generated/main/native/include/wpi/nt/DoubleArrayTopic.hpp b/ntcore/src/generated/main/native/include/wpi/nt/DoubleArrayTopic.hpp index f89c29f451..8699071820 100644 --- a/ntcore/src/generated/main/native/include/wpi/nt/DoubleArrayTopic.hpp +++ b/ntcore/src/generated/main/native/include/wpi/nt/DoubleArrayTopic.hpp @@ -19,12 +19,12 @@ #include "wpi/nt/Topic.hpp" #include "wpi/nt/ntcore_cpp.hpp" -namespace wpi { +namespace wpi::util { template class SmallVectorImpl; } // namespace wpi -namespace nt { +namespace wpi::nt { class DoubleArrayTopic; @@ -74,7 +74,7 @@ class DoubleArraySubscriber : public Subscriber { * @return value */ ValueType Get(ParamType defaultValue) const { - return ::nt::GetDoubleArray(m_subHandle, defaultValue); + return ::wpi::nt::GetDoubleArray(m_subHandle, defaultValue); } /** @@ -84,7 +84,7 @@ class DoubleArraySubscriber : public Subscriber { * @param buf storage for returned value * @return value */ - SmallRetType Get(wpi::SmallVectorImpl& buf) const { + SmallRetType Get(wpi::util::SmallVectorImpl& buf) const { return Get(buf, m_defaultValue); } @@ -96,8 +96,8 @@ class DoubleArraySubscriber : public Subscriber { * @param defaultValue default value to return if no value has been published * @return value */ - SmallRetType Get(wpi::SmallVectorImpl& buf, ParamType defaultValue) const { - return nt::GetDoubleArray(m_subHandle, buf, defaultValue); + SmallRetType Get(wpi::util::SmallVectorImpl& buf, ParamType defaultValue) const { + return wpi::nt::GetDoubleArray(m_subHandle, buf, defaultValue); } /** @@ -120,7 +120,7 @@ class DoubleArraySubscriber : public Subscriber { * @return timestamped value */ TimestampedValueType GetAtomic(ParamType defaultValue) const { - return ::nt::GetAtomicDoubleArray(m_subHandle, defaultValue); + return ::wpi::nt::GetAtomicDoubleArray(m_subHandle, defaultValue); } /** @@ -132,7 +132,7 @@ class DoubleArraySubscriber : public Subscriber { * @return timestamped value */ TimestampedValueViewType GetAtomic( - wpi::SmallVectorImpl& buf) const { + wpi::util::SmallVectorImpl& buf) const { return GetAtomic(buf, m_defaultValue); } @@ -146,9 +146,9 @@ class DoubleArraySubscriber : public Subscriber { * @return timestamped value */ TimestampedValueViewType GetAtomic( - wpi::SmallVectorImpl& buf, + wpi::util::SmallVectorImpl& buf, ParamType defaultValue) const { - return nt::GetAtomicDoubleArray(m_subHandle, buf, defaultValue); + return wpi::nt::GetAtomicDoubleArray(m_subHandle, buf, defaultValue); } /** @@ -162,7 +162,7 @@ class DoubleArraySubscriber : public Subscriber { * been published since the previous call. */ std::vector ReadQueue() { - return ::nt::ReadQueueDoubleArray(m_subHandle); + return ::wpi::nt::ReadQueueDoubleArray(m_subHandle); } /** @@ -207,7 +207,7 @@ class DoubleArrayPublisher : public Publisher { * @param time timestamp; 0 indicates current NT time should be used */ void Set(ParamType value, int64_t time = 0) { - ::nt::SetDoubleArray(m_pubHandle, value, time); + ::wpi::nt::SetDoubleArray(m_pubHandle, value, time); } /** @@ -218,7 +218,7 @@ class DoubleArrayPublisher : public Publisher { * @param value value */ void SetDefault(ParamType value) { - ::nt::SetDefaultDoubleArray(m_pubHandle, value); + ::wpi::nt::SetDefaultDoubleArray(m_pubHandle, value); } /** @@ -286,7 +286,7 @@ class DoubleArrayEntry final : public DoubleArraySubscriber, * Stops publishing the entry if it's published. */ void Unpublish() { - ::nt::Unpublish(m_pubHandle); + ::wpi::nt::Unpublish(m_pubHandle); } }; @@ -341,7 +341,7 @@ class DoubleArrayTopic final : public Topic { ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return DoubleArraySubscriber{ - ::nt::Subscribe(m_handle, NT_DOUBLE_ARRAY, "double[]", options), + ::wpi::nt::Subscribe(m_handle, NT_DOUBLE_ARRAY, "double[]", options), defaultValue}; } /** @@ -365,7 +365,7 @@ class DoubleArrayTopic final : public Topic { std::string_view typeString, ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return DoubleArraySubscriber{ - ::nt::Subscribe(m_handle, NT_DOUBLE_ARRAY, typeString, options), + ::wpi::nt::Subscribe(m_handle, NT_DOUBLE_ARRAY, typeString, options), defaultValue}; } @@ -387,7 +387,7 @@ class DoubleArrayTopic final : public Topic { [[nodiscard]] PublisherType Publish(const PubSubOptions& options = kDefaultPubSubOptions) { return DoubleArrayPublisher{ - ::nt::Publish(m_handle, NT_DOUBLE_ARRAY, "double[]", options)}; + ::wpi::nt::Publish(m_handle, NT_DOUBLE_ARRAY, "double[]", options)}; } /** @@ -410,9 +410,9 @@ class DoubleArrayTopic final : public Topic { */ [[nodiscard]] PublisherType PublishEx(std::string_view typeString, - const wpi::json& properties, const PubSubOptions& options = kDefaultPubSubOptions) { + const wpi::util::json& properties, const PubSubOptions& options = kDefaultPubSubOptions) { return DoubleArrayPublisher{ - ::nt::PublishEx(m_handle, NT_DOUBLE_ARRAY, typeString, properties, options)}; + ::wpi::nt::PublishEx(m_handle, NT_DOUBLE_ARRAY, typeString, properties, options)}; } /** @@ -439,7 +439,7 @@ class DoubleArrayTopic final : public Topic { EntryType GetEntry(ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return DoubleArrayEntry{ - ::nt::GetEntry(m_handle, NT_DOUBLE_ARRAY, "double[]", options), + ::wpi::nt::GetEntry(m_handle, NT_DOUBLE_ARRAY, "double[]", options), defaultValue}; } /** @@ -467,22 +467,22 @@ class DoubleArrayTopic final : public Topic { EntryType GetEntryEx(std::string_view typeString, ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return DoubleArrayEntry{ - ::nt::GetEntry(m_handle, NT_DOUBLE_ARRAY, typeString, options), + ::wpi::nt::GetEntry(m_handle, NT_DOUBLE_ARRAY, typeString, options), defaultValue}; } }; inline DoubleArrayTopic DoubleArraySubscriber::GetTopic() const { - return DoubleArrayTopic{::nt::GetTopicFromHandle(m_subHandle)}; + return DoubleArrayTopic{::wpi::nt::GetTopicFromHandle(m_subHandle)}; } inline DoubleArrayTopic DoubleArrayPublisher::GetTopic() const { - return DoubleArrayTopic{::nt::GetTopicFromHandle(m_pubHandle)}; + return DoubleArrayTopic{::wpi::nt::GetTopicFromHandle(m_pubHandle)}; } inline DoubleArrayTopic DoubleArrayEntry::GetTopic() const { - return DoubleArrayTopic{::nt::GetTopicFromHandle(m_subHandle)}; + return DoubleArrayTopic{::wpi::nt::GetTopicFromHandle(m_subHandle)}; } -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/generated/main/native/include/wpi/nt/DoubleTopic.hpp b/ntcore/src/generated/main/native/include/wpi/nt/DoubleTopic.hpp index 41dca50f43..e0e85ab5de 100644 --- a/ntcore/src/generated/main/native/include/wpi/nt/DoubleTopic.hpp +++ b/ntcore/src/generated/main/native/include/wpi/nt/DoubleTopic.hpp @@ -19,12 +19,12 @@ #include "wpi/nt/Topic.hpp" #include "wpi/nt/ntcore_cpp.hpp" -namespace wpi { +namespace wpi::util { template class SmallVectorImpl; } // namespace wpi -namespace nt { +namespace wpi::nt { class DoubleTopic; @@ -70,7 +70,7 @@ class DoubleSubscriber : public Subscriber { * @return value */ ValueType Get(ParamType defaultValue) const { - return ::nt::GetDouble(m_subHandle, defaultValue); + return ::wpi::nt::GetDouble(m_subHandle, defaultValue); } /** @@ -93,7 +93,7 @@ class DoubleSubscriber : public Subscriber { * @return timestamped value */ TimestampedValueType GetAtomic(ParamType defaultValue) const { - return ::nt::GetAtomicDouble(m_subHandle, defaultValue); + return ::wpi::nt::GetAtomicDouble(m_subHandle, defaultValue); } /** @@ -107,7 +107,7 @@ class DoubleSubscriber : public Subscriber { * been published since the previous call. */ std::vector ReadQueue() { - return ::nt::ReadQueueDouble(m_subHandle); + return ::wpi::nt::ReadQueueDouble(m_subHandle); } /** @@ -149,7 +149,7 @@ class DoublePublisher : public Publisher { * @param time timestamp; 0 indicates current NT time should be used */ void Set(ParamType value, int64_t time = 0) { - ::nt::SetDouble(m_pubHandle, value, time); + ::wpi::nt::SetDouble(m_pubHandle, value, time); } /** @@ -160,7 +160,7 @@ class DoublePublisher : public Publisher { * @param value value */ void SetDefault(ParamType value) { - ::nt::SetDefaultDouble(m_pubHandle, value); + ::wpi::nt::SetDefaultDouble(m_pubHandle, value); } /** @@ -225,7 +225,7 @@ class DoubleEntry final : public DoubleSubscriber, * Stops publishing the entry if it's published. */ void Unpublish() { - ::nt::Unpublish(m_pubHandle); + ::wpi::nt::Unpublish(m_pubHandle); } }; @@ -280,7 +280,7 @@ class DoubleTopic final : public Topic { ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return DoubleSubscriber{ - ::nt::Subscribe(m_handle, NT_DOUBLE, "double", options), + ::wpi::nt::Subscribe(m_handle, NT_DOUBLE, "double", options), defaultValue}; } /** @@ -304,7 +304,7 @@ class DoubleTopic final : public Topic { std::string_view typeString, ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return DoubleSubscriber{ - ::nt::Subscribe(m_handle, NT_DOUBLE, typeString, options), + ::wpi::nt::Subscribe(m_handle, NT_DOUBLE, typeString, options), defaultValue}; } @@ -326,7 +326,7 @@ class DoubleTopic final : public Topic { [[nodiscard]] PublisherType Publish(const PubSubOptions& options = kDefaultPubSubOptions) { return DoublePublisher{ - ::nt::Publish(m_handle, NT_DOUBLE, "double", options)}; + ::wpi::nt::Publish(m_handle, NT_DOUBLE, "double", options)}; } /** @@ -349,9 +349,9 @@ class DoubleTopic final : public Topic { */ [[nodiscard]] PublisherType PublishEx(std::string_view typeString, - const wpi::json& properties, const PubSubOptions& options = kDefaultPubSubOptions) { + const wpi::util::json& properties, const PubSubOptions& options = kDefaultPubSubOptions) { return DoublePublisher{ - ::nt::PublishEx(m_handle, NT_DOUBLE, typeString, properties, options)}; + ::wpi::nt::PublishEx(m_handle, NT_DOUBLE, typeString, properties, options)}; } /** @@ -378,7 +378,7 @@ class DoubleTopic final : public Topic { EntryType GetEntry(ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return DoubleEntry{ - ::nt::GetEntry(m_handle, NT_DOUBLE, "double", options), + ::wpi::nt::GetEntry(m_handle, NT_DOUBLE, "double", options), defaultValue}; } /** @@ -406,22 +406,22 @@ class DoubleTopic final : public Topic { EntryType GetEntryEx(std::string_view typeString, ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return DoubleEntry{ - ::nt::GetEntry(m_handle, NT_DOUBLE, typeString, options), + ::wpi::nt::GetEntry(m_handle, NT_DOUBLE, typeString, options), defaultValue}; } }; inline DoubleTopic DoubleSubscriber::GetTopic() const { - return DoubleTopic{::nt::GetTopicFromHandle(m_subHandle)}; + return DoubleTopic{::wpi::nt::GetTopicFromHandle(m_subHandle)}; } inline DoubleTopic DoublePublisher::GetTopic() const { - return DoubleTopic{::nt::GetTopicFromHandle(m_pubHandle)}; + return DoubleTopic{::wpi::nt::GetTopicFromHandle(m_pubHandle)}; } inline DoubleTopic DoubleEntry::GetTopic() const { - return DoubleTopic{::nt::GetTopicFromHandle(m_subHandle)}; + return DoubleTopic{::wpi::nt::GetTopicFromHandle(m_subHandle)}; } -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/generated/main/native/include/wpi/nt/FloatArrayTopic.hpp b/ntcore/src/generated/main/native/include/wpi/nt/FloatArrayTopic.hpp index aa6ddb0bc9..4ab4cc89f2 100644 --- a/ntcore/src/generated/main/native/include/wpi/nt/FloatArrayTopic.hpp +++ b/ntcore/src/generated/main/native/include/wpi/nt/FloatArrayTopic.hpp @@ -19,12 +19,12 @@ #include "wpi/nt/Topic.hpp" #include "wpi/nt/ntcore_cpp.hpp" -namespace wpi { +namespace wpi::util { template class SmallVectorImpl; } // namespace wpi -namespace nt { +namespace wpi::nt { class FloatArrayTopic; @@ -74,7 +74,7 @@ class FloatArraySubscriber : public Subscriber { * @return value */ ValueType Get(ParamType defaultValue) const { - return ::nt::GetFloatArray(m_subHandle, defaultValue); + return ::wpi::nt::GetFloatArray(m_subHandle, defaultValue); } /** @@ -84,7 +84,7 @@ class FloatArraySubscriber : public Subscriber { * @param buf storage for returned value * @return value */ - SmallRetType Get(wpi::SmallVectorImpl& buf) const { + SmallRetType Get(wpi::util::SmallVectorImpl& buf) const { return Get(buf, m_defaultValue); } @@ -96,8 +96,8 @@ class FloatArraySubscriber : public Subscriber { * @param defaultValue default value to return if no value has been published * @return value */ - SmallRetType Get(wpi::SmallVectorImpl& buf, ParamType defaultValue) const { - return nt::GetFloatArray(m_subHandle, buf, defaultValue); + SmallRetType Get(wpi::util::SmallVectorImpl& buf, ParamType defaultValue) const { + return wpi::nt::GetFloatArray(m_subHandle, buf, defaultValue); } /** @@ -120,7 +120,7 @@ class FloatArraySubscriber : public Subscriber { * @return timestamped value */ TimestampedValueType GetAtomic(ParamType defaultValue) const { - return ::nt::GetAtomicFloatArray(m_subHandle, defaultValue); + return ::wpi::nt::GetAtomicFloatArray(m_subHandle, defaultValue); } /** @@ -132,7 +132,7 @@ class FloatArraySubscriber : public Subscriber { * @return timestamped value */ TimestampedValueViewType GetAtomic( - wpi::SmallVectorImpl& buf) const { + wpi::util::SmallVectorImpl& buf) const { return GetAtomic(buf, m_defaultValue); } @@ -146,9 +146,9 @@ class FloatArraySubscriber : public Subscriber { * @return timestamped value */ TimestampedValueViewType GetAtomic( - wpi::SmallVectorImpl& buf, + wpi::util::SmallVectorImpl& buf, ParamType defaultValue) const { - return nt::GetAtomicFloatArray(m_subHandle, buf, defaultValue); + return wpi::nt::GetAtomicFloatArray(m_subHandle, buf, defaultValue); } /** @@ -162,7 +162,7 @@ class FloatArraySubscriber : public Subscriber { * been published since the previous call. */ std::vector ReadQueue() { - return ::nt::ReadQueueFloatArray(m_subHandle); + return ::wpi::nt::ReadQueueFloatArray(m_subHandle); } /** @@ -207,7 +207,7 @@ class FloatArrayPublisher : public Publisher { * @param time timestamp; 0 indicates current NT time should be used */ void Set(ParamType value, int64_t time = 0) { - ::nt::SetFloatArray(m_pubHandle, value, time); + ::wpi::nt::SetFloatArray(m_pubHandle, value, time); } /** @@ -218,7 +218,7 @@ class FloatArrayPublisher : public Publisher { * @param value value */ void SetDefault(ParamType value) { - ::nt::SetDefaultFloatArray(m_pubHandle, value); + ::wpi::nt::SetDefaultFloatArray(m_pubHandle, value); } /** @@ -286,7 +286,7 @@ class FloatArrayEntry final : public FloatArraySubscriber, * Stops publishing the entry if it's published. */ void Unpublish() { - ::nt::Unpublish(m_pubHandle); + ::wpi::nt::Unpublish(m_pubHandle); } }; @@ -341,7 +341,7 @@ class FloatArrayTopic final : public Topic { ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return FloatArraySubscriber{ - ::nt::Subscribe(m_handle, NT_FLOAT_ARRAY, "float[]", options), + ::wpi::nt::Subscribe(m_handle, NT_FLOAT_ARRAY, "float[]", options), defaultValue}; } /** @@ -365,7 +365,7 @@ class FloatArrayTopic final : public Topic { std::string_view typeString, ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return FloatArraySubscriber{ - ::nt::Subscribe(m_handle, NT_FLOAT_ARRAY, typeString, options), + ::wpi::nt::Subscribe(m_handle, NT_FLOAT_ARRAY, typeString, options), defaultValue}; } @@ -387,7 +387,7 @@ class FloatArrayTopic final : public Topic { [[nodiscard]] PublisherType Publish(const PubSubOptions& options = kDefaultPubSubOptions) { return FloatArrayPublisher{ - ::nt::Publish(m_handle, NT_FLOAT_ARRAY, "float[]", options)}; + ::wpi::nt::Publish(m_handle, NT_FLOAT_ARRAY, "float[]", options)}; } /** @@ -410,9 +410,9 @@ class FloatArrayTopic final : public Topic { */ [[nodiscard]] PublisherType PublishEx(std::string_view typeString, - const wpi::json& properties, const PubSubOptions& options = kDefaultPubSubOptions) { + const wpi::util::json& properties, const PubSubOptions& options = kDefaultPubSubOptions) { return FloatArrayPublisher{ - ::nt::PublishEx(m_handle, NT_FLOAT_ARRAY, typeString, properties, options)}; + ::wpi::nt::PublishEx(m_handle, NT_FLOAT_ARRAY, typeString, properties, options)}; } /** @@ -439,7 +439,7 @@ class FloatArrayTopic final : public Topic { EntryType GetEntry(ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return FloatArrayEntry{ - ::nt::GetEntry(m_handle, NT_FLOAT_ARRAY, "float[]", options), + ::wpi::nt::GetEntry(m_handle, NT_FLOAT_ARRAY, "float[]", options), defaultValue}; } /** @@ -467,22 +467,22 @@ class FloatArrayTopic final : public Topic { EntryType GetEntryEx(std::string_view typeString, ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return FloatArrayEntry{ - ::nt::GetEntry(m_handle, NT_FLOAT_ARRAY, typeString, options), + ::wpi::nt::GetEntry(m_handle, NT_FLOAT_ARRAY, typeString, options), defaultValue}; } }; inline FloatArrayTopic FloatArraySubscriber::GetTopic() const { - return FloatArrayTopic{::nt::GetTopicFromHandle(m_subHandle)}; + return FloatArrayTopic{::wpi::nt::GetTopicFromHandle(m_subHandle)}; } inline FloatArrayTopic FloatArrayPublisher::GetTopic() const { - return FloatArrayTopic{::nt::GetTopicFromHandle(m_pubHandle)}; + return FloatArrayTopic{::wpi::nt::GetTopicFromHandle(m_pubHandle)}; } inline FloatArrayTopic FloatArrayEntry::GetTopic() const { - return FloatArrayTopic{::nt::GetTopicFromHandle(m_subHandle)}; + return FloatArrayTopic{::wpi::nt::GetTopicFromHandle(m_subHandle)}; } -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/generated/main/native/include/wpi/nt/FloatTopic.hpp b/ntcore/src/generated/main/native/include/wpi/nt/FloatTopic.hpp index 04f73ff688..f27d8ec586 100644 --- a/ntcore/src/generated/main/native/include/wpi/nt/FloatTopic.hpp +++ b/ntcore/src/generated/main/native/include/wpi/nt/FloatTopic.hpp @@ -19,12 +19,12 @@ #include "wpi/nt/Topic.hpp" #include "wpi/nt/ntcore_cpp.hpp" -namespace wpi { +namespace wpi::util { template class SmallVectorImpl; } // namespace wpi -namespace nt { +namespace wpi::nt { class FloatTopic; @@ -70,7 +70,7 @@ class FloatSubscriber : public Subscriber { * @return value */ ValueType Get(ParamType defaultValue) const { - return ::nt::GetFloat(m_subHandle, defaultValue); + return ::wpi::nt::GetFloat(m_subHandle, defaultValue); } /** @@ -93,7 +93,7 @@ class FloatSubscriber : public Subscriber { * @return timestamped value */ TimestampedValueType GetAtomic(ParamType defaultValue) const { - return ::nt::GetAtomicFloat(m_subHandle, defaultValue); + return ::wpi::nt::GetAtomicFloat(m_subHandle, defaultValue); } /** @@ -107,7 +107,7 @@ class FloatSubscriber : public Subscriber { * been published since the previous call. */ std::vector ReadQueue() { - return ::nt::ReadQueueFloat(m_subHandle); + return ::wpi::nt::ReadQueueFloat(m_subHandle); } /** @@ -149,7 +149,7 @@ class FloatPublisher : public Publisher { * @param time timestamp; 0 indicates current NT time should be used */ void Set(ParamType value, int64_t time = 0) { - ::nt::SetFloat(m_pubHandle, value, time); + ::wpi::nt::SetFloat(m_pubHandle, value, time); } /** @@ -160,7 +160,7 @@ class FloatPublisher : public Publisher { * @param value value */ void SetDefault(ParamType value) { - ::nt::SetDefaultFloat(m_pubHandle, value); + ::wpi::nt::SetDefaultFloat(m_pubHandle, value); } /** @@ -225,7 +225,7 @@ class FloatEntry final : public FloatSubscriber, * Stops publishing the entry if it's published. */ void Unpublish() { - ::nt::Unpublish(m_pubHandle); + ::wpi::nt::Unpublish(m_pubHandle); } }; @@ -280,7 +280,7 @@ class FloatTopic final : public Topic { ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return FloatSubscriber{ - ::nt::Subscribe(m_handle, NT_FLOAT, "float", options), + ::wpi::nt::Subscribe(m_handle, NT_FLOAT, "float", options), defaultValue}; } /** @@ -304,7 +304,7 @@ class FloatTopic final : public Topic { std::string_view typeString, ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return FloatSubscriber{ - ::nt::Subscribe(m_handle, NT_FLOAT, typeString, options), + ::wpi::nt::Subscribe(m_handle, NT_FLOAT, typeString, options), defaultValue}; } @@ -326,7 +326,7 @@ class FloatTopic final : public Topic { [[nodiscard]] PublisherType Publish(const PubSubOptions& options = kDefaultPubSubOptions) { return FloatPublisher{ - ::nt::Publish(m_handle, NT_FLOAT, "float", options)}; + ::wpi::nt::Publish(m_handle, NT_FLOAT, "float", options)}; } /** @@ -349,9 +349,9 @@ class FloatTopic final : public Topic { */ [[nodiscard]] PublisherType PublishEx(std::string_view typeString, - const wpi::json& properties, const PubSubOptions& options = kDefaultPubSubOptions) { + const wpi::util::json& properties, const PubSubOptions& options = kDefaultPubSubOptions) { return FloatPublisher{ - ::nt::PublishEx(m_handle, NT_FLOAT, typeString, properties, options)}; + ::wpi::nt::PublishEx(m_handle, NT_FLOAT, typeString, properties, options)}; } /** @@ -378,7 +378,7 @@ class FloatTopic final : public Topic { EntryType GetEntry(ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return FloatEntry{ - ::nt::GetEntry(m_handle, NT_FLOAT, "float", options), + ::wpi::nt::GetEntry(m_handle, NT_FLOAT, "float", options), defaultValue}; } /** @@ -406,22 +406,22 @@ class FloatTopic final : public Topic { EntryType GetEntryEx(std::string_view typeString, ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return FloatEntry{ - ::nt::GetEntry(m_handle, NT_FLOAT, typeString, options), + ::wpi::nt::GetEntry(m_handle, NT_FLOAT, typeString, options), defaultValue}; } }; inline FloatTopic FloatSubscriber::GetTopic() const { - return FloatTopic{::nt::GetTopicFromHandle(m_subHandle)}; + return FloatTopic{::wpi::nt::GetTopicFromHandle(m_subHandle)}; } inline FloatTopic FloatPublisher::GetTopic() const { - return FloatTopic{::nt::GetTopicFromHandle(m_pubHandle)}; + return FloatTopic{::wpi::nt::GetTopicFromHandle(m_pubHandle)}; } inline FloatTopic FloatEntry::GetTopic() const { - return FloatTopic{::nt::GetTopicFromHandle(m_subHandle)}; + return FloatTopic{::wpi::nt::GetTopicFromHandle(m_subHandle)}; } -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/generated/main/native/include/wpi/nt/IntegerArrayTopic.hpp b/ntcore/src/generated/main/native/include/wpi/nt/IntegerArrayTopic.hpp index 77c4e01ecf..4c90a59e8b 100644 --- a/ntcore/src/generated/main/native/include/wpi/nt/IntegerArrayTopic.hpp +++ b/ntcore/src/generated/main/native/include/wpi/nt/IntegerArrayTopic.hpp @@ -19,12 +19,12 @@ #include "wpi/nt/Topic.hpp" #include "wpi/nt/ntcore_cpp.hpp" -namespace wpi { +namespace wpi::util { template class SmallVectorImpl; } // namespace wpi -namespace nt { +namespace wpi::nt { class IntegerArrayTopic; @@ -74,7 +74,7 @@ class IntegerArraySubscriber : public Subscriber { * @return value */ ValueType Get(ParamType defaultValue) const { - return ::nt::GetIntegerArray(m_subHandle, defaultValue); + return ::wpi::nt::GetIntegerArray(m_subHandle, defaultValue); } /** @@ -84,7 +84,7 @@ class IntegerArraySubscriber : public Subscriber { * @param buf storage for returned value * @return value */ - SmallRetType Get(wpi::SmallVectorImpl& buf) const { + SmallRetType Get(wpi::util::SmallVectorImpl& buf) const { return Get(buf, m_defaultValue); } @@ -96,8 +96,8 @@ class IntegerArraySubscriber : public Subscriber { * @param defaultValue default value to return if no value has been published * @return value */ - SmallRetType Get(wpi::SmallVectorImpl& buf, ParamType defaultValue) const { - return nt::GetIntegerArray(m_subHandle, buf, defaultValue); + SmallRetType Get(wpi::util::SmallVectorImpl& buf, ParamType defaultValue) const { + return wpi::nt::GetIntegerArray(m_subHandle, buf, defaultValue); } /** @@ -120,7 +120,7 @@ class IntegerArraySubscriber : public Subscriber { * @return timestamped value */ TimestampedValueType GetAtomic(ParamType defaultValue) const { - return ::nt::GetAtomicIntegerArray(m_subHandle, defaultValue); + return ::wpi::nt::GetAtomicIntegerArray(m_subHandle, defaultValue); } /** @@ -132,7 +132,7 @@ class IntegerArraySubscriber : public Subscriber { * @return timestamped value */ TimestampedValueViewType GetAtomic( - wpi::SmallVectorImpl& buf) const { + wpi::util::SmallVectorImpl& buf) const { return GetAtomic(buf, m_defaultValue); } @@ -146,9 +146,9 @@ class IntegerArraySubscriber : public Subscriber { * @return timestamped value */ TimestampedValueViewType GetAtomic( - wpi::SmallVectorImpl& buf, + wpi::util::SmallVectorImpl& buf, ParamType defaultValue) const { - return nt::GetAtomicIntegerArray(m_subHandle, buf, defaultValue); + return wpi::nt::GetAtomicIntegerArray(m_subHandle, buf, defaultValue); } /** @@ -162,7 +162,7 @@ class IntegerArraySubscriber : public Subscriber { * been published since the previous call. */ std::vector ReadQueue() { - return ::nt::ReadQueueIntegerArray(m_subHandle); + return ::wpi::nt::ReadQueueIntegerArray(m_subHandle); } /** @@ -207,7 +207,7 @@ class IntegerArrayPublisher : public Publisher { * @param time timestamp; 0 indicates current NT time should be used */ void Set(ParamType value, int64_t time = 0) { - ::nt::SetIntegerArray(m_pubHandle, value, time); + ::wpi::nt::SetIntegerArray(m_pubHandle, value, time); } /** @@ -218,7 +218,7 @@ class IntegerArrayPublisher : public Publisher { * @param value value */ void SetDefault(ParamType value) { - ::nt::SetDefaultIntegerArray(m_pubHandle, value); + ::wpi::nt::SetDefaultIntegerArray(m_pubHandle, value); } /** @@ -286,7 +286,7 @@ class IntegerArrayEntry final : public IntegerArraySubscriber, * Stops publishing the entry if it's published. */ void Unpublish() { - ::nt::Unpublish(m_pubHandle); + ::wpi::nt::Unpublish(m_pubHandle); } }; @@ -341,7 +341,7 @@ class IntegerArrayTopic final : public Topic { ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return IntegerArraySubscriber{ - ::nt::Subscribe(m_handle, NT_INTEGER_ARRAY, "int[]", options), + ::wpi::nt::Subscribe(m_handle, NT_INTEGER_ARRAY, "int[]", options), defaultValue}; } /** @@ -365,7 +365,7 @@ class IntegerArrayTopic final : public Topic { std::string_view typeString, ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return IntegerArraySubscriber{ - ::nt::Subscribe(m_handle, NT_INTEGER_ARRAY, typeString, options), + ::wpi::nt::Subscribe(m_handle, NT_INTEGER_ARRAY, typeString, options), defaultValue}; } @@ -387,7 +387,7 @@ class IntegerArrayTopic final : public Topic { [[nodiscard]] PublisherType Publish(const PubSubOptions& options = kDefaultPubSubOptions) { return IntegerArrayPublisher{ - ::nt::Publish(m_handle, NT_INTEGER_ARRAY, "int[]", options)}; + ::wpi::nt::Publish(m_handle, NT_INTEGER_ARRAY, "int[]", options)}; } /** @@ -410,9 +410,9 @@ class IntegerArrayTopic final : public Topic { */ [[nodiscard]] PublisherType PublishEx(std::string_view typeString, - const wpi::json& properties, const PubSubOptions& options = kDefaultPubSubOptions) { + const wpi::util::json& properties, const PubSubOptions& options = kDefaultPubSubOptions) { return IntegerArrayPublisher{ - ::nt::PublishEx(m_handle, NT_INTEGER_ARRAY, typeString, properties, options)}; + ::wpi::nt::PublishEx(m_handle, NT_INTEGER_ARRAY, typeString, properties, options)}; } /** @@ -439,7 +439,7 @@ class IntegerArrayTopic final : public Topic { EntryType GetEntry(ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return IntegerArrayEntry{ - ::nt::GetEntry(m_handle, NT_INTEGER_ARRAY, "int[]", options), + ::wpi::nt::GetEntry(m_handle, NT_INTEGER_ARRAY, "int[]", options), defaultValue}; } /** @@ -467,22 +467,22 @@ class IntegerArrayTopic final : public Topic { EntryType GetEntryEx(std::string_view typeString, ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return IntegerArrayEntry{ - ::nt::GetEntry(m_handle, NT_INTEGER_ARRAY, typeString, options), + ::wpi::nt::GetEntry(m_handle, NT_INTEGER_ARRAY, typeString, options), defaultValue}; } }; inline IntegerArrayTopic IntegerArraySubscriber::GetTopic() const { - return IntegerArrayTopic{::nt::GetTopicFromHandle(m_subHandle)}; + return IntegerArrayTopic{::wpi::nt::GetTopicFromHandle(m_subHandle)}; } inline IntegerArrayTopic IntegerArrayPublisher::GetTopic() const { - return IntegerArrayTopic{::nt::GetTopicFromHandle(m_pubHandle)}; + return IntegerArrayTopic{::wpi::nt::GetTopicFromHandle(m_pubHandle)}; } inline IntegerArrayTopic IntegerArrayEntry::GetTopic() const { - return IntegerArrayTopic{::nt::GetTopicFromHandle(m_subHandle)}; + return IntegerArrayTopic{::wpi::nt::GetTopicFromHandle(m_subHandle)}; } -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/generated/main/native/include/wpi/nt/IntegerTopic.hpp b/ntcore/src/generated/main/native/include/wpi/nt/IntegerTopic.hpp index d7efb3e81d..8954672c3f 100644 --- a/ntcore/src/generated/main/native/include/wpi/nt/IntegerTopic.hpp +++ b/ntcore/src/generated/main/native/include/wpi/nt/IntegerTopic.hpp @@ -19,12 +19,12 @@ #include "wpi/nt/Topic.hpp" #include "wpi/nt/ntcore_cpp.hpp" -namespace wpi { +namespace wpi::util { template class SmallVectorImpl; } // namespace wpi -namespace nt { +namespace wpi::nt { class IntegerTopic; @@ -70,7 +70,7 @@ class IntegerSubscriber : public Subscriber { * @return value */ ValueType Get(ParamType defaultValue) const { - return ::nt::GetInteger(m_subHandle, defaultValue); + return ::wpi::nt::GetInteger(m_subHandle, defaultValue); } /** @@ -93,7 +93,7 @@ class IntegerSubscriber : public Subscriber { * @return timestamped value */ TimestampedValueType GetAtomic(ParamType defaultValue) const { - return ::nt::GetAtomicInteger(m_subHandle, defaultValue); + return ::wpi::nt::GetAtomicInteger(m_subHandle, defaultValue); } /** @@ -107,7 +107,7 @@ class IntegerSubscriber : public Subscriber { * been published since the previous call. */ std::vector ReadQueue() { - return ::nt::ReadQueueInteger(m_subHandle); + return ::wpi::nt::ReadQueueInteger(m_subHandle); } /** @@ -149,7 +149,7 @@ class IntegerPublisher : public Publisher { * @param time timestamp; 0 indicates current NT time should be used */ void Set(ParamType value, int64_t time = 0) { - ::nt::SetInteger(m_pubHandle, value, time); + ::wpi::nt::SetInteger(m_pubHandle, value, time); } /** @@ -160,7 +160,7 @@ class IntegerPublisher : public Publisher { * @param value value */ void SetDefault(ParamType value) { - ::nt::SetDefaultInteger(m_pubHandle, value); + ::wpi::nt::SetDefaultInteger(m_pubHandle, value); } /** @@ -225,7 +225,7 @@ class IntegerEntry final : public IntegerSubscriber, * Stops publishing the entry if it's published. */ void Unpublish() { - ::nt::Unpublish(m_pubHandle); + ::wpi::nt::Unpublish(m_pubHandle); } }; @@ -280,7 +280,7 @@ class IntegerTopic final : public Topic { ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return IntegerSubscriber{ - ::nt::Subscribe(m_handle, NT_INTEGER, "int", options), + ::wpi::nt::Subscribe(m_handle, NT_INTEGER, "int", options), defaultValue}; } /** @@ -304,7 +304,7 @@ class IntegerTopic final : public Topic { std::string_view typeString, ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return IntegerSubscriber{ - ::nt::Subscribe(m_handle, NT_INTEGER, typeString, options), + ::wpi::nt::Subscribe(m_handle, NT_INTEGER, typeString, options), defaultValue}; } @@ -326,7 +326,7 @@ class IntegerTopic final : public Topic { [[nodiscard]] PublisherType Publish(const PubSubOptions& options = kDefaultPubSubOptions) { return IntegerPublisher{ - ::nt::Publish(m_handle, NT_INTEGER, "int", options)}; + ::wpi::nt::Publish(m_handle, NT_INTEGER, "int", options)}; } /** @@ -349,9 +349,9 @@ class IntegerTopic final : public Topic { */ [[nodiscard]] PublisherType PublishEx(std::string_view typeString, - const wpi::json& properties, const PubSubOptions& options = kDefaultPubSubOptions) { + const wpi::util::json& properties, const PubSubOptions& options = kDefaultPubSubOptions) { return IntegerPublisher{ - ::nt::PublishEx(m_handle, NT_INTEGER, typeString, properties, options)}; + ::wpi::nt::PublishEx(m_handle, NT_INTEGER, typeString, properties, options)}; } /** @@ -378,7 +378,7 @@ class IntegerTopic final : public Topic { EntryType GetEntry(ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return IntegerEntry{ - ::nt::GetEntry(m_handle, NT_INTEGER, "int", options), + ::wpi::nt::GetEntry(m_handle, NT_INTEGER, "int", options), defaultValue}; } /** @@ -406,22 +406,22 @@ class IntegerTopic final : public Topic { EntryType GetEntryEx(std::string_view typeString, ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return IntegerEntry{ - ::nt::GetEntry(m_handle, NT_INTEGER, typeString, options), + ::wpi::nt::GetEntry(m_handle, NT_INTEGER, typeString, options), defaultValue}; } }; inline IntegerTopic IntegerSubscriber::GetTopic() const { - return IntegerTopic{::nt::GetTopicFromHandle(m_subHandle)}; + return IntegerTopic{::wpi::nt::GetTopicFromHandle(m_subHandle)}; } inline IntegerTopic IntegerPublisher::GetTopic() const { - return IntegerTopic{::nt::GetTopicFromHandle(m_pubHandle)}; + return IntegerTopic{::wpi::nt::GetTopicFromHandle(m_pubHandle)}; } inline IntegerTopic IntegerEntry::GetTopic() const { - return IntegerTopic{::nt::GetTopicFromHandle(m_subHandle)}; + return IntegerTopic{::wpi::nt::GetTopicFromHandle(m_subHandle)}; } -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/generated/main/native/include/wpi/nt/RawTopic.hpp b/ntcore/src/generated/main/native/include/wpi/nt/RawTopic.hpp index 1c53742416..ba7e2f94d9 100644 --- a/ntcore/src/generated/main/native/include/wpi/nt/RawTopic.hpp +++ b/ntcore/src/generated/main/native/include/wpi/nt/RawTopic.hpp @@ -19,12 +19,12 @@ #include "wpi/nt/Topic.hpp" #include "wpi/nt/ntcore_cpp.hpp" -namespace wpi { +namespace wpi::util { template class SmallVectorImpl; } // namespace wpi -namespace nt { +namespace wpi::nt { class RawTopic; @@ -74,7 +74,7 @@ class RawSubscriber : public Subscriber { * @return value */ ValueType Get(ParamType defaultValue) const { - return ::nt::GetRaw(m_subHandle, defaultValue); + return ::wpi::nt::GetRaw(m_subHandle, defaultValue); } /** @@ -84,7 +84,7 @@ class RawSubscriber : public Subscriber { * @param buf storage for returned value * @return value */ - SmallRetType Get(wpi::SmallVectorImpl& buf) const { + SmallRetType Get(wpi::util::SmallVectorImpl& buf) const { return Get(buf, m_defaultValue); } @@ -96,8 +96,8 @@ class RawSubscriber : public Subscriber { * @param defaultValue default value to return if no value has been published * @return value */ - SmallRetType Get(wpi::SmallVectorImpl& buf, ParamType defaultValue) const { - return nt::GetRaw(m_subHandle, buf, defaultValue); + SmallRetType Get(wpi::util::SmallVectorImpl& buf, ParamType defaultValue) const { + return wpi::nt::GetRaw(m_subHandle, buf, defaultValue); } /** @@ -120,7 +120,7 @@ class RawSubscriber : public Subscriber { * @return timestamped value */ TimestampedValueType GetAtomic(ParamType defaultValue) const { - return ::nt::GetAtomicRaw(m_subHandle, defaultValue); + return ::wpi::nt::GetAtomicRaw(m_subHandle, defaultValue); } /** @@ -132,7 +132,7 @@ class RawSubscriber : public Subscriber { * @return timestamped value */ TimestampedValueViewType GetAtomic( - wpi::SmallVectorImpl& buf) const { + wpi::util::SmallVectorImpl& buf) const { return GetAtomic(buf, m_defaultValue); } @@ -146,9 +146,9 @@ class RawSubscriber : public Subscriber { * @return timestamped value */ TimestampedValueViewType GetAtomic( - wpi::SmallVectorImpl& buf, + wpi::util::SmallVectorImpl& buf, ParamType defaultValue) const { - return nt::GetAtomicRaw(m_subHandle, buf, defaultValue); + return wpi::nt::GetAtomicRaw(m_subHandle, buf, defaultValue); } /** @@ -162,7 +162,7 @@ class RawSubscriber : public Subscriber { * been published since the previous call. */ std::vector ReadQueue() { - return ::nt::ReadQueueRaw(m_subHandle); + return ::wpi::nt::ReadQueueRaw(m_subHandle); } /** @@ -207,7 +207,7 @@ class RawPublisher : public Publisher { * @param time timestamp; 0 indicates current NT time should be used */ void Set(ParamType value, int64_t time = 0) { - ::nt::SetRaw(m_pubHandle, value, time); + ::wpi::nt::SetRaw(m_pubHandle, value, time); } /** @@ -218,7 +218,7 @@ class RawPublisher : public Publisher { * @param value value */ void SetDefault(ParamType value) { - ::nt::SetDefaultRaw(m_pubHandle, value); + ::wpi::nt::SetDefaultRaw(m_pubHandle, value); } /** @@ -286,7 +286,7 @@ class RawEntry final : public RawSubscriber, * Stops publishing the entry if it's published. */ void Unpublish() { - ::nt::Unpublish(m_pubHandle); + ::wpi::nt::Unpublish(m_pubHandle); } }; @@ -341,7 +341,7 @@ class RawTopic final : public Topic { std::string_view typeString, ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return RawSubscriber{ - ::nt::Subscribe(m_handle, NT_RAW, typeString, options), + ::wpi::nt::Subscribe(m_handle, NT_RAW, typeString, options), defaultValue}; } /** @@ -364,7 +364,7 @@ class RawTopic final : public Topic { [[nodiscard]] PublisherType Publish(std::string_view typeString, const PubSubOptions& options = kDefaultPubSubOptions) { return RawPublisher{ - ::nt::Publish(m_handle, NT_RAW, typeString, options)}; + ::wpi::nt::Publish(m_handle, NT_RAW, typeString, options)}; } /** @@ -387,9 +387,9 @@ class RawTopic final : public Topic { */ [[nodiscard]] PublisherType PublishEx(std::string_view typeString, - const wpi::json& properties, const PubSubOptions& options = kDefaultPubSubOptions) { + const wpi::util::json& properties, const PubSubOptions& options = kDefaultPubSubOptions) { return RawPublisher{ - ::nt::PublishEx(m_handle, NT_RAW, typeString, properties, options)}; + ::wpi::nt::PublishEx(m_handle, NT_RAW, typeString, properties, options)}; } /** @@ -418,21 +418,21 @@ class RawTopic final : public Topic { EntryType GetEntry(std::string_view typeString, ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return RawEntry{ - ::nt::GetEntry(m_handle, NT_RAW, typeString, options), + ::wpi::nt::GetEntry(m_handle, NT_RAW, typeString, options), defaultValue}; } }; inline RawTopic RawSubscriber::GetTopic() const { - return RawTopic{::nt::GetTopicFromHandle(m_subHandle)}; + return RawTopic{::wpi::nt::GetTopicFromHandle(m_subHandle)}; } inline RawTopic RawPublisher::GetTopic() const { - return RawTopic{::nt::GetTopicFromHandle(m_pubHandle)}; + return RawTopic{::wpi::nt::GetTopicFromHandle(m_pubHandle)}; } inline RawTopic RawEntry::GetTopic() const { - return RawTopic{::nt::GetTopicFromHandle(m_subHandle)}; + return RawTopic{::wpi::nt::GetTopicFromHandle(m_subHandle)}; } -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/generated/main/native/include/wpi/nt/StringArrayTopic.hpp b/ntcore/src/generated/main/native/include/wpi/nt/StringArrayTopic.hpp index f6b62e68a2..287d4f8b9b 100644 --- a/ntcore/src/generated/main/native/include/wpi/nt/StringArrayTopic.hpp +++ b/ntcore/src/generated/main/native/include/wpi/nt/StringArrayTopic.hpp @@ -19,12 +19,12 @@ #include "wpi/nt/Topic.hpp" #include "wpi/nt/ntcore_cpp.hpp" -namespace wpi { +namespace wpi::util { template class SmallVectorImpl; } // namespace wpi -namespace nt { +namespace wpi::nt { class StringArrayTopic; @@ -70,7 +70,7 @@ class StringArraySubscriber : public Subscriber { * @return value */ ValueType Get(ParamType defaultValue) const { - return ::nt::GetStringArray(m_subHandle, defaultValue); + return ::wpi::nt::GetStringArray(m_subHandle, defaultValue); } /** @@ -93,7 +93,7 @@ class StringArraySubscriber : public Subscriber { * @return timestamped value */ TimestampedValueType GetAtomic(ParamType defaultValue) const { - return ::nt::GetAtomicStringArray(m_subHandle, defaultValue); + return ::wpi::nt::GetAtomicStringArray(m_subHandle, defaultValue); } /** @@ -107,7 +107,7 @@ class StringArraySubscriber : public Subscriber { * been published since the previous call. */ std::vector ReadQueue() { - return ::nt::ReadQueueStringArray(m_subHandle); + return ::wpi::nt::ReadQueueStringArray(m_subHandle); } /** @@ -149,7 +149,7 @@ class StringArrayPublisher : public Publisher { * @param time timestamp; 0 indicates current NT time should be used */ void Set(ParamType value, int64_t time = 0) { - ::nt::SetStringArray(m_pubHandle, value, time); + ::wpi::nt::SetStringArray(m_pubHandle, value, time); } /** @@ -160,7 +160,7 @@ class StringArrayPublisher : public Publisher { * @param value value */ void SetDefault(ParamType value) { - ::nt::SetDefaultStringArray(m_pubHandle, value); + ::wpi::nt::SetDefaultStringArray(m_pubHandle, value); } /** @@ -225,7 +225,7 @@ class StringArrayEntry final : public StringArraySubscriber, * Stops publishing the entry if it's published. */ void Unpublish() { - ::nt::Unpublish(m_pubHandle); + ::wpi::nt::Unpublish(m_pubHandle); } }; @@ -280,7 +280,7 @@ class StringArrayTopic final : public Topic { ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return StringArraySubscriber{ - ::nt::Subscribe(m_handle, NT_STRING_ARRAY, "string[]", options), + ::wpi::nt::Subscribe(m_handle, NT_STRING_ARRAY, "string[]", options), defaultValue}; } /** @@ -304,7 +304,7 @@ class StringArrayTopic final : public Topic { std::string_view typeString, ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return StringArraySubscriber{ - ::nt::Subscribe(m_handle, NT_STRING_ARRAY, typeString, options), + ::wpi::nt::Subscribe(m_handle, NT_STRING_ARRAY, typeString, options), defaultValue}; } @@ -326,7 +326,7 @@ class StringArrayTopic final : public Topic { [[nodiscard]] PublisherType Publish(const PubSubOptions& options = kDefaultPubSubOptions) { return StringArrayPublisher{ - ::nt::Publish(m_handle, NT_STRING_ARRAY, "string[]", options)}; + ::wpi::nt::Publish(m_handle, NT_STRING_ARRAY, "string[]", options)}; } /** @@ -349,9 +349,9 @@ class StringArrayTopic final : public Topic { */ [[nodiscard]] PublisherType PublishEx(std::string_view typeString, - const wpi::json& properties, const PubSubOptions& options = kDefaultPubSubOptions) { + const wpi::util::json& properties, const PubSubOptions& options = kDefaultPubSubOptions) { return StringArrayPublisher{ - ::nt::PublishEx(m_handle, NT_STRING_ARRAY, typeString, properties, options)}; + ::wpi::nt::PublishEx(m_handle, NT_STRING_ARRAY, typeString, properties, options)}; } /** @@ -378,7 +378,7 @@ class StringArrayTopic final : public Topic { EntryType GetEntry(ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return StringArrayEntry{ - ::nt::GetEntry(m_handle, NT_STRING_ARRAY, "string[]", options), + ::wpi::nt::GetEntry(m_handle, NT_STRING_ARRAY, "string[]", options), defaultValue}; } /** @@ -406,22 +406,22 @@ class StringArrayTopic final : public Topic { EntryType GetEntryEx(std::string_view typeString, ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return StringArrayEntry{ - ::nt::GetEntry(m_handle, NT_STRING_ARRAY, typeString, options), + ::wpi::nt::GetEntry(m_handle, NT_STRING_ARRAY, typeString, options), defaultValue}; } }; inline StringArrayTopic StringArraySubscriber::GetTopic() const { - return StringArrayTopic{::nt::GetTopicFromHandle(m_subHandle)}; + return StringArrayTopic{::wpi::nt::GetTopicFromHandle(m_subHandle)}; } inline StringArrayTopic StringArrayPublisher::GetTopic() const { - return StringArrayTopic{::nt::GetTopicFromHandle(m_pubHandle)}; + return StringArrayTopic{::wpi::nt::GetTopicFromHandle(m_pubHandle)}; } inline StringArrayTopic StringArrayEntry::GetTopic() const { - return StringArrayTopic{::nt::GetTopicFromHandle(m_subHandle)}; + return StringArrayTopic{::wpi::nt::GetTopicFromHandle(m_subHandle)}; } -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/generated/main/native/include/wpi/nt/StringTopic.hpp b/ntcore/src/generated/main/native/include/wpi/nt/StringTopic.hpp index cdf930e3a7..7d34a5c520 100644 --- a/ntcore/src/generated/main/native/include/wpi/nt/StringTopic.hpp +++ b/ntcore/src/generated/main/native/include/wpi/nt/StringTopic.hpp @@ -21,12 +21,12 @@ #include "wpi/nt/Topic.hpp" #include "wpi/nt/ntcore_cpp.hpp" -namespace wpi { +namespace wpi::util { template class SmallVectorImpl; } // namespace wpi -namespace nt { +namespace wpi::nt { class StringTopic; @@ -76,7 +76,7 @@ class StringSubscriber : public Subscriber { * @return value */ ValueType Get(ParamType defaultValue) const { - return ::nt::GetString(m_subHandle, defaultValue); + return ::wpi::nt::GetString(m_subHandle, defaultValue); } /** @@ -86,7 +86,7 @@ class StringSubscriber : public Subscriber { * @param buf storage for returned value * @return value */ - SmallRetType Get(wpi::SmallVectorImpl& buf) const { + SmallRetType Get(wpi::util::SmallVectorImpl& buf) const { return Get(buf, m_defaultValue); } @@ -98,8 +98,8 @@ class StringSubscriber : public Subscriber { * @param defaultValue default value to return if no value has been published * @return value */ - SmallRetType Get(wpi::SmallVectorImpl& buf, ParamType defaultValue) const { - return nt::GetString(m_subHandle, buf, defaultValue); + SmallRetType Get(wpi::util::SmallVectorImpl& buf, ParamType defaultValue) const { + return wpi::nt::GetString(m_subHandle, buf, defaultValue); } /** @@ -122,7 +122,7 @@ class StringSubscriber : public Subscriber { * @return timestamped value */ TimestampedValueType GetAtomic(ParamType defaultValue) const { - return ::nt::GetAtomicString(m_subHandle, defaultValue); + return ::wpi::nt::GetAtomicString(m_subHandle, defaultValue); } /** @@ -134,7 +134,7 @@ class StringSubscriber : public Subscriber { * @return timestamped value */ TimestampedValueViewType GetAtomic( - wpi::SmallVectorImpl& buf) const { + wpi::util::SmallVectorImpl& buf) const { return GetAtomic(buf, m_defaultValue); } @@ -148,9 +148,9 @@ class StringSubscriber : public Subscriber { * @return timestamped value */ TimestampedValueViewType GetAtomic( - wpi::SmallVectorImpl& buf, + wpi::util::SmallVectorImpl& buf, ParamType defaultValue) const { - return nt::GetAtomicString(m_subHandle, buf, defaultValue); + return wpi::nt::GetAtomicString(m_subHandle, buf, defaultValue); } /** @@ -164,7 +164,7 @@ class StringSubscriber : public Subscriber { * been published since the previous call. */ std::vector ReadQueue() { - return ::nt::ReadQueueString(m_subHandle); + return ::wpi::nt::ReadQueueString(m_subHandle); } /** @@ -209,7 +209,7 @@ class StringPublisher : public Publisher { * @param time timestamp; 0 indicates current NT time should be used */ void Set(ParamType value, int64_t time = 0) { - ::nt::SetString(m_pubHandle, value, time); + ::wpi::nt::SetString(m_pubHandle, value, time); } /** @@ -220,7 +220,7 @@ class StringPublisher : public Publisher { * @param value value */ void SetDefault(ParamType value) { - ::nt::SetDefaultString(m_pubHandle, value); + ::wpi::nt::SetDefaultString(m_pubHandle, value); } /** @@ -288,7 +288,7 @@ class StringEntry final : public StringSubscriber, * Stops publishing the entry if it's published. */ void Unpublish() { - ::nt::Unpublish(m_pubHandle); + ::wpi::nt::Unpublish(m_pubHandle); } }; @@ -343,7 +343,7 @@ class StringTopic final : public Topic { ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return StringSubscriber{ - ::nt::Subscribe(m_handle, NT_STRING, "string", options), + ::wpi::nt::Subscribe(m_handle, NT_STRING, "string", options), defaultValue}; } /** @@ -367,7 +367,7 @@ class StringTopic final : public Topic { std::string_view typeString, ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return StringSubscriber{ - ::nt::Subscribe(m_handle, NT_STRING, typeString, options), + ::wpi::nt::Subscribe(m_handle, NT_STRING, typeString, options), defaultValue}; } @@ -389,7 +389,7 @@ class StringTopic final : public Topic { [[nodiscard]] PublisherType Publish(const PubSubOptions& options = kDefaultPubSubOptions) { return StringPublisher{ - ::nt::Publish(m_handle, NT_STRING, "string", options)}; + ::wpi::nt::Publish(m_handle, NT_STRING, "string", options)}; } /** @@ -412,9 +412,9 @@ class StringTopic final : public Topic { */ [[nodiscard]] PublisherType PublishEx(std::string_view typeString, - const wpi::json& properties, const PubSubOptions& options = kDefaultPubSubOptions) { + const wpi::util::json& properties, const PubSubOptions& options = kDefaultPubSubOptions) { return StringPublisher{ - ::nt::PublishEx(m_handle, NT_STRING, typeString, properties, options)}; + ::wpi::nt::PublishEx(m_handle, NT_STRING, typeString, properties, options)}; } /** @@ -441,7 +441,7 @@ class StringTopic final : public Topic { EntryType GetEntry(ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return StringEntry{ - ::nt::GetEntry(m_handle, NT_STRING, "string", options), + ::wpi::nt::GetEntry(m_handle, NT_STRING, "string", options), defaultValue}; } /** @@ -469,22 +469,22 @@ class StringTopic final : public Topic { EntryType GetEntryEx(std::string_view typeString, ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return StringEntry{ - ::nt::GetEntry(m_handle, NT_STRING, typeString, options), + ::wpi::nt::GetEntry(m_handle, NT_STRING, typeString, options), defaultValue}; } }; inline StringTopic StringSubscriber::GetTopic() const { - return StringTopic{::nt::GetTopicFromHandle(m_subHandle)}; + return StringTopic{::wpi::nt::GetTopicFromHandle(m_subHandle)}; } inline StringTopic StringPublisher::GetTopic() const { - return StringTopic{::nt::GetTopicFromHandle(m_pubHandle)}; + return StringTopic{::wpi::nt::GetTopicFromHandle(m_pubHandle)}; } inline StringTopic StringEntry::GetTopic() const { - return StringTopic{::nt::GetTopicFromHandle(m_subHandle)}; + return StringTopic{::wpi::nt::GetTopicFromHandle(m_subHandle)}; } -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/generated/main/native/include/wpi/nt/ntcore_cpp_types.hpp b/ntcore/src/generated/main/native/include/wpi/nt/ntcore_cpp_types.hpp index 5ae1297edb..f430892b90 100644 --- a/ntcore/src/generated/main/native/include/wpi/nt/ntcore_cpp_types.hpp +++ b/ntcore/src/generated/main/native/include/wpi/nt/ntcore_cpp_types.hpp @@ -16,12 +16,12 @@ #include "wpi/nt/ntcore_c.h" -namespace wpi { +namespace wpi::util { template class SmallVectorImpl; } // namespace wpi -namespace nt { +namespace wpi::nt { /** * Timestamped value. * @ingroup ntcore_cpp_handle_api @@ -371,7 +371,7 @@ std::vector ReadQueueValuesDouble(NT_Handle subentry); using TimestampedString = Timestamped; /** - * Timestamped String view (for SmallVector-taking functions). + * Timestamped String view (for wpi::util::SmallVector-taking functions). * @ingroup ntcore_cpp_handle_api */ using TimestampedStringView = Timestamped; @@ -447,11 +447,11 @@ std::vector ReadQueueString(NT_Handle subentry); */ std::vector ReadQueueValuesString(NT_Handle subentry); -std::string_view GetString(NT_Handle subentry, wpi::SmallVectorImpl& buf, std::string_view defaultValue); +std::string_view GetString(NT_Handle subentry, wpi::util::SmallVectorImpl& buf, std::string_view defaultValue); TimestampedStringView GetAtomicString( NT_Handle subentry, - wpi::SmallVectorImpl& buf, + wpi::util::SmallVectorImpl& buf, std::string_view defaultValue); /** @} */ @@ -463,7 +463,7 @@ TimestampedStringView GetAtomicString( using TimestampedRaw = Timestamped>; /** - * Timestamped Raw view (for SmallVector-taking functions). + * Timestamped Raw view (for wpi::util::SmallVector-taking functions). * @ingroup ntcore_cpp_handle_api */ using TimestampedRawView = Timestamped>; @@ -539,11 +539,11 @@ std::vector ReadQueueRaw(NT_Handle subentry); */ std::vector> ReadQueueValuesRaw(NT_Handle subentry); -std::span GetRaw(NT_Handle subentry, wpi::SmallVectorImpl& buf, std::span defaultValue); +std::span GetRaw(NT_Handle subentry, wpi::util::SmallVectorImpl& buf, std::span defaultValue); TimestampedRawView GetAtomicRaw( NT_Handle subentry, - wpi::SmallVectorImpl& buf, + wpi::util::SmallVectorImpl& buf, std::span defaultValue); /** @} */ @@ -555,7 +555,7 @@ TimestampedRawView GetAtomicRaw( using TimestampedBooleanArray = Timestamped>; /** - * Timestamped BooleanArray view (for SmallVector-taking functions). + * Timestamped BooleanArray view (for wpi::util::SmallVector-taking functions). * @ingroup ntcore_cpp_handle_api */ using TimestampedBooleanArrayView = Timestamped>; @@ -631,11 +631,11 @@ std::vector ReadQueueBooleanArray(NT_Handle subentry); */ std::vector> ReadQueueValuesBooleanArray(NT_Handle subentry); -std::span GetBooleanArray(NT_Handle subentry, wpi::SmallVectorImpl& buf, std::span defaultValue); +std::span GetBooleanArray(NT_Handle subentry, wpi::util::SmallVectorImpl& buf, std::span defaultValue); TimestampedBooleanArrayView GetAtomicBooleanArray( NT_Handle subentry, - wpi::SmallVectorImpl& buf, + wpi::util::SmallVectorImpl& buf, std::span defaultValue); /** @} */ @@ -647,7 +647,7 @@ TimestampedBooleanArrayView GetAtomicBooleanArray( using TimestampedIntegerArray = Timestamped>; /** - * Timestamped IntegerArray view (for SmallVector-taking functions). + * Timestamped IntegerArray view (for wpi::util::SmallVector-taking functions). * @ingroup ntcore_cpp_handle_api */ using TimestampedIntegerArrayView = Timestamped>; @@ -723,11 +723,11 @@ std::vector ReadQueueIntegerArray(NT_Handle subentry); */ std::vector> ReadQueueValuesIntegerArray(NT_Handle subentry); -std::span GetIntegerArray(NT_Handle subentry, wpi::SmallVectorImpl& buf, std::span defaultValue); +std::span GetIntegerArray(NT_Handle subentry, wpi::util::SmallVectorImpl& buf, std::span defaultValue); TimestampedIntegerArrayView GetAtomicIntegerArray( NT_Handle subentry, - wpi::SmallVectorImpl& buf, + wpi::util::SmallVectorImpl& buf, std::span defaultValue); /** @} */ @@ -739,7 +739,7 @@ TimestampedIntegerArrayView GetAtomicIntegerArray( using TimestampedFloatArray = Timestamped>; /** - * Timestamped FloatArray view (for SmallVector-taking functions). + * Timestamped FloatArray view (for wpi::util::SmallVector-taking functions). * @ingroup ntcore_cpp_handle_api */ using TimestampedFloatArrayView = Timestamped>; @@ -815,11 +815,11 @@ std::vector ReadQueueFloatArray(NT_Handle subentry); */ std::vector> ReadQueueValuesFloatArray(NT_Handle subentry); -std::span GetFloatArray(NT_Handle subentry, wpi::SmallVectorImpl& buf, std::span defaultValue); +std::span GetFloatArray(NT_Handle subentry, wpi::util::SmallVectorImpl& buf, std::span defaultValue); TimestampedFloatArrayView GetAtomicFloatArray( NT_Handle subentry, - wpi::SmallVectorImpl& buf, + wpi::util::SmallVectorImpl& buf, std::span defaultValue); /** @} */ @@ -831,7 +831,7 @@ TimestampedFloatArrayView GetAtomicFloatArray( using TimestampedDoubleArray = Timestamped>; /** - * Timestamped DoubleArray view (for SmallVector-taking functions). + * Timestamped DoubleArray view (for wpi::util::SmallVector-taking functions). * @ingroup ntcore_cpp_handle_api */ using TimestampedDoubleArrayView = Timestamped>; @@ -907,11 +907,11 @@ std::vector ReadQueueDoubleArray(NT_Handle subentry); */ std::vector> ReadQueueValuesDoubleArray(NT_Handle subentry); -std::span GetDoubleArray(NT_Handle subentry, wpi::SmallVectorImpl& buf, std::span defaultValue); +std::span GetDoubleArray(NT_Handle subentry, wpi::util::SmallVectorImpl& buf, std::span defaultValue); TimestampedDoubleArrayView GetAtomicDoubleArray( NT_Handle subentry, - wpi::SmallVectorImpl& buf, + wpi::util::SmallVectorImpl& buf, std::span defaultValue); /** @} */ @@ -995,4 +995,4 @@ std::vector> ReadQueueValuesStringArray(NT_Handle suben /** @} */ -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/main/native/cpp/ConnectionList.cpp b/ntcore/src/main/native/cpp/ConnectionList.cpp index 1676ee1c90..20ed596b63 100644 --- a/ntcore/src/main/native/cpp/ConnectionList.cpp +++ b/ntcore/src/main/native/cpp/ConnectionList.cpp @@ -14,12 +14,12 @@ #include "wpi/util/json.hpp" #include "wpi/util/raw_ostream.hpp" -using namespace nt; +using namespace wpi::nt; static std::string ConnInfoToJson(bool connected, const ConnectionInfo& info) { std::string str; - wpi::raw_string_ostream os{str}; - wpi::json::serializer s{os, ' ', 0}; + wpi::util::raw_string_ostream os{str}; + wpi::util::json::serializer s{os, ' ', 0}; os << "{\"connected\":" << (connected ? "true" : "false"); os << ",\"remote_id\":\""; s.dump_escaped(info.remote_id, false); @@ -99,7 +99,7 @@ void ConnectionList::AddListener(NT_Listener listener, unsigned int eventMask) { if ((eventMask & (NT_EVENT_CONNECTED | NT_EVENT_IMMEDIATE)) == (NT_EVENT_CONNECTED | NT_EVENT_IMMEDIATE) && !m_connections.empty()) { - wpi::SmallVector infos; + wpi::util::SmallVector infos; infos.reserve(m_connections.size()); for (auto&& conn : m_connections) { infos.emplace_back(&(*conn)); diff --git a/ntcore/src/main/native/cpp/ConnectionList.hpp b/ntcore/src/main/native/cpp/ConnectionList.hpp index edf4ef0c3e..916619c8db 100644 --- a/ntcore/src/main/native/cpp/ConnectionList.hpp +++ b/ntcore/src/main/native/cpp/ConnectionList.hpp @@ -21,7 +21,7 @@ #include "wpi/util/UidVector.hpp" #include "wpi/util/mutex.hpp" -namespace nt { +namespace wpi::nt { class IListenerStorage; @@ -48,11 +48,11 @@ class ConnectionList final : public IConnectionList { private: int m_inst; IListenerStorage& m_listenerStorage; - mutable wpi::mutex m_mutex; + mutable wpi::util::mutex m_mutex; // shared with user (must be atomic or mutex-protected) std::atomic_bool m_connected{false}; - wpi::UidVector, 8> m_connections; + wpi::util::UidVector, 8> m_connections; struct DataLoggerData { static constexpr auto kType = Handle::kConnectionDataLogger; @@ -70,4 +70,4 @@ class ConnectionList final : public IConnectionList { HandleMap m_dataloggers; }; -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/main/native/cpp/Handle.hpp b/ntcore/src/main/native/cpp/Handle.hpp index e29a9a627f..455cdd58c6 100644 --- a/ntcore/src/main/native/cpp/Handle.hpp +++ b/ntcore/src/main/native/cpp/Handle.hpp @@ -7,7 +7,7 @@ #include "wpi/nt/ntcore_c.h" #include "wpi/util/Synchronization.h" -namespace nt { +namespace wpi::nt { // Handle data layout: // Bits 30-24: Type @@ -17,7 +17,7 @@ namespace nt { class Handle { public: enum Type { - kListener = wpi::kHandleTypeNTBase, + kListener = wpi::util::kHandleTypeNTBase, kListenerPoller, kEntry, kInstance, @@ -29,7 +29,7 @@ class Handle { kPublisher, kTypeMax }; - static_assert(kTypeMax <= wpi::kHandleTypeHALBase); + static_assert(kTypeMax <= wpi::util::kHandleTypeHALBase); enum { kIndexMax = 0xfffff }; constexpr explicit Handle(NT_Handle handle) : m_handle(handle) {} @@ -67,4 +67,4 @@ class Handle { NT_Handle m_handle; }; -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/main/native/cpp/HandleMap.hpp b/ntcore/src/main/native/cpp/HandleMap.hpp index 22f4354513..9d9d1ca3ae 100644 --- a/ntcore/src/main/native/cpp/HandleMap.hpp +++ b/ntcore/src/main/native/cpp/HandleMap.hpp @@ -11,7 +11,7 @@ #include "Handle.hpp" #include "wpi/util/UidVector.hpp" -namespace nt { +namespace wpi::nt { template concept HandleType = requires { @@ -20,7 +20,7 @@ concept HandleType = requires { // Utility wrapper class for our UidVectors template -class HandleMap : public wpi::UidVector, Size> { +class HandleMap : public wpi::util::UidVector, Size> { public: template T* Add(int inst, Args&&... args) { @@ -56,4 +56,4 @@ class HandleMap : public wpi::UidVector, Size> { } }; -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/main/native/cpp/IConnectionList.hpp b/ntcore/src/main/native/cpp/IConnectionList.hpp index bd593c8cbd..302056f3de 100644 --- a/ntcore/src/main/native/cpp/IConnectionList.hpp +++ b/ntcore/src/main/native/cpp/IConnectionList.hpp @@ -8,7 +8,7 @@ #include "wpi/nt/ntcore_cpp.hpp" -namespace nt { +namespace wpi::nt { class IConnectionList { public: @@ -21,4 +21,4 @@ class IConnectionList { virtual bool IsConnected() const = 0; }; -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/main/native/cpp/IListenerStorage.hpp b/ntcore/src/main/native/cpp/IListenerStorage.hpp index ec69d2323d..77e3425973 100644 --- a/ntcore/src/main/native/cpp/IListenerStorage.hpp +++ b/ntcore/src/main/native/cpp/IListenerStorage.hpp @@ -11,7 +11,7 @@ #include "wpi/nt/ntcore_cpp.hpp" -namespace nt { +namespace wpi::nt { class IListenerStorage { public: @@ -49,4 +49,4 @@ class IListenerStorage { } }; -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/main/native/cpp/INetworkClient.hpp b/ntcore/src/main/native/cpp/INetworkClient.hpp index 2a49584489..7c3c8c373a 100644 --- a/ntcore/src/main/native/cpp/INetworkClient.hpp +++ b/ntcore/src/main/native/cpp/INetworkClient.hpp @@ -10,7 +10,7 @@ #include "wpi/nt/ntcore_cpp.hpp" -namespace nt { +namespace wpi::nt { class INetworkClient { public: @@ -27,4 +27,4 @@ class INetworkClient { virtual void Flush() = 0; }; -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/main/native/cpp/InstanceImpl.cpp b/ntcore/src/main/native/cpp/InstanceImpl.cpp index 12dadaf891..7c217954a7 100644 --- a/ntcore/src/main/native/cpp/InstanceImpl.cpp +++ b/ntcore/src/main/native/cpp/InstanceImpl.cpp @@ -8,11 +8,11 @@ #include #include -using namespace nt; +using namespace wpi::nt; std::atomic InstanceImpl::s_default{-1}; std::atomic InstanceImpl::s_instances[kNumInstances]; -wpi::mutex InstanceImpl::s_mutex; +wpi::util::mutex InstanceImpl::s_mutex; InstanceImpl::Cleanup InstanceImpl::s_cleanup; using namespace std::placeholders; diff --git a/ntcore/src/main/native/cpp/InstanceImpl.hpp b/ntcore/src/main/native/cpp/InstanceImpl.hpp index 7dcfb9cae4..61ae8731b1 100644 --- a/ntcore/src/main/native/cpp/InstanceImpl.hpp +++ b/ntcore/src/main/native/cpp/InstanceImpl.hpp @@ -22,7 +22,7 @@ #include "NetworkServer.hpp" #include "wpi/util/mutex.hpp" -namespace nt { +namespace wpi::nt { class InstanceImpl { public: @@ -61,7 +61,7 @@ class InstanceImpl { ListenerStorage listenerStorage; LoggerImpl logger_impl; - wpi::Logger logger; + wpi::util::Logger logger; ConnectionList connectionList; LocalStorage localStorage; std::atomic networkMode{NT_NET_MODE_NONE}; @@ -72,7 +72,7 @@ class InstanceImpl { static std::atomic s_default; static constexpr int kNumInstances = 16; static std::atomic s_instances[kNumInstances]; - static wpi::mutex s_mutex; + static wpi::util::mutex s_mutex; struct Cleanup { ~Cleanup() { @@ -87,7 +87,7 @@ class InstanceImpl { }; static Cleanup s_cleanup; - wpi::mutex m_mutex; + wpi::util::mutex m_mutex; std::shared_ptr m_networkServer; std::shared_ptr m_networkClient; std::vector> m_servers; @@ -96,4 +96,4 @@ class InstanceImpl { int m_inst; }; -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/main/native/cpp/ListenerStorage.cpp b/ntcore/src/main/native/cpp/ListenerStorage.cpp index 76d92f6d0c..662780da3b 100644 --- a/ntcore/src/main/native/cpp/ListenerStorage.cpp +++ b/ntcore/src/main/native/cpp/ListenerStorage.cpp @@ -11,19 +11,19 @@ #include "wpi/nt/ntcore_c.h" #include "wpi/util/SmallVector.hpp" -using namespace nt; +using namespace wpi::nt; void ListenerStorage::Thread::Main() { while (m_active) { WPI_Handle signaledBuf[3]; - auto signaled = wpi::WaitForObjects( + auto signaled = wpi::util::WaitForObjects( {m_poller, m_stopEvent.GetHandle(), m_waitQueueWakeup.GetHandle()}, signaledBuf); if (signaled.empty() || !m_active) { return; } // call all the way back out to the C++ API to ensure valid handle - auto events = nt::ReadListenerQueue(m_poller); + auto events = wpi::nt::ReadListenerQueue(m_poller); if (!events.empty()) { std::unique_lock lock{m_mutex}; for (auto&& event : events) { @@ -299,7 +299,7 @@ ListenerStorage::DestroyListenerPoller(NT_ListenerPoller pollerHandle) { std::scoped_lock lock{m_mutex}; if (auto poller = m_pollers.Remove(pollerHandle)) { // ensure all listeners that use this poller are removed - wpi::SmallVector toRemove; + wpi::util::SmallVector toRemove; for (auto&& listener : m_listeners) { if (listener->poller == poller.get()) { toRemove.emplace_back(listener->handle); @@ -341,7 +341,7 @@ bool ListenerStorage::WaitForListenerQueue(double timeout) { } } bool timedOut; - wpi::WaitForObject(h, timeout, &timedOut); + wpi::util::WaitForObject(h, timeout, &timedOut); return !timedOut; } diff --git a/ntcore/src/main/native/cpp/ListenerStorage.hpp b/ntcore/src/main/native/cpp/ListenerStorage.hpp index 458f99a5e9..d62aa3f59e 100644 --- a/ntcore/src/main/native/cpp/ListenerStorage.hpp +++ b/ntcore/src/main/native/cpp/ListenerStorage.hpp @@ -22,7 +22,7 @@ #include "wpi/util/Synchronization.h" #include "wpi/util/mutex.hpp" -namespace nt { +namespace wpi::nt { class ListenerStorage final : public IListenerStorage { public: @@ -72,14 +72,14 @@ class ListenerStorage final : public IListenerStorage { std::span handles); int m_inst; - mutable wpi::mutex m_mutex; + mutable wpi::util::mutex m_mutex; struct PollerData { static constexpr auto kType = Handle::kListenerPoller; explicit PollerData(NT_ListenerPoller handle) : handle{handle} {} - wpi::SignalObject handle; + wpi::util::SignalObject handle; std::vector queue; }; HandleMap m_pollers; @@ -90,9 +90,9 @@ class ListenerStorage final : public IListenerStorage { ListenerData(NT_Listener handle, PollerData* poller) : handle{handle}, poller{poller} {} - wpi::SignalObject handle; + wpi::util::SignalObject handle; PollerData* poller; - wpi::SmallVector, 2> sources; + wpi::util::SmallVector, 2> sources; unsigned int eventMask{0}; }; HandleMap m_listeners; @@ -103,18 +103,18 @@ class ListenerStorage final : public IListenerStorage { VectorSet m_logListeners; VectorSet m_timeSyncListeners; - class Thread final : public wpi::SafeThreadEvent { + class Thread final : public wpi::util::SafeThreadEvent { public: explicit Thread(NT_ListenerPoller poller) : m_poller{poller} {} void Main() final; NT_ListenerPoller m_poller; - wpi::DenseMap m_callbacks; - wpi::Event m_waitQueueWakeup; - wpi::Event m_waitQueueWaiter; + wpi::util::DenseMap m_callbacks; + wpi::util::Event m_waitQueueWakeup; + wpi::util::Event m_waitQueueWaiter; }; - wpi::SafeThreadOwner m_thread; + wpi::util::SafeThreadOwner m_thread; }; -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/main/native/cpp/LocalStorage.cpp b/ntcore/src/main/native/cpp/LocalStorage.cpp index ddac1f5073..f958294e0a 100644 --- a/ntcore/src/main/native/cpp/LocalStorage.cpp +++ b/ntcore/src/main/native/cpp/LocalStorage.cpp @@ -6,7 +6,7 @@ #include -using namespace nt; +using namespace wpi::nt; std::vector LocalStorage::GetTopics(std::string_view prefix, unsigned int types) { diff --git a/ntcore/src/main/native/cpp/LocalStorage.hpp b/ntcore/src/main/native/cpp/LocalStorage.hpp index 696e700705..29e6e078e1 100644 --- a/ntcore/src/main/native/cpp/LocalStorage.hpp +++ b/ntcore/src/main/native/cpp/LocalStorage.hpp @@ -21,24 +21,24 @@ #include "wpi/util/json.hpp" #include "wpi/util/mutex.hpp" -namespace wpi { +namespace wpi::util { class Logger; } // namespace wpi -namespace nt { +namespace wpi::nt { class IListenerStorage; class LocalStorage final : public net::ILocalStorage { public: - LocalStorage(int inst, IListenerStorage& listenerStorage, wpi::Logger& logger) + LocalStorage(int inst, IListenerStorage& listenerStorage, wpi::util::Logger& logger) : m_impl{inst, listenerStorage, logger} {} LocalStorage(const LocalStorage&) = delete; LocalStorage& operator=(const LocalStorage&) = delete; // network interface functions int ServerAnnounce(std::string_view name, int id, std::string_view typeStr, - const wpi::json& properties, + const wpi::util::json& properties, std::optional pubuid) final { std::scoped_lock lock{m_mutex}; auto topic = m_impl.GetOrCreateTopic(name); @@ -51,7 +51,7 @@ class LocalStorage final : public net::ILocalStorage { m_impl.RemoveNetworkPublisher(m_impl.GetOrCreateTopic(name)); } - void ServerPropertiesUpdate(std::string_view name, const wpi::json& update, + void ServerPropertiesUpdate(std::string_view name, const wpi::util::json& update, bool ack) final { std::scoped_lock lock{m_mutex}; if (auto topic = m_impl.GetTopicByName(name)) { @@ -177,17 +177,17 @@ class LocalStorage final : public net::ILocalStorage { return topic && topic->Exists(); } - wpi::json GetTopicProperty(NT_Topic topicHandle, std::string_view name) { + wpi::util::json GetTopicProperty(NT_Topic topicHandle, std::string_view name) { std::scoped_lock lock{m_mutex}; if (auto topic = m_impl.GetTopicByHandle(topicHandle)) { - return topic->properties.value(name, wpi::json{}); + return topic->properties.value(name, wpi::util::json{}); } else { return {}; } } void SetTopicProperty(NT_Topic topicHandle, std::string_view name, - const wpi::json& value) { + const wpi::util::json& value) { std::scoped_lock lock{m_mutex}; if (auto topic = m_impl.GetTopicByHandle(topicHandle)) { m_impl.SetProperty(topic, name, value); @@ -201,16 +201,16 @@ class LocalStorage final : public net::ILocalStorage { } } - wpi::json GetTopicProperties(NT_Topic topicHandle) { + wpi::util::json GetTopicProperties(NT_Topic topicHandle) { std::scoped_lock lock{m_mutex}; if (auto topic = m_impl.GetTopicByHandle(topicHandle)) { return topic->properties; } else { - return wpi::json::object(); + return wpi::util::json::object(); } } - bool SetTopicProperties(NT_Topic topicHandle, const wpi::json& update) { + bool SetTopicProperties(NT_Topic topicHandle, const wpi::util::json& update) { std::scoped_lock lock{m_mutex}; if (auto topic = m_impl.GetTopicByHandle(topicHandle)) { return m_impl.SetProperties(topic, update, true); @@ -262,7 +262,7 @@ class LocalStorage final : public net::ILocalStorage { } NT_Publisher Publish(NT_Topic topicHandle, NT_Type type, - std::string_view typeStr, const wpi::json& properties, + std::string_view typeStr, const wpi::util::json& properties, const PubSubOptions& options) { std::scoped_lock lock{m_mutex}; if (auto topic = m_impl.GetTopicByHandle(topicHandle)) { @@ -334,7 +334,7 @@ class LocalStorage final : public net::ILocalStorage { template Timestamped::SmallRet> GetAtomic( NT_Handle subentry, - wpi::SmallVectorImpl::SmallElem>& buf, + wpi::util::SmallVectorImpl::SmallElem>& buf, typename TypeInfo::View defaultValue) { std::scoped_lock lock{m_mutex}; Value* value = m_impl.GetSubEntryValue(subentry); @@ -485,8 +485,8 @@ class LocalStorage final : public net::ILocalStorage { } private: - wpi::mutex m_mutex; + wpi::util::mutex m_mutex; local::StorageImpl m_impl; }; -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/main/native/cpp/LoggerImpl.cpp b/ntcore/src/main/native/cpp/LoggerImpl.cpp index 478653758b..683185c6f2 100644 --- a/ntcore/src/main/native/cpp/LoggerImpl.cpp +++ b/ntcore/src/main/native/cpp/LoggerImpl.cpp @@ -12,26 +12,26 @@ #include "wpi/util/fs.hpp" #include "wpi/util/print.hpp" -using namespace nt; +using namespace wpi::nt; static void DefaultLogger(unsigned int level, const char* file, unsigned int line, const char* msg) { - if (level == wpi::WPI_LOG_INFO) { - wpi::print(stderr, "NT: {}\n", msg); + if (level == wpi::util::WPI_LOG_INFO) { + wpi::util::print(stderr, "NT: {}\n", msg); return; } std::string_view levelmsg; - if (level >= wpi::WPI_LOG_CRITICAL) { + if (level >= wpi::util::WPI_LOG_CRITICAL) { levelmsg = "CRITICAL"; - } else if (level >= wpi::WPI_LOG_ERROR) { + } else if (level >= wpi::util::WPI_LOG_ERROR) { levelmsg = "ERROR"; - } else if (level >= wpi::WPI_LOG_WARNING) { + } else if (level >= wpi::util::WPI_LOG_WARNING) { levelmsg = "WARNING"; } else { return; } - wpi::print(stderr, "NT: {}: {} ({}:{})\n", levelmsg, msg, file, line); + wpi::util::print(stderr, "NT: {}: {} ({}:{})\n", levelmsg, msg, file, line); } static constexpr unsigned int kFlagCritical = 1u << 16; @@ -45,23 +45,23 @@ static constexpr unsigned int kFlagDebug3 = 1u << 23; static constexpr unsigned int kFlagDebug4 = 1u << 24; static unsigned int LevelToFlag(unsigned int level) { - if (level >= wpi::WPI_LOG_CRITICAL) { + if (level >= wpi::util::WPI_LOG_CRITICAL) { return EventFlags::kLogMessage | kFlagCritical; - } else if (level >= wpi::WPI_LOG_ERROR) { + } else if (level >= wpi::util::WPI_LOG_ERROR) { return EventFlags::kLogMessage | kFlagError; - } else if (level >= wpi::WPI_LOG_WARNING) { + } else if (level >= wpi::util::WPI_LOG_WARNING) { return EventFlags::kLogMessage | kFlagWarning; - } else if (level >= wpi::WPI_LOG_INFO) { + } else if (level >= wpi::util::WPI_LOG_INFO) { return EventFlags::kLogMessage | kFlagInfo; - } else if (level >= wpi::WPI_LOG_DEBUG) { + } else if (level >= wpi::util::WPI_LOG_DEBUG) { return EventFlags::kLogMessage | kFlagDebug; - } else if (level >= wpi::WPI_LOG_DEBUG1) { + } else if (level >= wpi::util::WPI_LOG_DEBUG1) { return EventFlags::kLogMessage | kFlagDebug1; - } else if (level >= wpi::WPI_LOG_DEBUG2) { + } else if (level >= wpi::util::WPI_LOG_DEBUG2) { return EventFlags::kLogMessage | kFlagDebug2; - } else if (level >= wpi::WPI_LOG_DEBUG3) { + } else if (level >= wpi::util::WPI_LOG_DEBUG3) { return EventFlags::kLogMessage | kFlagDebug3; - } else if (level >= wpi::WPI_LOG_DEBUG4) { + } else if (level >= wpi::util::WPI_LOG_DEBUG4) { return EventFlags::kLogMessage | kFlagDebug4; } else { return EventFlags::kLogMessage; @@ -71,31 +71,31 @@ static unsigned int LevelToFlag(unsigned int level) { static unsigned int LevelsToEventMask(unsigned int minLevel, unsigned int maxLevel) { unsigned int mask = 0; - if (minLevel <= wpi::WPI_LOG_CRITICAL && maxLevel >= wpi::WPI_LOG_CRITICAL) { + if (minLevel <= wpi::util::WPI_LOG_CRITICAL && maxLevel >= wpi::util::WPI_LOG_CRITICAL) { mask |= kFlagCritical; } - if (minLevel <= wpi::WPI_LOG_ERROR && maxLevel >= wpi::WPI_LOG_ERROR) { + if (minLevel <= wpi::util::WPI_LOG_ERROR && maxLevel >= wpi::util::WPI_LOG_ERROR) { mask |= kFlagError; } - if (minLevel <= wpi::WPI_LOG_WARNING && maxLevel >= wpi::WPI_LOG_WARNING) { + if (minLevel <= wpi::util::WPI_LOG_WARNING && maxLevel >= wpi::util::WPI_LOG_WARNING) { mask |= kFlagWarning; } - if (minLevel <= wpi::WPI_LOG_INFO && maxLevel >= wpi::WPI_LOG_INFO) { + if (minLevel <= wpi::util::WPI_LOG_INFO && maxLevel >= wpi::util::WPI_LOG_INFO) { mask |= kFlagInfo; } - if (minLevel <= wpi::WPI_LOG_DEBUG && maxLevel >= wpi::WPI_LOG_DEBUG) { + if (minLevel <= wpi::util::WPI_LOG_DEBUG && maxLevel >= wpi::util::WPI_LOG_DEBUG) { mask |= kFlagDebug; } - if (minLevel <= wpi::WPI_LOG_DEBUG1 && maxLevel >= wpi::WPI_LOG_DEBUG1) { + if (minLevel <= wpi::util::WPI_LOG_DEBUG1 && maxLevel >= wpi::util::WPI_LOG_DEBUG1) { mask |= kFlagDebug1; } - if (minLevel <= wpi::WPI_LOG_DEBUG2 && maxLevel >= wpi::WPI_LOG_DEBUG2) { + if (minLevel <= wpi::util::WPI_LOG_DEBUG2 && maxLevel >= wpi::util::WPI_LOG_DEBUG2) { mask |= kFlagDebug2; } - if (minLevel <= wpi::WPI_LOG_DEBUG3 && maxLevel >= wpi::WPI_LOG_DEBUG3) { + if (minLevel <= wpi::util::WPI_LOG_DEBUG3 && maxLevel >= wpi::util::WPI_LOG_DEBUG3) { mask |= kFlagDebug3; } - if (minLevel <= wpi::WPI_LOG_DEBUG4 && maxLevel >= wpi::WPI_LOG_DEBUG4) { + if (minLevel <= wpi::util::WPI_LOG_DEBUG4 && maxLevel >= wpi::util::WPI_LOG_DEBUG4) { mask |= kFlagDebug4; } if (mask == 0) { diff --git a/ntcore/src/main/native/cpp/LoggerImpl.hpp b/ntcore/src/main/native/cpp/LoggerImpl.hpp index 5641f151df..9d9c09ae7a 100644 --- a/ntcore/src/main/native/cpp/LoggerImpl.hpp +++ b/ntcore/src/main/native/cpp/LoggerImpl.hpp @@ -12,7 +12,7 @@ #include "wpi/nt/ntcore_cpp.hpp" #include "wpi/util/mutex.hpp" -namespace nt { +namespace wpi::nt { class IListenerStorage; @@ -35,7 +35,7 @@ class LoggerImpl { private: IListenerStorage& m_listenerStorage; std::atomic_int m_listenerCount{0}; - wpi::mutex m_mutex; + wpi::util::mutex m_mutex; struct ListenerLevels { ListenerLevels(NT_Listener listener, unsigned int minLevel, @@ -49,4 +49,4 @@ class LoggerImpl { std::vector m_listenerLevels; }; -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/main/native/cpp/NetworkClient.cpp b/ntcore/src/main/native/cpp/NetworkClient.cpp index 8b659dc86b..8f2f824505 100644 --- a/ntcore/src/main/native/cpp/NetworkClient.cpp +++ b/ntcore/src/main/native/cpp/NetworkClient.cpp @@ -24,8 +24,8 @@ #include "wpi/util/SmallString.hpp" #include "wpi/util/StringExtras.hpp" -using namespace nt; -namespace uv = wpi::uv; +using namespace wpi::nt; +namespace uv = wpi::net::uv; static constexpr uv::Timer::Time kReconnectRate{1000}; static constexpr uv::Timer::Time kWebsocketHandshakeTimeout{500}; @@ -35,7 +35,7 @@ static constexpr size_t kMaxMessageSize = 2 * 1024 * 1024; NetworkClientBase::NetworkClientBase(int inst, std::string_view id, net::ILocalStorage& localStorage, IConnectionList& connList, - wpi::Logger& logger) + wpi::util::Logger& logger) : m_inst{inst}, m_localStorage{localStorage}, m_connList{connList}, @@ -62,7 +62,7 @@ void NetworkClientBase::StartDSClient(unsigned int port) { return; } m_dsClientServer.second = port == 0 ? NT_DEFAULT_PORT : port; - m_dsClient = wpi::DsClient::Create(m_loop, m_logger); + m_dsClient = wpi::net::DsClient::Create(m_loop, m_logger); if (m_dsClient) { m_dsClient->setIp.connect([this](std::string_view ip) { m_dsClientServer.first = ip; @@ -107,7 +107,7 @@ void NetworkClientBase::DoSetServers( std::vector> serversCopy; serversCopy.reserve(servers.size()); for (auto&& server : servers) { - serversCopy.emplace_back(wpi::trim(server.first), + serversCopy.emplace_back(wpi::util::trim(server.first), server.second == 0 ? defaultPort : server.second); } @@ -144,13 +144,13 @@ void NetworkClientBase::DoDisconnect(std::string_view reason) { NetworkClient::NetworkClient( int inst, std::string_view id, net::ILocalStorage& localStorage, - IConnectionList& connList, wpi::Logger& logger, + IConnectionList& connList, wpi::util::Logger& logger, std::function timeSyncUpdated) : NetworkClientBase{inst, id, localStorage, connList, logger}, m_timeSyncUpdated{std::move(timeSyncUpdated)} { m_loopRunner.ExecAsync([this](uv::Loop& loop) { - m_parallelConnect = wpi::ParallelTcpConnector::Create( + m_parallelConnect = wpi::net::ParallelTcpConnector::Create( loop, kReconnectRate, m_logger, [this](uv::Tcp& tcp) { TcpConnected(tcp); }, true); @@ -221,17 +221,17 @@ void NetworkClient::TcpConnected(uv::Tcp& tcp) { tcp.SetLogger(&m_logger); tcp.SetNoDelay(true); // Start the WS client - if (m_logger.min_level() >= wpi::WPI_LOG_DEBUG4) { + if (m_logger.min_level() >= wpi::util::WPI_LOG_DEBUG4) { std::string ip; unsigned int port = 0; uv::AddrToName(tcp.GetPeer(), &ip, &port); DEBUG4("Starting WebSocket client on {} port {}", ip, port); } - wpi::WebSocket::ClientOptions options; + wpi::net::WebSocket::ClientOptions options; options.handshakeTimeout = kWebsocketHandshakeTimeout; - wpi::SmallString<128> idBuf; - auto ws = wpi::WebSocket::CreateClient( - tcp, fmt::format("/nt/{}", wpi::EscapeURI(m_id, idBuf)), "", + wpi::util::SmallString<128> idBuf; + auto ws = wpi::net::WebSocket::CreateClient( + tcp, fmt::format("/nt/{}", wpi::net::EscapeURI(m_id, idBuf)), "", {"v4.1.networktables.first.wpi.edu", "networktables.first.wpi.edu"}, options); ws->SetMaxMessageSize(kMaxMessageSize); @@ -244,7 +244,7 @@ void NetworkClient::TcpConnected(uv::Tcp& tcp) { }); } -void NetworkClient::WsConnected(wpi::WebSocket& ws, uv::Tcp& tcp, +void NetworkClient::WsConnected(wpi::net::WebSocket& ws, uv::Tcp& tcp, std::string_view protocol) { if (m_parallelConnect) { m_parallelConnect->Succeeded(tcp); @@ -258,7 +258,7 @@ void NetworkClient::WsConnected(wpi::WebSocket& ws, uv::Tcp& tcp, INFO("CONNECTED NT4 to {} port {}", connInfo.remote_ip, connInfo.remote_port); m_connHandle = m_connList.AddConnection(connInfo); - bool local = wpi::starts_with(connInfo.remote_ip, "127."); + bool local = wpi::util::starts_with(connInfo.remote_ip, "127."); m_wire = std::make_shared( ws, connInfo.protocol_version, m_logger); diff --git a/ntcore/src/main/native/cpp/NetworkClient.hpp b/ntcore/src/main/native/cpp/NetworkClient.hpp index aba53f4ab4..0fce2f0711 100644 --- a/ntcore/src/main/native/cpp/NetworkClient.hpp +++ b/ntcore/src/main/native/cpp/NetworkClient.hpp @@ -25,15 +25,15 @@ #include "wpi/net/uv/Async.hpp" #include "wpi/net/uv/Timer.hpp" -namespace wpi { +namespace wpi::util { class Logger; } // namespace wpi -namespace nt::net { +namespace wpi::nt::net { class ILocalStorage; -} // namespace nt::net +} // namespace wpi::nt::net -namespace nt { +namespace wpi::nt { class IConnectionList; @@ -41,7 +41,7 @@ class NetworkClientBase : public INetworkClient { public: NetworkClientBase(int inst, std::string_view id, net::ILocalStorage& localStorage, IConnectionList& connList, - wpi::Logger& logger); + wpi::util::Logger& logger); ~NetworkClientBase() override; void Disconnect() override; @@ -57,7 +57,7 @@ class NetworkClientBase : public INetworkClient { std::span> servers, unsigned int defaultPort); - virtual void TcpConnected(wpi::uv::Tcp& tcp) = 0; + virtual void TcpConnected(wpi::net::uv::Tcp& tcp) = 0; virtual void ForceDisconnect(std::string_view reason) = 0; virtual void DoDisconnect(std::string_view reason); @@ -65,15 +65,15 @@ class NetworkClientBase : public INetworkClient { int m_inst; net::ILocalStorage& m_localStorage; IConnectionList& m_connList; - wpi::Logger& m_logger; + wpi::util::Logger& m_logger; std::string m_id; // used only from loop - std::shared_ptr m_parallelConnect; - std::shared_ptr m_readLocalTimer; - std::shared_ptr m_sendOutgoingTimer; - std::shared_ptr> m_flushLocal; - std::shared_ptr> m_flush; + std::shared_ptr m_parallelConnect; + std::shared_ptr m_readLocalTimer; + std::shared_ptr m_sendOutgoingTimer; + std::shared_ptr> m_flushLocal; + std::shared_ptr> m_flush; using Queue = net::LocalClientMessageQueue; net::ClientMessage m_localMsgs[Queue::kBlockSize]; @@ -81,25 +81,25 @@ class NetworkClientBase : public INetworkClient { std::vector> m_servers; std::pair m_dsClientServer{"", 0}; - std::shared_ptr m_dsClient; + std::shared_ptr m_dsClient; // shared with user - std::atomic*> m_flushLocalAtomic{nullptr}; - std::atomic*> m_flushAtomic{nullptr}; + std::atomic*> m_flushLocalAtomic{nullptr}; + std::atomic*> m_flushAtomic{nullptr}; Queue m_localQueue; int m_connHandle = 0; - wpi::EventLoopRunner m_loopRunner; - wpi::uv::Loop& m_loop; + wpi::net::EventLoopRunner m_loopRunner; + wpi::net::uv::Loop& m_loop; }; class NetworkClient final : public NetworkClientBase { public: NetworkClient( int inst, std::string_view id, net::ILocalStorage& localStorage, - IConnectionList& connList, wpi::Logger& logger, + IConnectionList& connList, wpi::util::Logger& logger, std::function timeSyncUpdated); ~NetworkClient() final; @@ -111,8 +111,8 @@ class NetworkClient final : public NetworkClientBase { private: void HandleLocal(); - void TcpConnected(wpi::uv::Tcp& tcp) final; - void WsConnected(wpi::WebSocket& ws, wpi::uv::Tcp& tcp, + void TcpConnected(wpi::net::uv::Tcp& tcp) final; + void WsConnected(wpi::net::WebSocket& ws, wpi::net::uv::Tcp& tcp, std::string_view protocol); void ForceDisconnect(std::string_view reason) override; void DoDisconnect(std::string_view reason) override; @@ -123,4 +123,4 @@ class NetworkClient final : public NetworkClientBase { std::unique_ptr m_clientImpl; }; -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/main/native/cpp/NetworkServer.cpp b/ntcore/src/main/native/cpp/NetworkServer.cpp index 804d3ee18b..3f2a0f95e2 100644 --- a/ntcore/src/main/native/cpp/NetworkServer.cpp +++ b/ntcore/src/main/native/cpp/NetworkServer.cpp @@ -34,8 +34,8 @@ #include "wpi/util/raw_ostream.hpp" #include "wpi/util/timestamp.h" -using namespace nt; -namespace uv = wpi::uv; +using namespace wpi::nt; +namespace uv = wpi::net::uv; // use a larger max message size for websockets static constexpr size_t kMaxMessageSize = 2 * 1024 * 1024; @@ -45,7 +45,7 @@ static constexpr size_t kClientProcessMessageCountMax = 16; class NetworkServer::ServerConnection { public: ServerConnection(NetworkServer& server, std::string_view addr, - unsigned int port, wpi::Logger& logger) + unsigned int port, wpi::util::Logger& logger) : m_server{server}, m_connInfo{fmt::format("{}:{}", addr, port)}, m_logger{logger} { @@ -64,7 +64,7 @@ class NetworkServer::ServerConnection { NetworkServer& m_server; ConnectionInfo m_info; std::string m_connInfo; - wpi::Logger& m_logger; + wpi::util::Logger& m_logger; int m_clientId; private: @@ -73,11 +73,11 @@ class NetworkServer::ServerConnection { class NetworkServer::ServerConnection4 final : public ServerConnection, - public wpi::HttpWebSocketServerConnection { + public wpi::net::HttpWebSocketServerConnection { public: ServerConnection4(std::shared_ptr stream, NetworkServer& server, std::string_view addr, unsigned int port, - wpi::Logger& logger) + wpi::util::Logger& logger) : ServerConnection{server, addr, port, logger}, HttpWebSocketServerConnection( stream, @@ -125,8 +125,8 @@ void NetworkServer::ServerConnection::ConnectionClosed() { void NetworkServer::ServerConnection4::ProcessRequest() { DEBUG1("HTTP request: '{}'", m_request.GetUrl()); - wpi::UrlParser url{m_request.GetUrl(), - m_request.GetMethod() == wpi::HTTP_CONNECT}; + wpi::net::UrlParser url{m_request.GetUrl(), + m_request.GetMethod() == wpi::net::HTTP_CONNECT}; if (!url.IsValid()) { // failed to parse URL SendError(400); @@ -145,7 +145,7 @@ void NetworkServer::ServerConnection4::ProcessRequest() { } DEBUG4("query: \"{}\"\n", query); - const bool isGET = m_request.GetMethod() == wpi::HTTP_GET; + const bool isGET = m_request.GetMethod() == wpi::net::HTTP_GET; if (isGET && path == "/") { // build HTML root page SendResponse(200, "OK", "text/html", @@ -162,18 +162,18 @@ void NetworkServer::ServerConnection4::ProcessRequest() { void NetworkServer::ServerConnection4::ProcessWsUpgrade() { // get name from URL - wpi::UrlParser url{m_request.GetUrl(), false}; + wpi::net::UrlParser url{m_request.GetUrl(), false}; std::string_view path; if (url.HasPath()) { path = url.GetPath(); } DEBUG4("path: '{}'", path); - wpi::SmallString<128> nameBuf; + wpi::util::SmallString<128> nameBuf; std::string_view name; bool err = false; - if (auto uri = wpi::remove_prefix(path, "/nt/")) { - name = wpi::UnescapeURI(*uri, nameBuf, &err); + if (auto uri = wpi::util::remove_prefix(path, "/nt/")) { + name = wpi::net::UnescapeURI(*uri, nameBuf, &err); } if (err || name.empty()) { INFO("invalid path '{}' (from {}), must match /nt/[clientId], closing", @@ -208,7 +208,7 @@ void NetworkServer::ServerConnection4::ProcessWsUpgrade() { // respond to RTT ping if (pubuid == -1) { m_wire->SendBinary([&](auto& os) { - net::WireEncodeBinary(os, -1, wpi::Now(), value); + net::WireEncodeBinary(os, -1, wpi::util::Now(), value); }); } } @@ -221,7 +221,7 @@ void NetworkServer::ServerConnection4::ProcessWsUpgrade() { return; } - bool local = wpi::starts_with(m_info.remote_ip, "127."); + bool local = wpi::util::starts_with(m_info.remote_ip, "127."); std::string dedupName; std::tie(dedupName, m_clientId) = m_server.m_serverImpl.AddClient( name, m_connInfo, local, *m_wire, @@ -255,14 +255,14 @@ void NetworkServer::ServerConnection4::ProcessWsUpgrade() { NetworkServer::NetworkServer(std::string_view persistentFilename, std::string_view listenAddress, unsigned int port, net::ILocalStorage& localStorage, - IConnectionList& connList, wpi::Logger& logger, + IConnectionList& connList, wpi::util::Logger& logger, std::function initDone) : m_localStorage{localStorage}, m_connList{connList}, m_logger{logger}, m_initDone{std::move(initDone)}, m_persistentFilename{persistentFilename}, - m_listenAddress{wpi::trim(listenAddress)}, + m_listenAddress{wpi::util::trim(listenAddress)}, m_port{port}, m_serverImpl{logger}, m_localQueue{logger}, @@ -302,7 +302,7 @@ void NetworkServer::ProcessAllLocal() { } void NetworkServer::LoadPersistent() { - auto fileBuffer = wpi::MemoryBuffer::GetFile(m_persistentFilename); + auto fileBuffer = wpi::util::MemoryBuffer::GetFile(m_persistentFilename); if (!fileBuffer) { INFO( "could not open persistent file '{}': {} " @@ -313,7 +313,7 @@ void NetworkServer::LoadPersistent() { fs::copy_file(m_persistentFilename, m_persistentFilename + ".bak", std::filesystem::copy_options::overwrite_existing, ec); // try to write an empty file so it doesn't happen again - wpi::raw_fd_ostream os{m_persistentFilename, ec, fs::F_Text}; + wpi::util::raw_fd_ostream os{m_persistentFilename, ec, fs::F_Text}; if (ec.value() == 0) { os << "[]\n"; os.close(); @@ -330,7 +330,7 @@ void NetworkServer::SavePersistent(std::string_view filename, // write to temporary file auto tmp = fmt::format("{}.tmp", filename); std::error_code ec; - wpi::raw_fd_ostream os{tmp, ec, fs::F_Text}; + wpi::util::raw_fd_ostream os{tmp, ec, fs::F_Text}; if (ec.value() != 0) { INFO("could not open persistent file '{}' for write: {}", tmp, ec.message()); diff --git a/ntcore/src/main/native/cpp/NetworkServer.hpp b/ntcore/src/main/native/cpp/NetworkServer.hpp index b542dca8fe..721a52a8d1 100644 --- a/ntcore/src/main/native/cpp/NetworkServer.hpp +++ b/ntcore/src/main/native/cpp/NetworkServer.hpp @@ -20,15 +20,15 @@ #include "wpi/net/uv/Timer.hpp" #include "wpi/nt/ntcore_cpp.hpp" -namespace wpi { +namespace wpi::util { class Logger; } // namespace wpi -namespace nt::net { +namespace wpi::nt::net { class ILocalStorage; -} // namespace nt::net +} // namespace wpi::nt::net -namespace nt { +namespace wpi::nt { class IConnectionList; @@ -37,7 +37,7 @@ class NetworkServer { NetworkServer(std::string_view persistentFilename, std::string_view listenAddress, unsigned int port, net::ILocalStorage& localStorage, IConnectionList& connList, - wpi::Logger& logger, std::function initDone); + wpi::util::Logger& logger, std::function initDone); ~NetworkServer(); void FlushLocal(); @@ -56,7 +56,7 @@ class NetworkServer { net::ILocalStorage& m_localStorage; IConnectionList& m_connList; - wpi::Logger& m_logger; + wpi::util::Logger& m_logger; std::function m_initDone; std::string m_persistentData; std::string m_persistentFilename; @@ -64,11 +64,11 @@ class NetworkServer { unsigned int m_port; // used only from loop - std::shared_ptr m_readLocalTimer; - std::shared_ptr m_savePersistentTimer; - std::shared_ptr> m_flushLocal; - std::shared_ptr> m_flush; - std::shared_ptr m_idle; + std::shared_ptr m_readLocalTimer; + std::shared_ptr m_savePersistentTimer; + std::shared_ptr> m_flushLocal; + std::shared_ptr> m_flush; + std::shared_ptr m_idle; bool m_shutdown = false; using Queue = net::LocalClientMessageQueue; @@ -77,9 +77,9 @@ class NetworkServer { server::ServerImpl m_serverImpl; // shared with user (must be atomic or mutex-protected) - std::atomic*> m_flushLocalAtomic{nullptr}; - std::atomic*> m_flushAtomic{nullptr}; - mutable wpi::mutex m_mutex; + std::atomic*> m_flushLocalAtomic{nullptr}; + std::atomic*> m_flushAtomic{nullptr}; + mutable wpi::util::mutex m_mutex; struct Connection { ServerConnection* conn; int connHandle; @@ -88,8 +88,8 @@ class NetworkServer { Queue m_localQueue; - wpi::EventLoopRunner m_loopRunner; - wpi::uv::Loop& m_loop; + wpi::net::EventLoopRunner m_loopRunner; + wpi::net::uv::Loop& m_loop; }; -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/main/native/cpp/PubSubOptions.hpp b/ntcore/src/main/native/cpp/PubSubOptions.hpp index 67ed602cf9..65d678969b 100644 --- a/ntcore/src/main/native/cpp/PubSubOptions.hpp +++ b/ntcore/src/main/native/cpp/PubSubOptions.hpp @@ -6,7 +6,7 @@ #include "wpi/nt/ntcore_cpp.hpp" -namespace nt { +namespace wpi::nt { // internal helper class for PubSubOptions class PubSubOptionsImpl : public PubSubOptions { @@ -33,4 +33,4 @@ class PubSubOptionsImpl : public PubSubOptions { unsigned int periodicMs = kDefaultPeriodicMs; }; -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/main/native/cpp/Types_internal.cpp b/ntcore/src/main/native/cpp/Types_internal.cpp index faf49d645f..cb9c706413 100644 --- a/ntcore/src/main/native/cpp/Types_internal.cpp +++ b/ntcore/src/main/native/cpp/Types_internal.cpp @@ -4,7 +4,7 @@ #include "Types_internal.hpp" -std::string_view nt::TypeToString(NT_Type type) { +std::string_view wpi::nt::TypeToString(NT_Type type) { switch (type) { case NT_BOOLEAN: return "boolean"; @@ -33,7 +33,7 @@ std::string_view nt::TypeToString(NT_Type type) { } } -NT_Type nt::StringToType(std::string_view typeStr) { +NT_Type wpi::nt::StringToType(std::string_view typeStr) { if (typeStr == "boolean") { return NT_BOOLEAN; } else if (typeStr == "double") { @@ -61,7 +61,7 @@ NT_Type nt::StringToType(std::string_view typeStr) { } } -NT_Type nt::StringToType3(std::string_view typeStr) { +NT_Type wpi::nt::StringToType3(std::string_view typeStr) { if (typeStr == "boolean") { return NT_BOOLEAN; } else if (typeStr == "double" || typeStr == "int" || typeStr == "float") { diff --git a/ntcore/src/main/native/cpp/Types_internal.hpp b/ntcore/src/main/native/cpp/Types_internal.hpp index c05e068f3c..4e680edf13 100644 --- a/ntcore/src/main/native/cpp/Types_internal.hpp +++ b/ntcore/src/main/native/cpp/Types_internal.hpp @@ -8,7 +8,7 @@ #include "wpi/nt/ntcore_c.h" -namespace nt { +namespace wpi::nt { std::string_view TypeToString(NT_Type type); NT_Type StringToType(std::string_view typeStr); @@ -27,4 +27,4 @@ constexpr bool IsNumericCompatible(NT_Type a, NT_Type b) { (IsNumericArray(a) && IsNumericArray(b)); } -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/main/native/cpp/Value.cpp b/ntcore/src/main/native/cpp/Value.cpp index 626343148b..c121526042 100644 --- a/ntcore/src/main/native/cpp/Value.cpp +++ b/ntcore/src/main/native/cpp/Value.cpp @@ -18,7 +18,7 @@ #include "wpi/util/MemAlloc.hpp" #include "wpi/util/timestamp.h" -using namespace nt; +using namespace wpi::nt; namespace { struct StringArrayStorage { @@ -176,7 +176,7 @@ Value Value::MakeStringArray(std::vector&& value, int64_t time) { return val; } -void nt::ConvertToC(const Value& in, NT_Value* out) { +void wpi::nt::ConvertToC(const Value& in, NT_Value* out) { *out = in.value(); switch (in.type()) { case NT_STRING: @@ -184,7 +184,7 @@ void nt::ConvertToC(const Value& in, NT_Value* out) { break; case NT_RAW: { auto v = in.GetRaw(); - out->data.v_raw.data = static_cast(wpi::safe_malloc(v.size())); + out->data.v_raw.data = static_cast(wpi::util::safe_malloc(v.size())); out->data.v_raw.size = v.size(); std::memcpy(out->data.v_raw.data, v.data(), v.size()); break; @@ -192,7 +192,7 @@ void nt::ConvertToC(const Value& in, NT_Value* out) { case NT_BOOLEAN_ARRAY: { auto v = in.GetBooleanArray(); out->data.arr_boolean.arr = - static_cast(wpi::safe_malloc(v.size() * sizeof(int))); + static_cast(wpi::util::safe_malloc(v.size() * sizeof(int))); out->data.arr_boolean.size = v.size(); std::copy(v.begin(), v.end(), out->data.arr_boolean.arr); break; @@ -200,7 +200,7 @@ void nt::ConvertToC(const Value& in, NT_Value* out) { case NT_INTEGER_ARRAY: { auto v = in.GetIntegerArray(); out->data.arr_int.arr = - static_cast(wpi::safe_malloc(v.size() * sizeof(int64_t))); + static_cast(wpi::util::safe_malloc(v.size() * sizeof(int64_t))); out->data.arr_int.size = v.size(); std::copy(v.begin(), v.end(), out->data.arr_int.arr); break; @@ -208,7 +208,7 @@ void nt::ConvertToC(const Value& in, NT_Value* out) { case NT_FLOAT_ARRAY: { auto v = in.GetFloatArray(); out->data.arr_float.arr = - static_cast(wpi::safe_malloc(v.size() * sizeof(float))); + static_cast(wpi::util::safe_malloc(v.size() * sizeof(float))); out->data.arr_float.size = v.size(); std::copy(v.begin(), v.end(), out->data.arr_float.arr); break; @@ -216,7 +216,7 @@ void nt::ConvertToC(const Value& in, NT_Value* out) { case NT_DOUBLE_ARRAY: { auto v = in.GetDoubleArray(); out->data.arr_double.arr = - static_cast(wpi::safe_malloc(v.size() * sizeof(double))); + static_cast(wpi::util::safe_malloc(v.size() * sizeof(double))); out->data.arr_double.size = v.size(); std::copy(v.begin(), v.end(), out->data.arr_double.arr); break; @@ -235,7 +235,7 @@ void nt::ConvertToC(const Value& in, NT_Value* out) { } } -void nt::ConvertToC(std::string_view in, WPI_String* out) { +void wpi::nt::ConvertToC(std::string_view in, WPI_String* out) { if (in.empty()) { out->len = 0; out->str = nullptr; @@ -245,7 +245,7 @@ void nt::ConvertToC(std::string_view in, WPI_String* out) { std::memcpy(write, in.data(), in.size()); } -Value nt::ConvertFromC(const NT_Value& value) { +Value wpi::nt::ConvertFromC(const NT_Value& value) { switch (value.type) { case NT_BOOLEAN: return Value::MakeBoolean(value.data.v_boolean != 0, value.last_change); @@ -290,7 +290,7 @@ Value nt::ConvertFromC(const NT_Value& value) { } } -bool nt::operator==(const Value& lhs, const Value& rhs) { +bool wpi::nt::operator==(const Value& lhs, const Value& rhs) { if (lhs.type() != rhs.type()) { return false; } diff --git a/ntcore/src/main/native/cpp/ValueCircularBuffer.cpp b/ntcore/src/main/native/cpp/ValueCircularBuffer.cpp index c1ac1b26d2..16aa106f5f 100644 --- a/ntcore/src/main/native/cpp/ValueCircularBuffer.cpp +++ b/ntcore/src/main/native/cpp/ValueCircularBuffer.cpp @@ -7,7 +7,7 @@ #include #include -using namespace nt; +using namespace wpi::nt; std::vector ValueCircularBuffer::ReadValue(unsigned int types) { std::vector rv; diff --git a/ntcore/src/main/native/cpp/ValueCircularBuffer.hpp b/ntcore/src/main/native/cpp/ValueCircularBuffer.hpp index fd363a5cb0..2f6e687b38 100644 --- a/ntcore/src/main/native/cpp/ValueCircularBuffer.hpp +++ b/ntcore/src/main/native/cpp/ValueCircularBuffer.hpp @@ -12,7 +12,7 @@ #include "wpi/nt/ntcore_cpp_types.hpp" #include "wpi/util/circular_buffer.hpp" -namespace nt { +namespace wpi::nt { class ValueCircularBuffer { public: @@ -28,7 +28,7 @@ class ValueCircularBuffer { std::vector::Value>> Read(); private: - wpi::circular_buffer m_storage; + wpi::util::circular_buffer m_storage; }; template @@ -45,4 +45,4 @@ ValueCircularBuffer::Read() { return rv; } -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/main/native/cpp/Value_internal.cpp b/ntcore/src/main/native/cpp/Value_internal.cpp index 74ed89fe1a..b050f3a836 100644 --- a/ntcore/src/main/native/cpp/Value_internal.cpp +++ b/ntcore/src/main/native/cpp/Value_internal.cpp @@ -4,9 +4,9 @@ #include "Value_internal.hpp" -using namespace nt; +using namespace wpi::nt; -Value nt::ConvertNumericValue(const Value& value, NT_Type type) { +Value wpi::nt::ConvertNumericValue(const Value& value, NT_Type type) { switch (type) { case NT_INTEGER: { Value newval = diff --git a/ntcore/src/main/native/cpp/Value_internal.hpp b/ntcore/src/main/native/cpp/Value_internal.hpp index e4c2a24632..32a70d8982 100644 --- a/ntcore/src/main/native/cpp/Value_internal.hpp +++ b/ntcore/src/main/native/cpp/Value_internal.hpp @@ -18,7 +18,7 @@ #include "wpi/nt/ntcore_cpp_types.hpp" #include "wpi/util/MemAlloc.hpp" -namespace nt { +namespace wpi::nt { template struct TypeInfo {}; @@ -356,7 +356,7 @@ inline typename TypeInfo::Value CopyValue(typename TypeInfo::View value) { template inline typename TypeInfo::SmallRet CopyValue( typename TypeInfo::View arr, - wpi::SmallVectorImpl::SmallElem>& buf) { + wpi::util::SmallVectorImpl::SmallElem>& buf) { buf.assign(arr.begin(), arr.end()); return {buf.data(), buf.size()}; } @@ -375,7 +375,7 @@ inline typename TypeInfo::Value GetValueCopy(const Value& value) { template inline typename TypeInfo::SmallRet GetValueCopy( const Value& value, - wpi::SmallVectorImpl::SmallElem>& buf) { + wpi::util::SmallVectorImpl::SmallElem>& buf) { if constexpr (ConvertNumeric && NumericArrayType) { if (value.IsIntegerArray()) { auto arr = value.GetIntegerArray(); @@ -407,7 +407,7 @@ inline Timestamped::Value> GetTimestamped( template inline Timestamped::SmallRet> GetTimestamped( const Value& value, - wpi::SmallVectorImpl::SmallElem>& buf) { + wpi::util::SmallVectorImpl::SmallElem>& buf) { return {value.time(), value.server_time(), GetValueCopy(value, buf)}; } @@ -434,7 +434,7 @@ O* ConvertToC(const std::vector& in, size_t* out_len) { if (in.empty()) { return nullptr; } - O* out = static_cast(wpi::safe_malloc(sizeof(O) * in.size())); + O* out = static_cast(wpi::util::safe_malloc(sizeof(O) * in.size())); for (size_t i = 0; i < in.size(); ++i) { ConvertToC(in[i], &out[i]); } @@ -443,7 +443,7 @@ O* ConvertToC(const std::vector& in, size_t* out_len) { template O* ConvertToC(const std::basic_string& in, size_t* out_len) { - char* out = static_cast(wpi::safe_malloc(in.size() + 1)); + char* out = static_cast(wpi::util::safe_malloc(in.size() + 1)); std::memmove(out, in.data(), in.size()); // NOLINT out[in.size()] = '\0'; *out_len = in.size(); @@ -452,4 +452,4 @@ O* ConvertToC(const std::basic_string& in, size_t* out_len) { Value ConvertNumericValue(const Value& value, NT_Type type); -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/main/native/cpp/VectorSet.hpp b/ntcore/src/main/native/cpp/VectorSet.hpp index 9e13490736..25f9355d26 100644 --- a/ntcore/src/main/native/cpp/VectorSet.hpp +++ b/ntcore/src/main/native/cpp/VectorSet.hpp @@ -6,7 +6,7 @@ #include -namespace nt { +namespace wpi::nt { // Utility wrapper for making a set-like vector template @@ -18,4 +18,4 @@ class VectorSet : public std::vector { bool Remove(T value) { return std::erase(*this, value) != 0; } }; -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/main/native/cpp/jni/NetworkTablesJNI.cpp b/ntcore/src/main/native/cpp/jni/NetworkTablesJNI.cpp index be77522dfd..1b2c820d81 100644 --- a/ntcore/src/main/native/cpp/jni/NetworkTablesJNI.cpp +++ b/ntcore/src/main/native/cpp/jni/NetworkTablesJNI.cpp @@ -18,16 +18,16 @@ #include "wpi/util/jni_util.hpp" #include "wpi/util/json.hpp" -using namespace wpi::java; +using namespace wpi::util::java; #ifdef __GNUC__ #pragma GCC diagnostic ignored "-Wdeprecated-declarations" #endif -namespace nt { +namespace wpi::nt { bool JNI_LoadTypes(JNIEnv* env); void JNI_UnloadTypes(JNIEnv* env); -} // namespace nt +} // namespace wpi::nt // // Globals and load/unload @@ -94,7 +94,7 @@ JNIEXPORT jint JNICALL JNI_OnLoad(JavaVM* vm, void* reserved) { } } - if (!nt::JNI_LoadTypes(env)) { + if (!wpi::nt::JNI_LoadTypes(env)) { return JNI_ERR; } @@ -113,7 +113,7 @@ JNIEXPORT void JNICALL JNI_OnUnload(JavaVM* vm, void* reserved) { for (auto& c : exceptions) { c.cls->free(env); } - nt::JNI_UnloadTypes(env); + wpi::nt::JNI_UnloadTypes(env); } } // extern "C" @@ -122,7 +122,7 @@ JNIEXPORT void JNICALL JNI_OnUnload(JavaVM* vm, void* reserved) { // Conversions from Java objects to C++ // -static nt::PubSubOptions FromJavaPubSubOptions(JNIEnv* env, jobject joptions) { +static wpi::nt::PubSubOptions FromJavaPubSubOptions(JNIEnv* env, jobject joptions) { if (!joptions) { return {}; } @@ -188,7 +188,7 @@ static jobject MakeJObject(JNIEnv* env, std::optional value) { } } -static jobject MakeJObject(JNIEnv* env, const nt::Value& value) { +static jobject MakeJObject(JNIEnv* env, const wpi::nt::Value& value) { static jmethodID booleanConstructor = nullptr; static jmethodID doubleConstructor = nullptr; static jmethodID floatConstructor = nullptr; @@ -238,7 +238,7 @@ static jobject MakeJObject(JNIEnv* env, const nt::Value& value) { } } -static jobject MakeJValue(JNIEnv* env, const nt::Value& value) { +static jobject MakeJValue(JNIEnv* env, const wpi::nt::Value& value) { static jmethodID constructor = env->GetMethodID(valueCls, "", "(ILjava/lang/Object;JJ)V"); if (!value) { @@ -252,7 +252,7 @@ static jobject MakeJValue(JNIEnv* env, const nt::Value& value) { static_cast(value.server_time())); } -static jobject MakeJObject(JNIEnv* env, const nt::ConnectionInfo& info) { +static jobject MakeJObject(JNIEnv* env, const wpi::nt::ConnectionInfo& info) { static jmethodID constructor = env->GetMethodID(connectionInfoCls, "", "(Ljava/lang/String;Ljava/lang/String;IJI)V"); @@ -264,7 +264,7 @@ static jobject MakeJObject(JNIEnv* env, const nt::ConnectionInfo& info) { static_cast(info.protocol_version)); } -static jobject MakeJObject(JNIEnv* env, const nt::LogMessage& msg) { +static jobject MakeJObject(JNIEnv* env, const wpi::nt::LogMessage& msg) { static jmethodID constructor = env->GetMethodID( logMessageCls, "", "(ILjava/lang/String;ILjava/lang/String;)V"); JLocal filename{env, MakeJString(env, msg.filename)}; @@ -275,7 +275,7 @@ static jobject MakeJObject(JNIEnv* env, const nt::LogMessage& msg) { } static jobject MakeJObject(JNIEnv* env, jobject inst, - const nt::TopicInfo& info) { + const wpi::nt::TopicInfo& info) { static jmethodID constructor = env->GetMethodID( topicInfoCls, "", "(Lorg/wpilib/networktables/" @@ -288,7 +288,7 @@ static jobject MakeJObject(JNIEnv* env, jobject inst, } static jobject MakeJObject(JNIEnv* env, jobject inst, - const nt::ValueEventData& data) { + const wpi::nt::ValueEventData& data) { static jmethodID constructor = env->GetMethodID(valueEventDataCls, "", "(Lorg/wpilib/networktables/NetworkTableInstance;II" @@ -299,7 +299,7 @@ static jobject MakeJObject(JNIEnv* env, jobject inst, static_cast(data.subentry), value.obj()); } -static jobject MakeJObject(JNIEnv* env, const nt::TimeSyncEventData& data) { +static jobject MakeJObject(JNIEnv* env, const wpi::nt::TimeSyncEventData& data) { static jmethodID constructor = env->GetMethodID(timeSyncEventDataCls, "", "(JJZ)V"); return env->NewObject(timeSyncEventDataCls, constructor, @@ -308,7 +308,7 @@ static jobject MakeJObject(JNIEnv* env, const nt::TimeSyncEventData& data) { static_cast(data.valid)); } -static jobject MakeJObject(JNIEnv* env, jobject inst, const nt::Event& event) { +static jobject MakeJObject(JNIEnv* env, jobject inst, const wpi::nt::Event& event) { static jmethodID constructor = env->GetMethodID(eventCls, "", "(Lorg/wpilib/networktables/NetworkTableInstance;II" @@ -339,7 +339,7 @@ static jobject MakeJObject(JNIEnv* env, jobject inst, const nt::Event& event) { valueData.obj(), logMessage.obj(), timeSyncData.obj()); } -static jobjectArray MakeJObject(JNIEnv* env, std::span arr) { +static jobjectArray MakeJObject(JNIEnv* env, std::span arr) { jobjectArray jarr = env->NewObjectArray(arr.size(), valueCls, nullptr); if (!jarr) { return nullptr; @@ -352,7 +352,7 @@ static jobjectArray MakeJObject(JNIEnv* env, std::span arr) { } static jobjectArray MakeJObject(JNIEnv* env, jobject inst, - std::span arr) { + std::span arr) { jobjectArray jarr = env->NewObjectArray(arr.size(), eventCls, nullptr); if (!jarr) { return nullptr; @@ -375,7 +375,7 @@ JNIEXPORT jint JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_getDefaultInstance (JNIEnv*, jclass) { - return nt::GetDefaultInstance(); + return wpi::nt::GetDefaultInstance(); } /* @@ -387,7 +387,7 @@ JNIEXPORT jint JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_createInstance (JNIEnv*, jclass) { - return nt::CreateInstance(); + return wpi::nt::CreateInstance(); } /* @@ -399,7 +399,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_destroyInstance (JNIEnv*, jclass, jint inst) { - nt::DestroyInstance(inst); + wpi::nt::DestroyInstance(inst); } /* @@ -411,7 +411,7 @@ JNIEXPORT jint JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_getInstanceFromHandle (JNIEnv*, jclass, jint handle) { - return nt::GetInstanceFromHandle(handle); + return wpi::nt::GetInstanceFromHandle(handle); } /* @@ -427,7 +427,7 @@ Java_org_wpilib_networktables_NetworkTablesJNI_getEntry nullPointerEx.Throw(env, "key cannot be null"); return false; } - return nt::GetEntry(inst, JStringRef{env, key}); + return wpi::nt::GetEntry(inst, JStringRef{env, key}); } /* @@ -439,7 +439,7 @@ JNIEXPORT jstring JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_getEntryName (JNIEnv* env, jclass, jint entry) { - return MakeJString(env, nt::GetEntryName(entry)); + return MakeJString(env, wpi::nt::GetEntryName(entry)); } /* @@ -451,7 +451,7 @@ JNIEXPORT jlong JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_getEntryLastChange (JNIEnv*, jclass, jint entry) { - return nt::GetEntryLastChange(entry); + return wpi::nt::GetEntryLastChange(entry); } /* @@ -463,7 +463,7 @@ JNIEXPORT jint JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_getType (JNIEnv*, jclass, jint entry) { - return nt::GetEntryType(entry); + return wpi::nt::GetEntryType(entry); } /* @@ -479,7 +479,7 @@ Java_org_wpilib_networktables_NetworkTablesJNI_getTopics nullPointerEx.Throw(env, "prefix cannot be null"); return nullptr; } - auto arr = nt::GetTopics(inst, JStringRef{env, prefix}.str(), types); + auto arr = wpi::nt::GetTopics(inst, JStringRef{env, prefix}.str(), types); return MakeJIntArray(env, arr); } @@ -516,7 +516,7 @@ Java_org_wpilib_networktables_NetworkTablesJNI_getTopicsStr typeStrs.emplace_back(typeStrData.back()); } - auto arr = nt::GetTopics(inst, JStringRef{env, prefix}.str(), typeStrs); + auto arr = wpi::nt::GetTopics(inst, JStringRef{env, prefix}.str(), typeStrs); return MakeJIntArray(env, arr); } @@ -534,7 +534,7 @@ Java_org_wpilib_networktables_NetworkTablesJNI_getTopicInfos nullPointerEx.Throw(env, "prefix cannot be null"); return nullptr; } - auto arr = nt::GetTopicInfo(inst, JStringRef{env, prefix}.str(), types); + auto arr = wpi::nt::GetTopicInfo(inst, JStringRef{env, prefix}.str(), types); jobjectArray jarr = env->NewObjectArray(arr.size(), topicInfoCls, nullptr); if (!jarr) { return nullptr; @@ -580,7 +580,7 @@ Java_org_wpilib_networktables_NetworkTablesJNI_getTopicInfosStr typeStrs.emplace_back(typeStrData.back()); } - auto arr = nt::GetTopicInfo(inst, JStringRef{env, prefix}.str(), typeStrs); + auto arr = wpi::nt::GetTopicInfo(inst, JStringRef{env, prefix}.str(), typeStrs); jobjectArray jarr = env->NewObjectArray(arr.size(), topicInfoCls, nullptr); if (!jarr) { return nullptr; @@ -601,7 +601,7 @@ JNIEXPORT jint JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_getTopic (JNIEnv* env, jclass, jint inst, jstring name) { - return nt::GetTopic(inst, JStringRef{env, name}); + return wpi::nt::GetTopic(inst, JStringRef{env, name}); } /* @@ -613,7 +613,7 @@ JNIEXPORT jstring JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_getTopicName (JNIEnv* env, jclass, jint topic) { - return MakeJString(env, nt::GetTopicName(topic)); + return MakeJString(env, wpi::nt::GetTopicName(topic)); } /* @@ -625,7 +625,7 @@ JNIEXPORT jint JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_getTopicType (JNIEnv*, jclass, jint topic) { - return nt::GetTopicType(topic); + return wpi::nt::GetTopicType(topic); } /* @@ -637,7 +637,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_setTopicPersistent (JNIEnv*, jclass, jint topic, jboolean value) { - nt::SetTopicPersistent(topic, value); + wpi::nt::SetTopicPersistent(topic, value); } /* @@ -649,7 +649,7 @@ JNIEXPORT jboolean JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_getTopicPersistent (JNIEnv*, jclass, jint topic) { - return nt::GetTopicPersistent(topic); + return wpi::nt::GetTopicPersistent(topic); } /* @@ -661,7 +661,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_setTopicRetained (JNIEnv*, jclass, jint topic, jboolean value) { - nt::SetTopicRetained(topic, value); + wpi::nt::SetTopicRetained(topic, value); } /* @@ -673,7 +673,7 @@ JNIEXPORT jboolean JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_getTopicRetained (JNIEnv*, jclass, jint topic) { - return nt::GetTopicRetained(topic); + return wpi::nt::GetTopicRetained(topic); } /* @@ -685,7 +685,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_setTopicCached (JNIEnv*, jclass, jint topic, jboolean value) { - nt::SetTopicCached(topic, value); + wpi::nt::SetTopicCached(topic, value); } /* @@ -697,7 +697,7 @@ JNIEXPORT jboolean JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_getTopicCached (JNIEnv*, jclass, jint topic) { - return nt::GetTopicCached(topic); + return wpi::nt::GetTopicCached(topic); } /* @@ -709,7 +709,7 @@ JNIEXPORT jstring JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_getTopicTypeString (JNIEnv* env, jclass, jint topic) { - return MakeJString(env, nt::GetTopicTypeString(topic)); + return MakeJString(env, wpi::nt::GetTopicTypeString(topic)); } /* @@ -721,7 +721,7 @@ JNIEXPORT jboolean JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_getTopicExists (JNIEnv*, jclass, jint topic) { - return nt::GetTopicExists(topic); + return wpi::nt::GetTopicExists(topic); } /* @@ -734,7 +734,7 @@ Java_org_wpilib_networktables_NetworkTablesJNI_getTopicProperty (JNIEnv* env, jclass, jint topic, jstring name) { return MakeJString(env, - nt::GetTopicProperty(topic, JStringRef{env, name}).dump()); + wpi::nt::GetTopicProperty(topic, JStringRef{env, name}).dump()); } /* @@ -746,15 +746,15 @@ JNIEXPORT void JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_setTopicProperty (JNIEnv* env, jclass, jint topic, jstring name, jstring value) { - wpi::json j; + wpi::util::json j; try { - j = wpi::json::parse(std::string_view{JStringRef{env, value}}); - } catch (wpi::json::parse_error& err) { + j = wpi::util::json::parse(std::string_view{JStringRef{env, value}}); + } catch (wpi::util::json::parse_error& err) { illegalArgEx.Throw( env, fmt::format("could not parse value JSON: {}", err.what())); return; } - nt::SetTopicProperty(topic, JStringRef{env, name}, j); + wpi::nt::SetTopicProperty(topic, JStringRef{env, name}, j); } /* @@ -766,7 +766,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_deleteTopicProperty (JNIEnv* env, jclass, jint topic, jstring name) { - nt::DeleteTopicProperty(topic, JStringRef{env, name}); + wpi::nt::DeleteTopicProperty(topic, JStringRef{env, name}); } /* @@ -778,7 +778,7 @@ JNIEXPORT jstring JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_getTopicProperties (JNIEnv* env, jclass, jint topic) { - return MakeJString(env, nt::GetTopicProperties(topic).dump()); + return MakeJString(env, wpi::nt::GetTopicProperties(topic).dump()); } /* @@ -790,10 +790,10 @@ JNIEXPORT void JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_setTopicProperties (JNIEnv* env, jclass, jint topic, jstring properties) { - wpi::json j; + wpi::util::json j; try { - j = wpi::json::parse(std::string_view{JStringRef{env, properties}}); - } catch (wpi::json::parse_error& err) { + j = wpi::util::json::parse(std::string_view{JStringRef{env, properties}}); + } catch (wpi::util::json::parse_error& err) { illegalArgEx.Throw( env, fmt::format("could not parse properties JSON: {}", err.what())); return; @@ -802,7 +802,7 @@ Java_org_wpilib_networktables_NetworkTablesJNI_setTopicProperties illegalArgEx.Throw(env, "properties is not a JSON object"); return; } - nt::SetTopicProperties(topic, j); + wpi::nt::SetTopicProperties(topic, j); } /* @@ -814,7 +814,7 @@ JNIEXPORT jint JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_subscribe (JNIEnv* env, jclass, jint topic, jint type, jstring typeStr, jobject options) { - return nt::Subscribe(topic, static_cast(type), + return wpi::nt::Subscribe(topic, static_cast(type), JStringRef{env, typeStr}, FromJavaPubSubOptions(env, options)); } @@ -828,7 +828,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_unsubscribe (JNIEnv*, jclass, jint sub) { - nt::Unsubscribe(sub); + wpi::nt::Unsubscribe(sub); } /* @@ -840,7 +840,7 @@ JNIEXPORT jint JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_publish (JNIEnv* env, jclass, jint topic, jint type, jstring typeStr, jobject options) { - return nt::Publish(topic, static_cast(type), + return wpi::nt::Publish(topic, static_cast(type), JStringRef{env, typeStr}, FromJavaPubSubOptions(env, options)); } @@ -855,10 +855,10 @@ Java_org_wpilib_networktables_NetworkTablesJNI_publishEx (JNIEnv* env, jclass, jint topic, jint type, jstring typeStr, jstring properties, jobject options) { - wpi::json j; + wpi::util::json j; try { - j = wpi::json::parse(std::string_view{JStringRef{env, properties}}); - } catch (wpi::json::parse_error& err) { + j = wpi::util::json::parse(std::string_view{JStringRef{env, properties}}); + } catch (wpi::util::json::parse_error& err) { illegalArgEx.Throw( env, fmt::format("could not parse properties JSON: {}", err.what())); return 0; @@ -867,7 +867,7 @@ Java_org_wpilib_networktables_NetworkTablesJNI_publishEx illegalArgEx.Throw(env, "properties is not a JSON object"); return 0; } - return nt::PublishEx(topic, static_cast(type), + return wpi::nt::PublishEx(topic, static_cast(type), JStringRef{env, typeStr}, j, FromJavaPubSubOptions(env, options)); } @@ -881,7 +881,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_unpublish (JNIEnv*, jclass, jint pubentry) { - nt::Unpublish(pubentry); + wpi::nt::Unpublish(pubentry); } /* @@ -893,7 +893,7 @@ JNIEXPORT jint JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_getEntryImpl (JNIEnv* env, jclass, jint topic, jint type, jstring typeStr, jobject options) { - return nt::GetEntry(topic, static_cast(type), + return wpi::nt::GetEntry(topic, static_cast(type), JStringRef{env, typeStr}, FromJavaPubSubOptions(env, options)); } @@ -907,7 +907,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_releaseEntry (JNIEnv*, jclass, jint entry) { - nt::ReleaseEntry(entry); + wpi::nt::ReleaseEntry(entry); } /* @@ -919,7 +919,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_release (JNIEnv*, jclass, jint pubsubentry) { - nt::Release(pubsubentry); + wpi::nt::Release(pubsubentry); } /* @@ -931,7 +931,7 @@ JNIEXPORT jint JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_getTopicFromHandle (JNIEnv*, jclass, jint pubsubentry) { - return nt::GetTopicFromHandle(pubsubentry); + return wpi::nt::GetTopicFromHandle(pubsubentry); } /* @@ -964,7 +964,7 @@ Java_org_wpilib_networktables_NetworkTablesJNI_subscribeMultiple prefixStringViews.emplace_back(prefixStrings.back()); } - return nt::SubscribeMultiple(inst, prefixStringViews, + return wpi::nt::SubscribeMultiple(inst, prefixStringViews, FromJavaPubSubOptions(env, options)); } @@ -977,7 +977,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_unsubscribeMultiple (JNIEnv*, jclass, jint sub) { - nt::UnsubscribeMultiple(sub); + wpi::nt::UnsubscribeMultiple(sub); } /* @@ -989,7 +989,7 @@ JNIEXPORT jobjectArray JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_readQueueValue (JNIEnv* env, jclass, jint subentry) { - return MakeJObject(env, nt::ReadQueueValue(subentry)); + return MakeJObject(env, wpi::nt::ReadQueueValue(subentry)); } /* @@ -1001,7 +1001,7 @@ JNIEXPORT jobject JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_getValue (JNIEnv* env, jclass, jint entry) { - return MakeJValue(env, nt::GetEntryValue(entry)); + return MakeJValue(env, wpi::nt::GetEntryValue(entry)); } /* @@ -1013,7 +1013,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_setEntryFlags (JNIEnv*, jclass, jint entry, jint flags) { - nt::SetEntryFlags(entry, flags); + wpi::nt::SetEntryFlags(entry, flags); } /* @@ -1025,7 +1025,7 @@ JNIEXPORT jint JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_getEntryFlags (JNIEnv*, jclass, jint entry) { - return nt::GetEntryFlags(entry); + return wpi::nt::GetEntryFlags(entry); } /* @@ -1037,7 +1037,7 @@ JNIEXPORT jobject JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_getTopicInfo (JNIEnv* env, jclass, jobject inst, jint topic) { - return MakeJObject(env, inst, nt::GetTopicInfo(topic)); + return MakeJObject(env, inst, wpi::nt::GetTopicInfo(topic)); } /* @@ -1049,7 +1049,7 @@ JNIEXPORT jint JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_createListenerPoller (JNIEnv*, jclass, jint inst) { - return nt::CreateListenerPoller(inst); + return wpi::nt::CreateListenerPoller(inst); } /* @@ -1061,7 +1061,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_destroyListenerPoller (JNIEnv*, jclass, jint poller) { - nt::DestroyListenerPoller(poller); + wpi::nt::DestroyListenerPoller(poller); } /* @@ -1095,7 +1095,7 @@ Java_org_wpilib_networktables_NetworkTablesJNI_addListener__I_3Ljava_lang_String arrview.emplace_back(arr.back()); } - return nt::AddPolledListener(poller, arrview, flags); + return wpi::nt::AddPolledListener(poller, arrview, flags); } /* @@ -1107,7 +1107,7 @@ JNIEXPORT jint JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_addListener__III (JNIEnv* env, jclass, jint poller, jint handle, jint flags) { - return nt::AddPolledListener(poller, handle, flags); + return wpi::nt::AddPolledListener(poller, handle, flags); } /* @@ -1119,7 +1119,7 @@ JNIEXPORT jobjectArray JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_readListenerQueue (JNIEnv* env, jclass, jobject inst, jint poller) { - return MakeJObject(env, inst, nt::ReadListenerQueue(poller)); + return MakeJObject(env, inst, wpi::nt::ReadListenerQueue(poller)); } /* @@ -1131,7 +1131,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_removeListener (JNIEnv*, jclass, jint topicListener) { - nt::RemoveListener(topicListener); + wpi::nt::RemoveListener(topicListener); } /* @@ -1143,7 +1143,7 @@ JNIEXPORT jint JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_getNetworkMode (JNIEnv*, jclass, jint inst) { - return nt::GetNetworkMode(inst); + return wpi::nt::GetNetworkMode(inst); } /* @@ -1155,7 +1155,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_startLocal (JNIEnv*, jclass, jint inst) { - nt::StartLocal(inst); + wpi::nt::StartLocal(inst); } /* @@ -1167,7 +1167,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_stopLocal (JNIEnv*, jclass, jint inst) { - nt::StopLocal(inst); + wpi::nt::StopLocal(inst); } /* @@ -1188,7 +1188,7 @@ Java_org_wpilib_networktables_NetworkTablesJNI_startServer nullPointerEx.Throw(env, "listenAddress cannot be null"); return; } - nt::StartServer(inst, JStringRef{env, persistFilename}.str(), + wpi::nt::StartServer(inst, JStringRef{env, persistFilename}.str(), JStringRef{env, listenAddress}.c_str(), port); } @@ -1201,7 +1201,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_stopServer (JNIEnv*, jclass, jint inst) { - nt::StopServer(inst); + wpi::nt::StopServer(inst); } /* @@ -1217,7 +1217,7 @@ Java_org_wpilib_networktables_NetworkTablesJNI_startClient nullPointerEx.Throw(env, "identity cannot be null"); return; } - nt::StartClient(inst, JStringRef{env, identity}.str()); + wpi::nt::StartClient(inst, JStringRef{env, identity}.str()); } /* @@ -1229,7 +1229,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_stopClient (JNIEnv*, jclass, jint inst) { - nt::StopClient(inst); + wpi::nt::StopClient(inst); } /* @@ -1245,7 +1245,7 @@ Java_org_wpilib_networktables_NetworkTablesJNI_setServer__ILjava_lang_String_2I nullPointerEx.Throw(env, "serverName cannot be null"); return; } - nt::SetServer(inst, JStringRef{env, serverName}.c_str(), port); + wpi::nt::SetServer(inst, JStringRef{env, serverName}.c_str(), port); } /* @@ -1291,7 +1291,7 @@ Java_org_wpilib_networktables_NetworkTablesJNI_setServer__I_3Ljava_lang_String_2 servers.emplace_back( std::pair{std::string_view{names.back()}, portInts[i]}); } - nt::SetServer(inst, servers); + wpi::nt::SetServer(inst, servers); } /* @@ -1303,7 +1303,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_setServerTeam (JNIEnv* env, jclass, jint inst, jint team, jint port) { - nt::SetServerTeam(inst, team, port); + wpi::nt::SetServerTeam(inst, team, port); } /* @@ -1315,7 +1315,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_disconnect (JNIEnv* env, jclass, jint inst) { - nt::Disconnect(inst); + wpi::nt::Disconnect(inst); } /* @@ -1327,7 +1327,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_startDSClient (JNIEnv*, jclass, jint inst, jint port) { - nt::StartDSClient(inst, port); + wpi::nt::StartDSClient(inst, port); } /* @@ -1339,7 +1339,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_stopDSClient (JNIEnv*, jclass, jint inst) { - nt::StopDSClient(inst); + wpi::nt::StopDSClient(inst); } /* @@ -1351,7 +1351,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_flushLocal (JNIEnv*, jclass, jint inst) { - nt::FlushLocal(inst); + wpi::nt::FlushLocal(inst); } /* @@ -1363,7 +1363,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_flush (JNIEnv*, jclass, jint inst) { - nt::Flush(inst); + wpi::nt::Flush(inst); } /* @@ -1375,7 +1375,7 @@ JNIEXPORT jobjectArray JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_getConnections (JNIEnv* env, jclass, jint inst) { - auto arr = nt::GetConnections(inst); + auto arr = wpi::nt::GetConnections(inst); jobjectArray jarr = env->NewObjectArray(arr.size(), connectionInfoCls, nullptr); if (!jarr) { @@ -1397,7 +1397,7 @@ JNIEXPORT jboolean JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_isConnected (JNIEnv*, jclass, jint inst) { - return nt::IsConnected(inst); + return wpi::nt::IsConnected(inst); } /* @@ -1409,7 +1409,7 @@ JNIEXPORT jobject JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_getServerTimeOffset (JNIEnv* env, jclass, jint inst) { - return MakeJObject(env, nt::GetServerTimeOffset(inst)); + return MakeJObject(env, wpi::nt::GetServerTimeOffset(inst)); } /* @@ -1421,7 +1421,7 @@ JNIEXPORT jlong JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_now (JNIEnv*, jclass) { - return nt::Now(); + return wpi::nt::Now(); } /* @@ -1433,7 +1433,7 @@ JNIEXPORT jint JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_startEntryDataLog (JNIEnv* env, jclass, jint inst, jlong log, jstring prefix, jstring logPrefix) { - return nt::StartEntryDataLog(inst, *reinterpret_cast(log), + return wpi::nt::StartEntryDataLog(inst, *reinterpret_cast(log), JStringRef{env, prefix}, JStringRef{env, logPrefix}); } @@ -1447,7 +1447,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_stopEntryDataLog (JNIEnv*, jclass, jint logger) { - nt::StopEntryDataLog(logger); + wpi::nt::StopEntryDataLog(logger); } /* @@ -1459,7 +1459,7 @@ JNIEXPORT jint JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_startConnectionDataLog (JNIEnv* env, jclass, jint inst, jlong log, jstring name) { - return nt::StartConnectionDataLog( + return wpi::nt::StartConnectionDataLog( inst, *reinterpret_cast(log), JStringRef{env, name}); } @@ -1472,7 +1472,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_stopConnectionDataLog (JNIEnv*, jclass, jint logger) { - nt::StopConnectionDataLog(logger); + wpi::nt::StopConnectionDataLog(logger); } /* @@ -1484,7 +1484,7 @@ JNIEXPORT jint JNICALL Java_org_wpilib_networktables_NetworkTablesJNI_addLogger (JNIEnv*, jclass, jint poller, jint minLevel, jint maxLevel) { - return nt::AddPolledLogger(poller, minLevel, maxLevel); + return wpi::nt::AddPolledLogger(poller, minLevel, maxLevel); } } // extern "C" diff --git a/ntcore/src/main/native/cpp/local/LocalDataLogger.cpp b/ntcore/src/main/native/cpp/local/LocalDataLogger.cpp index d3fd1095df..d8d73caaef 100644 --- a/ntcore/src/main/native/cpp/local/LocalDataLogger.cpp +++ b/ntcore/src/main/native/cpp/local/LocalDataLogger.cpp @@ -9,7 +9,7 @@ #include "wpi/datalog/DataLog.hpp" #include "wpi/util/StringExtras.hpp" -using namespace nt::local; +using namespace wpi::nt::local; int LocalDataLogger::Start(std::string_view name, std::string_view typeStr, std::string_view metadata, int64_t time) { @@ -20,6 +20,6 @@ int LocalDataLogger::Start(std::string_view name, std::string_view typeStr, typeStr = "int64[]"; } return log.Start(fmt::format("{}{}", logPrefix, - wpi::remove_prefix(name, prefix).value_or(name)), + wpi::util::remove_prefix(name, prefix).value_or(name)), typeStr, metadata, time); } diff --git a/ntcore/src/main/native/cpp/local/LocalDataLogger.hpp b/ntcore/src/main/native/cpp/local/LocalDataLogger.hpp index 1f13bcb6d1..2b73ba9a09 100644 --- a/ntcore/src/main/native/cpp/local/LocalDataLogger.hpp +++ b/ntcore/src/main/native/cpp/local/LocalDataLogger.hpp @@ -16,7 +16,7 @@ namespace wpi::log { class DataLog; } // namespace wpi::log -namespace nt::local { +namespace wpi::nt::local { struct LocalTopic; @@ -36,4 +36,4 @@ struct LocalDataLogger { std::string logPrefix; }; -} // namespace nt::local +} // namespace wpi::nt::local diff --git a/ntcore/src/main/native/cpp/local/LocalDataLoggerEntry.cpp b/ntcore/src/main/native/cpp/local/LocalDataLoggerEntry.cpp index 36c0a43391..dda58a02ef 100644 --- a/ntcore/src/main/native/cpp/local/LocalDataLoggerEntry.cpp +++ b/ntcore/src/main/native/cpp/local/LocalDataLoggerEntry.cpp @@ -12,7 +12,7 @@ #include "wpi/nt/NetworkTableValue.hpp" #include "wpi/util/StringExtras.hpp" -using namespace nt::local; +using namespace wpi::nt::local; std::string LocalDataLoggerEntry::MakeMetadata(std::string_view properties) { return fmt::format("{{\"properties\":{},\"source\":\"NT\"}}", properties); diff --git a/ntcore/src/main/native/cpp/local/LocalDataLoggerEntry.hpp b/ntcore/src/main/native/cpp/local/LocalDataLoggerEntry.hpp index ad89746a5e..c97cb880d2 100644 --- a/ntcore/src/main/native/cpp/local/LocalDataLoggerEntry.hpp +++ b/ntcore/src/main/native/cpp/local/LocalDataLoggerEntry.hpp @@ -16,11 +16,11 @@ namespace wpi::log { class DataLog; } // namespace wpi::log -namespace nt { +namespace wpi::nt { class Value; -} // namespace nt +} // namespace wpi::nt -namespace nt::local { +namespace wpi::nt::local { struct LocalTopic; @@ -41,4 +41,4 @@ struct LocalDataLoggerEntry { NT_DataLogger logger; }; -} // namespace nt::local +} // namespace wpi::nt::local diff --git a/ntcore/src/main/native/cpp/local/LocalEntry.hpp b/ntcore/src/main/native/cpp/local/LocalEntry.hpp index 876779a373..0ef9d45bb6 100644 --- a/ntcore/src/main/native/cpp/local/LocalEntry.hpp +++ b/ntcore/src/main/native/cpp/local/LocalEntry.hpp @@ -8,7 +8,7 @@ #include "local/LocalSubscriber.hpp" #include "wpi/util/Synchronization.h" -namespace nt::local { +namespace wpi::nt::local { struct LocalPublisher; @@ -19,7 +19,7 @@ struct LocalEntry { : handle{handle}, topic{subscriber->topic}, subscriber{subscriber} {} // invariants - wpi::SignalObject handle; + wpi::util::SignalObject handle; LocalTopic* topic; LocalSubscriber* subscriber; @@ -27,4 +27,4 @@ struct LocalEntry { LocalPublisher* publisher{nullptr}; }; -} // namespace nt::local +} // namespace wpi::nt::local diff --git a/ntcore/src/main/native/cpp/local/LocalListener.hpp b/ntcore/src/main/native/cpp/local/LocalListener.hpp index 12485c14ce..6dc1cff9e7 100644 --- a/ntcore/src/main/native/cpp/local/LocalListener.hpp +++ b/ntcore/src/main/native/cpp/local/LocalListener.hpp @@ -6,7 +6,7 @@ #include "wpi/nt/ntcore_c.h" -namespace nt::local { +namespace wpi::nt::local { struct LocalMultiSubscriber; struct LocalSubscriber; @@ -32,4 +32,4 @@ struct LocalListener { bool subscriberOwned; }; -} // namespace nt::local +} // namespace wpi::nt::local diff --git a/ntcore/src/main/native/cpp/local/LocalMultiSubscriber.hpp b/ntcore/src/main/native/cpp/local/LocalMultiSubscriber.hpp index 04b821caad..ed75ecb2a2 100644 --- a/ntcore/src/main/native/cpp/local/LocalMultiSubscriber.hpp +++ b/ntcore/src/main/native/cpp/local/LocalMultiSubscriber.hpp @@ -16,11 +16,11 @@ #include "wpi/util/StringExtras.hpp" #include "wpi/util/Synchronization.h" -namespace nt::local { +namespace wpi::nt::local { constexpr bool PrefixMatch(std::string_view name, std::string_view prefix, bool special) { - return (!special || !prefix.empty()) && wpi::starts_with(name, prefix); + return (!special || !prefix.empty()) && wpi::util::starts_with(name, prefix); } struct LocalMultiSubscriber { @@ -47,7 +47,7 @@ struct LocalMultiSubscriber { } // invariants - wpi::SignalObject handle; + wpi::util::SignalObject handle; std::vector prefixes; PubSubOptionsImpl options; @@ -55,4 +55,4 @@ struct LocalMultiSubscriber { VectorSet valueListeners; }; -} // namespace nt::local +} // namespace wpi::nt::local diff --git a/ntcore/src/main/native/cpp/local/LocalPublisher.hpp b/ntcore/src/main/native/cpp/local/LocalPublisher.hpp index 68cdd38919..bc763f0cab 100644 --- a/ntcore/src/main/native/cpp/local/LocalPublisher.hpp +++ b/ntcore/src/main/native/cpp/local/LocalPublisher.hpp @@ -11,7 +11,7 @@ #include "local/PubSubConfig.hpp" #include "wpi/util/Synchronization.h" -namespace nt::local { +namespace wpi::nt::local { struct LocalPublisher { static constexpr auto kType = Handle::kPublisher; @@ -24,7 +24,7 @@ struct LocalPublisher { } // invariants - wpi::SignalObject handle; + wpi::util::SignalObject handle; LocalTopic* topic; PubSubConfig config; @@ -32,4 +32,4 @@ struct LocalPublisher { bool active{false}; }; -} // namespace nt::local +} // namespace wpi::nt::local diff --git a/ntcore/src/main/native/cpp/local/LocalStorageImpl.cpp b/ntcore/src/main/native/cpp/local/LocalStorageImpl.cpp index d12bdef4dc..b444cebbd9 100644 --- a/ntcore/src/main/native/cpp/local/LocalStorageImpl.cpp +++ b/ntcore/src/main/native/cpp/local/LocalStorageImpl.cpp @@ -19,8 +19,8 @@ #include "wpi/util/SmallString.hpp" #include "wpi/util/StringExtras.hpp" -using namespace nt; -using namespace nt::local; +using namespace wpi::nt; +using namespace wpi::nt::local; // maximum number of local publishers / subscribers to any given topic static constexpr size_t kMaxPublishers = 512; @@ -29,7 +29,7 @@ static constexpr size_t kMaxMultiSubscribers = 512; static constexpr size_t kMaxListeners = 512; StorageImpl::StorageImpl(int inst, IListenerStorage& listenerStorage, - wpi::Logger& logger) + wpi::util::Logger& logger) : m_inst{inst}, m_listenerStorage{listenerStorage}, m_logger{logger} {} // @@ -37,7 +37,7 @@ StorageImpl::StorageImpl(int inst, IListenerStorage& listenerStorage, // void StorageImpl::NetworkAnnounce(LocalTopic* topic, std::string_view typeStr, - const wpi::json& properties, + const wpi::util::json& properties, std::optional pubuid) { DEBUG4("LS NetworkAnnounce({}, {}, {}, {})", topic->name, typeStr, properties.dump(), pubuid.value_or(-1)); @@ -68,7 +68,7 @@ void StorageImpl::NetworkAnnounce(LocalTopic* topic, std::string_view typeStr, // may be properties update, but need to compare to see if it actually // changed to determine whether to update string / send event - wpi::json update = topic->CompareProperties(properties); + wpi::util::json update = topic->CompareProperties(properties); if (!update.empty()) { topic->properties = properties; PropertiesUpdated(topic, update, event, false); @@ -110,7 +110,7 @@ void StorageImpl::RemoveNetworkPublisher(LocalTopic* topic) { } void StorageImpl::NetworkPropertiesUpdate(LocalTopic* topic, - const wpi::json& update, bool ack) { + const wpi::util::json& update, bool ack) { DEBUG4("NetworkPropertiesUpdate({},{})", topic->name, ack); if (ack) { return; // ignore acks @@ -185,7 +185,7 @@ LocalTopic* StorageImpl::GetOrCreateTopic(std::string_view name) { // void StorageImpl::SetFlags(LocalTopic* topic, unsigned int flags) { - wpi::json update = topic->SetFlags(flags); + wpi::util::json update = topic->SetFlags(flags); if ((flags & NT_UNCACHED) != 0 && (flags & NT_PERSISTENT) != 0) { WARN("topic {}: disabling cached property disables persistent storage", topic->name); @@ -210,12 +210,12 @@ void StorageImpl::SetCached(LocalTopic* topic, bool value) { } void StorageImpl::SetProperty(LocalTopic* topic, std::string_view name, - const wpi::json& value) { + const wpi::util::json& value) { PropertiesUpdated(topic, topic->SetProperty(name, value), NT_EVENT_NONE, true); } -bool StorageImpl::SetProperties(LocalTopic* topic, const wpi::json& update, +bool StorageImpl::SetProperties(LocalTopic* topic, const wpi::util::json& update, bool sendNetwork) { DEBUG4("SetProperties({},{})", topic->name, sendNetwork); if (!topic->SetProperties(update)) { @@ -316,7 +316,7 @@ LocalSubscriber* StorageImpl::Subscribe(LocalTopic* topic, NT_Type type, LocalPublisher* StorageImpl::Publish(LocalTopic* topic, NT_Type type, std::string_view typeStr, - const wpi::json& properties, + const wpi::util::json& properties, const PubSubOptions& options) { if (type == NT_UNASSIGNED || typeStr.empty()) { ERR("cannot publish '{}' with an unassigned type or empty type string", @@ -589,7 +589,7 @@ void StorageImpl::AddListenerImpl(NT_Listener listenerHandle, .get(); // if we're doing anything immediate, get the list of matching topics - wpi::SmallVector topics; + wpi::util::SmallVector topics; if ((eventMask & NT_EVENT_IMMEDIATE) != 0 && (eventMask & (NT_EVENT_PUBLISH | NT_EVENT_VALUE_ALL)) != 0) { for (auto&& topic : m_topics) { @@ -695,7 +695,7 @@ LocalDataLogger* StorageImpl::StartDataLog(wpi::log::DataLog& log, auto datalogger = m_dataloggers.Add(m_inst, log, prefix, logPrefix); // start logging any matching topics - auto now = nt::Now(); + auto now = wpi::nt::Now(); for (auto&& topic : m_topics) { if (!PrefixMatch(topic->name, prefix, topic->special) || topic->type == NT_UNASSIGNED || topic->typeStr.empty()) { @@ -726,7 +726,7 @@ void StorageImpl::StopDataLog(NT_DataLogger logger) { // bool StorageImpl::HasSchema(std::string_view name) { - wpi::SmallString<128> fullName{"/.schema/"}; + wpi::util::SmallString<128> fullName{"/.schema/"}; fullName += name; auto it = m_schemas.find(fullName); return it != m_schemas.end(); @@ -734,7 +734,7 @@ bool StorageImpl::HasSchema(std::string_view name) { void StorageImpl::AddSchema(std::string_view name, std::string_view type, std::span schema) { - wpi::SmallString<128> fullName{"/.schema/"}; + wpi::util::SmallString<128> fullName{"/.schema/"}; fullName += name; auto& pubHandle = m_schemas[fullName]; if (pubHandle != 0) { @@ -776,7 +776,7 @@ void StorageImpl::NotifyTopic(LocalTopic* topic, unsigned int eventFlags) { m_listenerStorage.Notify(topic->listeners, eventFlags, topicInfo); } - wpi::SmallVector listeners; + wpi::util::SmallVector listeners; for (auto listener : m_topicPrefixListeners) { if (listener->multiSubscriber && listener->multiSubscriber->Matches(topic->name, topic->special)) { @@ -864,7 +864,7 @@ void StorageImpl::NotifyValue(LocalTopic* topic, const Value& value, } } -void StorageImpl::PropertiesUpdated(LocalTopic* topic, const wpi::json& update, +void StorageImpl::PropertiesUpdated(LocalTopic* topic, const wpi::util::json& update, unsigned int eventFlags, bool sendNetwork, bool updateFlags) { DEBUG4("PropertiesUpdated({}, {}, {}, {}, {})", topic->name, update.dump(), @@ -902,7 +902,7 @@ void StorageImpl::RefreshPubSubActive(LocalTopic* topic, } LocalPublisher* StorageImpl::AddLocalPublisher(LocalTopic* topic, - const wpi::json& properties, + const wpi::util::json& properties, const PubSubConfig& config) { bool didExist = topic->Exists(); auto publisher = m_publishers.Add(m_inst, topic, config); @@ -917,12 +917,12 @@ LocalPublisher* StorageImpl::AddLocalPublisher(LocalTopic* topic, RefreshPubSubActive(topic, true); if (properties.is_null()) { - topic->properties = wpi::json::object(); + topic->properties = wpi::util::json::object(); } else if (properties.is_object()) { topic->properties = properties; } else { WARN("ignoring non-object properties when publishing '{}'", topic->name); - topic->properties = wpi::json::object(); + topic->properties = wpi::util::json::object(); } if (topic->properties.empty()) { @@ -1054,7 +1054,7 @@ LocalPublisher* StorageImpl::PublishEntry(LocalEntry* entry, NT_Type type) { } } // create publisher - entry->publisher = AddLocalPublisher(entry->topic, wpi::json::object(), + entry->publisher = AddLocalPublisher(entry->topic, wpi::util::json::object(), entry->subscriber->config); // exclude publisher if requested if (entry->subscriber->config.excludeSelf) { diff --git a/ntcore/src/main/native/cpp/local/LocalStorageImpl.hpp b/ntcore/src/main/native/cpp/local/LocalStorageImpl.hpp index 7f248321a1..530002c51c 100644 --- a/ntcore/src/main/native/cpp/local/LocalStorageImpl.hpp +++ b/ntcore/src/main/native/cpp/local/LocalStorageImpl.hpp @@ -24,35 +24,35 @@ #include "wpi/util/Synchronization.h" #include "wpi/util/json.hpp" -namespace wpi { +namespace wpi::util { class Logger; } // namespace wpi -namespace nt { +namespace wpi::nt { class IListenerStorage; -} // namespace nt +} // namespace wpi::nt -namespace nt::net { +namespace wpi::nt::net { class ClientMessageHandler; -} // namespace nt::net +} // namespace wpi::nt::net -namespace nt::local { +namespace wpi::nt::local { // inner struct to protect against accidentally deadlocking on the mutex class StorageImpl { public: - StorageImpl(int inst, IListenerStorage& listenerStorage, wpi::Logger& logger); + StorageImpl(int inst, IListenerStorage& listenerStorage, wpi::util::Logger& logger); - wpi::Logger& GetLogger() { return m_logger; } + wpi::util::Logger& GetLogger() { return m_logger; } // // Network interface functions // void NetworkAnnounce(LocalTopic* topic, std::string_view typeStr, - const wpi::json& properties, std::optional pubuid); + const wpi::util::json& properties, std::optional pubuid); void RemoveNetworkPublisher(LocalTopic* topic); - void NetworkPropertiesUpdate(LocalTopic* topic, const wpi::json& update, + void NetworkPropertiesUpdate(LocalTopic* topic, const wpi::util::json& update, bool ack); void ServerSetValue(LocalTopic* topic, const Value& value) { @@ -80,7 +80,7 @@ class StorageImpl { if (!topic->Exists()) { continue; } - if (!wpi::starts_with(topic->name, prefix)) { + if (!wpi::util::starts_with(topic->name, prefix)) { continue; } if (types != 0 && (types & topic->type) == 0) { @@ -97,7 +97,7 @@ class StorageImpl { if (!topic->Exists()) { continue; } - if (!wpi::starts_with(topic->name, prefix)) { + if (!wpi::util::starts_with(topic->name, prefix)) { continue; } if (!types.empty()) { @@ -126,8 +126,8 @@ class StorageImpl { void SetCached(LocalTopic* topic, bool value); void SetProperty(LocalTopic* topic, std::string_view name, - const wpi::json& value); - bool SetProperties(LocalTopic* topic, const wpi::json& update, + const wpi::util::json& value); + bool SetProperties(LocalTopic* topic, const wpi::util::json& update, bool sendNetwork); void DeleteProperty(LocalTopic* topic, std::string_view name); @@ -156,7 +156,7 @@ class StorageImpl { const PubSubOptions& options); LocalPublisher* Publish(LocalTopic* topic, NT_Type type, - std::string_view typeStr, const wpi::json& properties, + std::string_view typeStr, const wpi::util::json& properties, const PubSubOptions& options); LocalEntry* GetEntry(LocalTopic* topicHandle, NT_Type type, @@ -252,14 +252,14 @@ class StorageImpl { unsigned int eventFlags, bool isDuplicate, const LocalPublisher* publisher); - void PropertiesUpdated(LocalTopic* topic, const wpi::json& update, + void PropertiesUpdated(LocalTopic* topic, const wpi::util::json& update, unsigned int eventFlags, bool sendNetwork, bool updateFlags = true); void RefreshPubSubActive(LocalTopic* topic, bool warnOnSubMismatch); LocalPublisher* AddLocalPublisher(LocalTopic* topic, - const wpi::json& properties, + const wpi::util::json& properties, const PubSubConfig& options); std::unique_ptr RemoveLocalPublisher(NT_Publisher pubHandle); @@ -292,7 +292,7 @@ class StorageImpl { private: int m_inst; IListenerStorage& m_listenerStorage; - wpi::Logger& m_logger; + wpi::util::Logger& m_logger; net::ClientMessageHandler* m_network{nullptr}; // handle mappings @@ -304,16 +304,16 @@ class StorageImpl { HandleMap m_dataloggers; // name mappings - wpi::StringMap m_nameTopics; + wpi::util::StringMap m_nameTopics; // listeners - wpi::DenseMap> m_listeners; + wpi::util::DenseMap> m_listeners; // string-based listeners VectorSet m_topicPrefixListeners; // schema publishers - wpi::StringMap m_schemas; + wpi::util::StringMap m_schemas; }; -} // namespace nt::local +} // namespace wpi::nt::local diff --git a/ntcore/src/main/native/cpp/local/LocalSubscriber.hpp b/ntcore/src/main/native/cpp/local/LocalSubscriber.hpp index 2b4e8379df..6744987afd 100644 --- a/ntcore/src/main/native/cpp/local/LocalSubscriber.hpp +++ b/ntcore/src/main/native/cpp/local/LocalSubscriber.hpp @@ -15,7 +15,7 @@ #include "wpi/nt/ntcore_c.h" #include "wpi/util/Synchronization.h" -namespace nt::local { +namespace wpi::nt::local { struct LocalSubscriber { static constexpr auto kType = Handle::kSubscriber; @@ -35,7 +35,7 @@ struct LocalSubscriber { } // invariants - wpi::SignalObject handle; + wpi::util::SignalObject handle; LocalTopic* topic; PubSubConfig config; @@ -49,4 +49,4 @@ struct LocalSubscriber { VectorSet valueListeners; }; -} // namespace nt::local +} // namespace wpi::nt::local diff --git a/ntcore/src/main/native/cpp/local/LocalTopic.cpp b/ntcore/src/main/native/cpp/local/LocalTopic.cpp index e280d145df..c13071805c 100644 --- a/ntcore/src/main/native/cpp/local/LocalTopic.cpp +++ b/ntcore/src/main/native/cpp/local/LocalTopic.cpp @@ -8,7 +8,7 @@ #include "local/LocalDataLogger.hpp" -using namespace nt::local; +using namespace wpi::nt::local; void LocalTopic::StartStopDataLog(LocalDataLogger* logger, int64_t timestamp, bool publish) { @@ -40,28 +40,28 @@ void LocalTopic::UpdateDataLogProperties() { } } -wpi::json LocalTopic::SetFlags(unsigned int flags) { - wpi::json update = wpi::json::object(); +wpi::util::json LocalTopic::SetFlags(unsigned int flags) { + wpi::util::json update = wpi::util::json::object(); if ((flags & NT_PERSISTENT) != 0) { properties["persistent"] = true; update["persistent"] = true; } else { properties.erase("persistent"); - update["persistent"] = wpi::json(); + update["persistent"] = wpi::util::json(); } if ((flags & NT_RETAINED) != 0) { properties["retained"] = true; update["retained"] = true; } else { properties.erase("retained"); - update["retained"] = wpi::json(); + update["retained"] = wpi::util::json(); } if ((flags & NT_UNCACHED) != 0) { properties["cached"] = false; update["cached"] = false; } else { properties.erase("cached"); - update["cached"] = wpi::json(); + update["cached"] = wpi::util::json(); } if ((flags & NT_UNCACHED) != 0) { lastValue = {}; @@ -72,8 +72,8 @@ wpi::json LocalTopic::SetFlags(unsigned int flags) { return update; } -wpi::json LocalTopic::SetPersistent(bool value) { - wpi::json update = wpi::json::object(); +wpi::util::json LocalTopic::SetPersistent(bool value) { + wpi::util::json update = wpi::util::json::object(); if (value) { m_flags |= NT_PERSISTENT; properties["persistent"] = true; @@ -81,13 +81,13 @@ wpi::json LocalTopic::SetPersistent(bool value) { } else { m_flags &= ~NT_PERSISTENT; properties.erase("persistent"); - update["persistent"] = wpi::json(); + update["persistent"] = wpi::util::json(); } return update; } -wpi::json LocalTopic::SetRetained(bool value) { - wpi::json update = wpi::json::object(); +wpi::util::json LocalTopic::SetRetained(bool value) { + wpi::util::json update = wpi::util::json::object(); if (value) { m_flags |= NT_RETAINED; properties["retained"] = true; @@ -95,17 +95,17 @@ wpi::json LocalTopic::SetRetained(bool value) { } else { m_flags &= ~NT_RETAINED; properties.erase("retained"); - update["retained"] = wpi::json(); + update["retained"] = wpi::util::json(); } return update; } -wpi::json LocalTopic::SetCached(bool value) { - wpi::json update = wpi::json::object(); +wpi::util::json LocalTopic::SetCached(bool value) { + wpi::util::json update = wpi::util::json::object(); if (value) { m_flags &= ~NT_UNCACHED; properties.erase("cached"); - update["cached"] = wpi::json(); + update["cached"] = wpi::util::json(); } else { m_flags |= NT_UNCACHED; properties["cached"] = false; @@ -114,26 +114,26 @@ wpi::json LocalTopic::SetCached(bool value) { return update; } -wpi::json LocalTopic::SetProperty(std::string_view name, - const wpi::json& value) { +wpi::util::json LocalTopic::SetProperty(std::string_view name, + const wpi::util::json& value) { if (value.is_null()) { properties.erase(name); } else { properties[name] = value; } - wpi::json update = wpi::json::object(); + wpi::util::json update = wpi::util::json::object(); update[name] = value; return update; } -wpi::json LocalTopic::DeleteProperty(std::string_view name) { +wpi::util::json LocalTopic::DeleteProperty(std::string_view name) { properties.erase(name); - wpi::json update = wpi::json::object(); - update[name] = wpi::json(); + wpi::util::json update = wpi::util::json::object(); + update[name] = wpi::util::json(); return update; } -bool LocalTopic::SetProperties(const wpi::json& update) { +bool LocalTopic::SetProperties(const wpi::util::json& update) { if (!update.is_object()) { return false; } @@ -154,8 +154,8 @@ void LocalTopic::RefreshProperties(bool updateFlags) { m_propertiesStr = properties.dump(); } -wpi::json LocalTopic::CompareProperties(const wpi::json props) { - wpi::json update = wpi::json::object(); +wpi::util::json LocalTopic::CompareProperties(const wpi::util::json props) { + wpi::util::json update = wpi::util::json::object(); // added/changed for (auto&& prop : props.items()) { auto it = properties.find(prop.key()); @@ -166,7 +166,7 @@ wpi::json LocalTopic::CompareProperties(const wpi::json props) { // removed for (auto&& prop : properties.items()) { if (props.find(prop.key()) == props.end()) { - update[prop.key()] = wpi::json(); + update[prop.key()] = wpi::util::json(); } } return update; @@ -182,7 +182,7 @@ void LocalTopic::ResetIfDoesNotExist() { type = NT_UNASSIGNED; typeStr.clear(); m_flags = 0; - properties = wpi::json::object(); + properties = wpi::util::json::object(); m_propertiesStr = "{}"; } diff --git a/ntcore/src/main/native/cpp/local/LocalTopic.hpp b/ntcore/src/main/native/cpp/local/LocalTopic.hpp index 087ee16e94..af323de282 100644 --- a/ntcore/src/main/native/cpp/local/LocalTopic.hpp +++ b/ntcore/src/main/native/cpp/local/LocalTopic.hpp @@ -18,7 +18,7 @@ #include "wpi/util/Synchronization.h" #include "wpi/util/json.hpp" -namespace nt::local { +namespace wpi::nt::local { struct LocalDataLogger; struct LocalEntry; @@ -48,20 +48,20 @@ struct LocalTopic { unsigned int GetFlags() const { return m_flags; } // these return update json - wpi::json SetFlags(unsigned int flags); - wpi::json SetPersistent(bool value); - wpi::json SetRetained(bool value); - wpi::json SetCached(bool value); - wpi::json SetProperty(std::string_view name, const wpi::json& value); - wpi::json DeleteProperty(std::string_view name); + wpi::util::json SetFlags(unsigned int flags); + wpi::util::json SetPersistent(bool value); + wpi::util::json SetRetained(bool value); + wpi::util::json SetCached(bool value); + wpi::util::json SetProperty(std::string_view name, const wpi::util::json& value); + wpi::util::json DeleteProperty(std::string_view name); // returns false if not object - bool SetProperties(const wpi::json& update); + bool SetProperties(const wpi::util::json& update); void RefreshProperties(bool updateFlags); // returns update json - wpi::json CompareProperties(const wpi::json props); + wpi::util::json CompareProperties(const wpi::util::json props); TopicInfo GetTopicInfo() const { TopicInfo info; @@ -76,7 +76,7 @@ struct LocalTopic { void ResetIfDoesNotExist(); // invariants - wpi::SignalObject handle; + wpi::util::SignalObject handle; std::string name; bool special; @@ -84,13 +84,13 @@ struct LocalTopic { Value lastValueNetwork; NT_Type type{NT_UNASSIGNED}; std::string typeStr; - wpi::json properties = wpi::json::object(); + wpi::util::json properties = wpi::util::json::object(); LocalEntry* entry{nullptr}; // cached entry for GetEntry() bool onNetwork{false}; // true if there are any remote publishers bool lastValueFromNetwork{false}; - wpi::SmallVector datalogs; + wpi::util::SmallVector datalogs; NT_Type datalogType{NT_UNASSIGNED}; VectorSet localPublishers; @@ -107,4 +107,4 @@ struct LocalTopic { std::string m_propertiesStr{"{}"}; // cached string for GetTopicInfo() et al }; -} // namespace nt::local +} // namespace wpi::nt::local diff --git a/ntcore/src/main/native/cpp/local/PubSubConfig.hpp b/ntcore/src/main/native/cpp/local/PubSubConfig.hpp index 69526cd33b..aeb70be3b6 100644 --- a/ntcore/src/main/native/cpp/local/PubSubConfig.hpp +++ b/ntcore/src/main/native/cpp/local/PubSubConfig.hpp @@ -10,7 +10,7 @@ #include "PubSubOptions.hpp" #include "wpi/nt/ntcore_c.h" -namespace nt::local { +namespace wpi::nt::local { struct PubSubConfig : public PubSubOptionsImpl { PubSubConfig() = default; @@ -24,4 +24,4 @@ struct PubSubConfig : public PubSubOptionsImpl { std::string typeStr; }; -} // namespace nt::local +} // namespace wpi::nt::local diff --git a/ntcore/src/main/native/cpp/net/ClientImpl.cpp b/ntcore/src/main/native/cpp/net/ClientImpl.cpp index 25731449a3..7359aed6f9 100644 --- a/ntcore/src/main/native/cpp/net/ClientImpl.cpp +++ b/ntcore/src/main/native/cpp/net/ClientImpl.cpp @@ -24,11 +24,11 @@ #include "wpi/util/raw_ostream.hpp" #include "wpi/util/timestamp.h" -using namespace nt; -using namespace nt::net; +using namespace wpi::nt; +using namespace wpi::nt::net; ClientImpl::ClientImpl( - uint64_t curTimeMs, WireConnection& wire, bool local, wpi::Logger& logger, + uint64_t curTimeMs, WireConnection& wire, bool local, wpi::util::Logger& logger, std::function timeSyncUpdated, std::function setPeriodic) @@ -42,7 +42,7 @@ ClientImpl::ClientImpl( : kRttIntervalMs)}, m_outgoing{wire, local} { // immediately send RTT ping - auto now = wpi::Now(); + auto now = wpi::util::Now(); DEBUG4("Sending initial RTT ping {}", now); m_wire.SendBinary( [&](auto& os) { WireEncodeBinary(os, -1, 0, Value::MakeInteger(now)); }); @@ -80,7 +80,7 @@ void ClientImpl::ProcessIncomingBinary(uint64_t curTimeMs, if (m_wire.GetVersion() < 0x0401) { m_pongTimeMs = curTimeMs; } - int64_t now = wpi::Now(); + int64_t now = wpi::util::Now(); int64_t rtt2 = (now - value.GetInteger()) / 2; if (rtt2 < m_rtt2Us) { m_rtt2Us = rtt2; @@ -135,7 +135,7 @@ void ClientImpl::SendOutgoing(uint64_t curTimeMs, bool flush) { return; } - auto now = wpi::Now(); + auto now = wpi::util::Now(); DEBUG4("Sending RTT ping {}", now); m_wire.SendBinary([&](auto& os) { WireEncodeBinary(os, -1, 0, Value::MakeInteger(now)); @@ -165,7 +165,7 @@ void ClientImpl::UpdatePeriodic() { } void ClientImpl::Publish(int32_t pubuid, std::string_view name, - std::string_view typeStr, const wpi::json& properties, + std::string_view typeStr, const wpi::util::json& properties, const PubSubOptionsImpl& options) { if (static_cast(pubuid) >= m_publishers.size()) { m_publishers.resize(pubuid + 1); @@ -222,7 +222,7 @@ void ClientImpl::SetValue(int32_t pubuid, const Value& value) { int ClientImpl::ServerAnnounce(std::string_view name, int id, std::string_view typeStr, - const wpi::json& properties, + const wpi::util::json& properties, std::optional pubuid) { DEBUG4("ServerAnnounce({}, {}, {})", name, id, typeStr); assert(m_local); @@ -239,7 +239,7 @@ void ClientImpl::ServerUnannounce(std::string_view name, int id) { } void ClientImpl::ServerPropertiesUpdate(std::string_view name, - const wpi::json& update, bool ack) { + const wpi::util::json& update, bool ack) { DEBUG4("ServerProperties({}, {}, {})", name, update.dump(), ack); assert(m_local); m_local->ServerPropertiesUpdate(name, update, ack); diff --git a/ntcore/src/main/native/cpp/net/ClientImpl.hpp b/ntcore/src/main/native/cpp/net/ClientImpl.hpp index 69cbf52317..0e450bbd80 100644 --- a/ntcore/src/main/native/cpp/net/ClientImpl.hpp +++ b/ntcore/src/main/native/cpp/net/ClientImpl.hpp @@ -20,16 +20,16 @@ #include "WireDecoder.hpp" #include "wpi/util/DenseMap.hpp" -namespace wpi { +namespace wpi::util { class Logger; } // namespace wpi -namespace nt { +namespace wpi::nt { class PubSubOptionsImpl; class Value; -} // namespace nt +} // namespace wpi::nt -namespace nt::net { +namespace wpi::nt::net { struct ClientMessage; class WireConnection; @@ -37,7 +37,7 @@ class WireConnection; class ClientImpl final : private ServerMessageHandler { public: ClientImpl( - uint64_t curTimeMs, WireConnection& wire, bool local, wpi::Logger& logger, + uint64_t curTimeMs, WireConnection& wire, bool local, wpi::util::Logger& logger, std::function timeSyncUpdated, std::function setPeriodic); @@ -63,20 +63,20 @@ class ClientImpl final : private ServerMessageHandler { // ServerMessageHandler interface int ServerAnnounce(std::string_view name, int id, std::string_view typeStr, - const wpi::json& properties, + const wpi::util::json& properties, std::optional pubuid) final; void ServerUnannounce(std::string_view name, int id) final; - void ServerPropertiesUpdate(std::string_view name, const wpi::json& update, + void ServerPropertiesUpdate(std::string_view name, const wpi::util::json& update, bool ack) final; void ServerSetValue(int topicId, const Value& value) final; void Publish(int pubuid, std::string_view name, std::string_view typeStr, - const wpi::json& properties, const PubSubOptionsImpl& options); + const wpi::util::json& properties, const PubSubOptionsImpl& options); void Unpublish(int pubuid, ClientMessage&& msg); void SetValue(int pubuid, const Value& value); WireConnection& m_wire; - wpi::Logger& m_logger; + wpi::util::Logger& m_logger; ServerMessageHandler* m_local{nullptr}; std::function m_timeSyncUpdated; @@ -86,7 +86,7 @@ class ClientImpl final : private ServerMessageHandler { std::vector> m_publishers; // indexed by server-provided topic id - wpi::DenseMap m_topicMap; + wpi::util::DenseMap m_topicMap; // ping NetworkPing m_ping; @@ -107,4 +107,4 @@ class ClientImpl final : private ServerMessageHandler { NetworkOutgoingQueue m_outgoing; }; -} // namespace nt::net +} // namespace wpi::nt::net diff --git a/ntcore/src/main/native/cpp/net/ClientMessageQueue.hpp b/ntcore/src/main/native/cpp/net/ClientMessageQueue.hpp index 988ff90854..3e7277c1a3 100644 --- a/ntcore/src/main/native/cpp/net/ClientMessageQueue.hpp +++ b/ntcore/src/main/native/cpp/net/ClientMessageQueue.hpp @@ -13,11 +13,11 @@ #include "wpi/util/Logger.hpp" #include "wpi/util/mutex.hpp" -namespace wpi { +namespace wpi::util { class Logger; } // namespace wpi -namespace nt::net { +namespace wpi::nt::net { class ClientMessageQueue { public: @@ -35,7 +35,7 @@ class ClientMessageQueueImpl final : public ClientMessageHandler, public: static constexpr size_t kBlockSize = 64; - explicit ClientMessageQueueImpl(wpi::Logger& logger) : m_logger{logger} {} + explicit ClientMessageQueueImpl(wpi::util::Logger& logger) : m_logger{logger} {} bool empty() const { return m_queue.empty(); } @@ -71,7 +71,7 @@ class ClientMessageQueueImpl final : public ClientMessageHandler, // ClientMessageHandler - calls to these append to the queue void ClientPublish(int pubuid, std::string_view name, - std::string_view typeStr, const wpi::json& properties, + std::string_view typeStr, const wpi::util::json& properties, const PubSubOptionsImpl& options) final { std::scoped_lock lock{m_mutex}; m_queue.enqueue(ClientMessage{PublishMsg{ @@ -84,7 +84,7 @@ class ClientMessageQueueImpl final : public ClientMessageHandler, } void ClientSetProperties(std::string_view name, - const wpi::json& update) final { + const wpi::util::json& update) final { std::scoped_lock lock{m_mutex}; m_queue.enqueue(ClientMessage{SetPropertiesMsg{std::string{name}, update}}); } @@ -117,8 +117,8 @@ class ClientMessageQueueImpl final : public ClientMessageHandler, } private: - wpi::FastQueue m_queue{kBlockSize - 1}; - wpi::Logger& m_logger; + wpi::util::FastQueue m_queue{kBlockSize - 1}; + wpi::util::Logger& m_logger; class NoMutex { public: @@ -126,7 +126,7 @@ class ClientMessageQueueImpl final : public ClientMessageHandler, void unlock() {} }; [[no_unique_address]] - std::conditional_t m_mutex; + std::conditional_t m_mutex; struct ValueSize { size_t size{0}; @@ -143,4 +143,4 @@ using LocalClientMessageQueue = detail::ClientMessageQueueImpl<2 * 1024 * 1024, true>; using NetworkIncomingClientQueue = detail::ClientMessageQueueImpl<0, false>; -} // namespace nt::net +} // namespace wpi::nt::net diff --git a/ntcore/src/main/native/cpp/net/Message.hpp b/ntcore/src/main/native/cpp/net/Message.hpp index 9de180dbba..9f05631ccc 100644 --- a/ntcore/src/main/native/cpp/net/Message.hpp +++ b/ntcore/src/main/native/cpp/net/Message.hpp @@ -13,7 +13,7 @@ #include "wpi/nt/NetworkTableValue.hpp" #include "wpi/util/json.hpp" -namespace nt::net { +namespace wpi::nt::net { #if __GNUC__ >= 13 #pragma GCC diagnostic push @@ -25,7 +25,7 @@ struct PublishMsg { int pubuid{0}; std::string name; std::string typeStr; - wpi::json properties; + wpi::util::json properties; PubSubOptionsImpl options; // will be empty when coming from network }; @@ -37,7 +37,7 @@ struct UnpublishMsg { struct SetPropertiesMsg { static constexpr std::string_view kMethodStr = "setproperties"; std::string name; - wpi::json update; + wpi::util::json update; }; struct SubscribeMsg { @@ -75,7 +75,7 @@ struct AnnounceMsg { int id{0}; std::string typeStr; std::optional pubuid; - wpi::json properties; + wpi::util::json properties; }; struct UnannounceMsg { @@ -87,7 +87,7 @@ struct UnannounceMsg { struct PropertiesUpdateMsg { static constexpr std::string_view kMethodStr = "properties"; std::string name; - wpi::json update; + wpi::util::json update; bool ack; }; @@ -103,4 +103,4 @@ struct ServerMessage { Contents contents; }; -} // namespace nt::net +} // namespace wpi::nt::net diff --git a/ntcore/src/main/native/cpp/net/MessageHandler.hpp b/ntcore/src/main/native/cpp/net/MessageHandler.hpp index ee3784393a..e8ae7b1de0 100644 --- a/ntcore/src/main/native/cpp/net/MessageHandler.hpp +++ b/ntcore/src/main/native/cpp/net/MessageHandler.hpp @@ -11,12 +11,12 @@ #include "wpi/util/json_fwd.hpp" -namespace nt { +namespace wpi::nt { class PubSubOptionsImpl; class Value; -} // namespace nt +} // namespace wpi::nt -namespace nt::net { +namespace wpi::nt::net { class ClientMessageHandler { public: @@ -24,11 +24,11 @@ class ClientMessageHandler { virtual void ClientPublish(int pubuid, std::string_view name, std::string_view typeStr, - const wpi::json& properties, + const wpi::util::json& properties, const PubSubOptionsImpl& options) = 0; virtual void ClientUnpublish(int pubuid) = 0; virtual void ClientSetProperties(std::string_view name, - const wpi::json& update) = 0; + const wpi::util::json& update) = 0; virtual void ClientSubscribe(int subuid, std::span topicNames, const PubSubOptionsImpl& options) = 0; @@ -41,12 +41,12 @@ class ServerMessageHandler { virtual ~ServerMessageHandler() = default; virtual int ServerAnnounce(std::string_view name, int id, std::string_view typeStr, - const wpi::json& properties, + const wpi::util::json& properties, std::optional pubuid) = 0; virtual void ServerUnannounce(std::string_view name, int id) = 0; virtual void ServerPropertiesUpdate(std::string_view name, - const wpi::json& update, bool ack) = 0; + const wpi::util::json& update, bool ack) = 0; virtual void ServerSetValue(int topicuid, const Value& value) = 0; }; -} // namespace nt::net +} // namespace wpi::nt::net diff --git a/ntcore/src/main/native/cpp/net/NetworkInterface.hpp b/ntcore/src/main/native/cpp/net/NetworkInterface.hpp index e4bd826d53..c3b5f58334 100644 --- a/ntcore/src/main/native/cpp/net/NetworkInterface.hpp +++ b/ntcore/src/main/native/cpp/net/NetworkInterface.hpp @@ -6,7 +6,7 @@ #include "MessageHandler.hpp" -namespace nt::net { +namespace wpi::nt::net { class ILocalStorage : public ServerMessageHandler { public: @@ -14,4 +14,4 @@ class ILocalStorage : public ServerMessageHandler { virtual void ClearNetwork() = 0; }; -} // namespace nt::net +} // namespace wpi::nt::net diff --git a/ntcore/src/main/native/cpp/net/NetworkOutgoingQueue.hpp b/ntcore/src/main/native/cpp/net/NetworkOutgoingQueue.hpp index 32655a22e4..f7438f07f2 100644 --- a/ntcore/src/main/native/cpp/net/NetworkOutgoingQueue.hpp +++ b/ntcore/src/main/native/cpp/net/NetworkOutgoingQueue.hpp @@ -20,7 +20,7 @@ #include "wpi/nt/ntcore_c.h" #include "wpi/util/DenseMap.hpp" -namespace nt::net { +namespace wpi::nt::net { static constexpr uint32_t kMinPeriodMs = 5; @@ -171,7 +171,7 @@ class NetworkOutgoingQueue { } // what queues are ready to send? - wpi::SmallVector queues; + wpi::util::SmallVector queues; for (unsigned int i = 0; i < m_queues.size(); ++i) { if (!m_queues[i].msgs.empty() && (flush || curTimeMs >= m_queues[i].nextSendMs)) { @@ -258,7 +258,7 @@ class NetworkOutgoingQueue { private: using ValueMsg = typename MessageType::ValueMsg; - void EncodeValue(wpi::raw_ostream& os, int id, const Value& value) { + void EncodeValue(wpi::util::raw_ostream& os, int id, const Value& value) { int64_t time = value.time(); if constexpr (std::same_as) { if (time != 0) { @@ -298,7 +298,7 @@ class NetworkOutgoingQueue { unsigned int queueIndex = 0; int valuePos = -1; // -1 if not in queue }; - wpi::DenseMap m_idMap; + wpi::util::DenseMap m_idMap; size_t m_totalSize{0}; uint64_t m_lastSendMs{0}; int64_t m_timeOffsetUs{0}; @@ -310,4 +310,4 @@ class NetworkOutgoingQueue { static constexpr size_t kOutgoingLimit = 1024 * 1024; }; -} // namespace nt::net +} // namespace wpi::nt::net diff --git a/ntcore/src/main/native/cpp/net/NetworkPing.cpp b/ntcore/src/main/native/cpp/net/NetworkPing.cpp index 209da1c92f..d770c8984e 100644 --- a/ntcore/src/main/native/cpp/net/NetworkPing.cpp +++ b/ntcore/src/main/native/cpp/net/NetworkPing.cpp @@ -6,7 +6,7 @@ #include "WireConnection.hpp" -using namespace nt::net; +using namespace wpi::nt::net; bool NetworkPing::Send(uint64_t curTimeMs) { if (curTimeMs < m_nextPingTimeMs) { diff --git a/ntcore/src/main/native/cpp/net/NetworkPing.hpp b/ntcore/src/main/native/cpp/net/NetworkPing.hpp index 304e01f23d..13ff9ef23f 100644 --- a/ntcore/src/main/native/cpp/net/NetworkPing.hpp +++ b/ntcore/src/main/native/cpp/net/NetworkPing.hpp @@ -6,7 +6,7 @@ #include -namespace nt::net { +namespace wpi::nt::net { class WireConnection; @@ -25,4 +25,4 @@ class NetworkPing { uint64_t m_pongTimeMs{0}; }; -} // namespace nt::net +} // namespace wpi::nt::net diff --git a/ntcore/src/main/native/cpp/net/WebSocketConnection.cpp b/ntcore/src/main/native/cpp/net/WebSocketConnection.cpp index d79c1a4385..22795acf39 100644 --- a/ntcore/src/main/native/cpp/net/WebSocketConnection.cpp +++ b/ntcore/src/main/native/cpp/net/WebSocketConnection.cpp @@ -15,8 +15,8 @@ #include "wpi/util/raw_ostream.hpp" #include "wpi/util/timestamp.h" -using namespace nt; -using namespace nt::net; +using namespace wpi::nt; +using namespace wpi::nt::net; // MTU - assume Ethernet, IPv6, TCP; does not include WS frame header (max 10) static constexpr size_t kMTU = 1500 - 40 - 20; @@ -28,7 +28,7 @@ static constexpr size_t kFlushThresholdFrames = 32; static constexpr size_t kFlushThresholdBytes = 16384; static constexpr size_t kMaxPoolSize = 32; -class WebSocketConnection::Stream final : public wpi::raw_ostream { +class WebSocketConnection::Stream final : public wpi::util::raw_ostream { public: explicit Stream(WebSocketConnection& conn) : m_conn{conn} { auto& buf = conn.m_bufs.back(); @@ -60,8 +60,8 @@ void WebSocketConnection::Stream::write_impl(const char* data, size_t len) { m_conn.m_written += amt; if (!m_disableAlloc) { #ifdef NT_ENABLE_WS_FRAG - m_conn.m_frames.back().opcode &= ~wpi::WebSocket::kFlagFin; - m_conn.StartFrame(wpi::WebSocket::Frame::kFragment); + m_conn.m_frames.back().opcode &= ~wpi::net::WebSocket::kFlagFin; + m_conn.StartFrame(wpi::net::WebSocket::Frame::kFragment); #else m_conn.m_bufs.emplace_back(m_conn.AllocBuf()); m_conn.m_bufs.back().len = 0; @@ -90,8 +90,8 @@ void WebSocketConnection::Stream::write_impl(const char* data, size_t len) { if (buf.len >= kAllocSize && (len > 0 || !m_disableAlloc)) { #ifdef NT_ENABLE_WS_FRAG // fragment the current frame and start a new one - m_conn.m_frames.back().opcode &= ~wpi::WebSocket::kFlagFin; - m_conn.StartFrame(wpi::WebSocket::Frame::kFragment); + m_conn.m_frames.back().opcode &= ~wpi::net::WebSocket::kFlagFin; + m_conn.StartFrame(wpi::net::WebSocket::Frame::kFragment); #else m_conn.m_bufs.emplace_back(m_conn.AllocBuf()); m_conn.m_bufs.back().len = 0; @@ -106,9 +106,9 @@ void WebSocketConnection::Stream::write_impl(const char* data, size_t len) { } } -WebSocketConnection::WebSocketConnection(wpi::WebSocket& ws, +WebSocketConnection::WebSocketConnection(wpi::net::WebSocket& ws, unsigned int version, - wpi::Logger& logger) + wpi::util::Logger& logger) : m_ws{ws}, m_logger{logger}, m_version{version} {} WebSocketConnection::~WebSocketConnection() { @@ -124,7 +124,7 @@ void WebSocketConnection::SendPing(uint64_t time) { WPI_DEBUG4(m_logger, "conn: sending ping {}", time); auto buf = AllocBuf(); buf.len = 8; - wpi::support::endian::write64(buf.base, time); + wpi::util::support::endian::write64(buf.base, time); m_ws.SendPing({buf}, [selfweak = weak_from_this()](auto bufs, auto err) { if (auto self = selfweak.lock()) { self->m_err = err; @@ -153,7 +153,7 @@ void WebSocketConnection::FinishText() { } int WebSocketConnection::Write( - State kind, wpi::function_ref writer) { + State kind, wpi::util::function_ref writer) { bool first = false; if (m_state != kind || (m_state == kind && m_framePos >= kNewFrameThresholdBytes)) { @@ -163,10 +163,10 @@ int WebSocketConnection::Write( } m_state = kind; if (!m_frames.empty()) { - m_frames.back().opcode |= wpi::WebSocket::kFlagFin; + m_frames.back().opcode |= wpi::net::WebSocket::kFlagFin; } - StartFrame(m_state == kText ? wpi::WebSocket::Frame::kText - : wpi::WebSocket::Frame::kBinary); + StartFrame(m_state == kText ? wpi::net::WebSocket::Frame::kText + : wpi::net::WebSocket::Frame::kBinary); m_framePos = 0; first = true; } @@ -188,7 +188,7 @@ int WebSocketConnection::Write( int WebSocketConnection::Flush() { WPI_DEBUG4(m_logger, "conn: flushing"); - m_lastFlushTime = wpi::Now(); + m_lastFlushTime = wpi::util::Now(); if (m_state == kEmpty) { return 0; } @@ -201,7 +201,7 @@ int WebSocketConnection::Flush() { if (m_frames.empty()) { return 0; } - m_frames.back().opcode |= wpi::WebSocket::kFlagFin; + m_frames.back().opcode |= wpi::net::WebSocket::kFlagFin; // convert internal frames into WS frames m_ws_frames.clear(); @@ -232,7 +232,7 @@ int WebSocketConnection::Flush() { int count = 0; for (auto&& frame : - wpi::take_back(std::span{m_frames}, unsentFrames.size())) { + wpi::util::take_back(std::span{m_frames}, unsentFrames.size())) { ReleaseBufs( std::span{m_bufs}.subspan(frame.start, frame.end - frame.start)); count += frame.count; @@ -243,17 +243,17 @@ int WebSocketConnection::Flush() { } void WebSocketConnection::Send( - uint8_t opcode, wpi::function_ref writer) { - wpi::SmallVector bufs; - wpi::raw_uv_ostream os{bufs, [this] { return AllocBuf(); }}; - if (opcode == wpi::WebSocket::Frame::kText) { + uint8_t opcode, wpi::util::function_ref writer) { + wpi::util::SmallVector bufs; + wpi::net::raw_uv_ostream os{bufs, [this] { return AllocBuf(); }}; + if (opcode == wpi::net::WebSocket::Frame::kText) { os << '['; } writer(os); - if (opcode == wpi::WebSocket::Frame::kText) { + if (opcode == wpi::net::WebSocket::Frame::kText) { os << ']'; } - wpi::WebSocket::Frame frame{opcode, os.bufs()}; + wpi::net::WebSocket::Frame frame{opcode, os.bufs()}; WPI_DEBUG4(m_logger, "Send({})", static_cast(opcode)); m_ws.SendFrames({{frame}}, [selfweak = weak_from_this()](auto bufs, auto) { if (auto self = selfweak.lock()) { @@ -271,16 +271,16 @@ void WebSocketConnection::Disconnect(std::string_view reason) { m_ws.Fail(1001, reason); } -wpi::uv::Buffer WebSocketConnection::AllocBuf() { +wpi::net::uv::Buffer WebSocketConnection::AllocBuf() { if (!m_buf_pool.empty()) { auto buf = m_buf_pool.back(); m_buf_pool.pop_back(); return buf; } - return wpi::uv::Buffer::Allocate(kAllocSize + 1); // leave space for ']' + return wpi::net::uv::Buffer::Allocate(kAllocSize + 1); // leave space for ']' } -void WebSocketConnection::ReleaseBufs(std::span bufs) { +void WebSocketConnection::ReleaseBufs(std::span bufs) { #ifdef __SANITIZE_ADDRESS__ size_t numToPool = 0; #else diff --git a/ntcore/src/main/native/cpp/net/WebSocketConnection.hpp b/ntcore/src/main/native/cpp/net/WebSocketConnection.hpp index 48c4103645..de62e7856e 100644 --- a/ntcore/src/main/native/cpp/net/WebSocketConnection.hpp +++ b/ntcore/src/main/native/cpp/net/WebSocketConnection.hpp @@ -15,18 +15,18 @@ #include "wpi/net/uv/Stream.hpp" #include "wpi/util/function_ref.hpp" -namespace wpi { +namespace wpi::util { class Logger; } // namespace wpi -namespace nt::net { +namespace wpi::nt::net { class WebSocketConnection final : public WireConnection, public std::enable_shared_from_this { public: - WebSocketConnection(wpi::WebSocket& ws, unsigned int version, - wpi::Logger& logger); + WebSocketConnection(wpi::net::WebSocket& ws, unsigned int version, + wpi::util::Logger& logger); ~WebSocketConnection() override; WebSocketConnection(const WebSocketConnection&) = delete; WebSocketConnection& operator=(const WebSocketConnection&) = delete; @@ -37,19 +37,19 @@ class WebSocketConnection final bool Ready() const final { return !m_ws.IsWriteInProgress(); } - int WriteText(wpi::function_ref writer) final { + int WriteText(wpi::util::function_ref writer) final { return Write(kText, writer); } - int WriteBinary(wpi::function_ref writer) final { + int WriteBinary(wpi::util::function_ref writer) final { return Write(kBinary, writer); } int Flush() final; - void SendText(wpi::function_ref writer) final { - Send(wpi::WebSocket::Frame::kText, writer); + void SendText(wpi::util::function_ref writer) final { + Send(wpi::net::WebSocket::Frame::kText, writer); } - void SendBinary(wpi::function_ref writer) final { - Send(wpi::WebSocket::Frame::kBinary, writer); + void SendBinary(wpi::util::function_ref writer) final { + Send(wpi::net::WebSocket::Frame::kBinary, writer); } uint64_t GetLastFlushTime() const final { return m_lastFlushTime; } @@ -78,17 +78,17 @@ class WebSocketConnection final private: enum State { kEmpty, kText, kBinary }; - int Write(State kind, wpi::function_ref writer); + int Write(State kind, wpi::util::function_ref writer); void Send(uint8_t opcode, - wpi::function_ref writer); + wpi::util::function_ref writer); void StartFrame(uint8_t opcode); void FinishText(); - wpi::uv::Buffer AllocBuf(); - void ReleaseBufs(std::span bufs); + wpi::net::uv::Buffer AllocBuf(); + void ReleaseBufs(std::span bufs); - wpi::WebSocket& m_ws; - wpi::Logger& m_logger; + wpi::net::WebSocket& m_ws; + wpi::util::Logger& m_logger; bool m_readActive = true; class Stream; @@ -102,17 +102,17 @@ class WebSocketConnection final unsigned int count = 0; uint8_t opcode; }; - std::vector m_ws_frames; // to reduce allocs + std::vector m_ws_frames; // to reduce allocs std::vector m_frames; - std::vector m_bufs; - std::vector m_buf_pool; + std::vector m_bufs; + std::vector m_buf_pool; size_t m_framePos = 0; size_t m_written = 0; - wpi::uv::Error m_err; + wpi::net::uv::Error m_err; State m_state = kEmpty; std::string m_reason; uint64_t m_lastFlushTime = 0; unsigned int m_version; }; -} // namespace nt::net +} // namespace wpi::nt::net diff --git a/ntcore/src/main/native/cpp/net/WireConnection.hpp b/ntcore/src/main/native/cpp/net/WireConnection.hpp index 1c9cd68fd2..cd5684c133 100644 --- a/ntcore/src/main/native/cpp/net/WireConnection.hpp +++ b/ntcore/src/main/native/cpp/net/WireConnection.hpp @@ -10,11 +10,11 @@ #include "wpi/util/function_ref.hpp" -namespace wpi { +namespace wpi::util { class raw_ostream; } // namespace wpi -namespace nt::net { +namespace wpi::nt::net { class WireConnection { public: @@ -33,10 +33,10 @@ class WireConnection { // not sent. [[nodiscard]] virtual int WriteText( - wpi::function_ref writer) = 0; + wpi::util::function_ref writer) = 0; [[nodiscard]] virtual int WriteBinary( - wpi::function_ref writer) = 0; + wpi::util::function_ref writer) = 0; // Flushes any pending buffers. Return value equivalent to // WriteText/WriteBinary (e.g. 1 means the last WriteX call was not sent). @@ -45,9 +45,9 @@ class WireConnection { // These immediately send the data even if the buffer is full. virtual void SendText( - wpi::function_ref writer) = 0; + wpi::util::function_ref writer) = 0; virtual void SendBinary( - wpi::function_ref writer) = 0; + wpi::util::function_ref writer) = 0; virtual uint64_t GetLastFlushTime() const = 0; // in microseconds @@ -60,4 +60,4 @@ class WireConnection { virtual void Disconnect(std::string_view reason) = 0; }; -} // namespace nt::net +} // namespace wpi::nt::net diff --git a/ntcore/src/main/native/cpp/net/WireDecoder.cpp b/ntcore/src/main/native/cpp/net/WireDecoder.cpp index 0b756a694e..3fbc44bd53 100644 --- a/ntcore/src/main/native/cpp/net/WireDecoder.cpp +++ b/ntcore/src/main/native/cpp/net/WireDecoder.cpp @@ -19,11 +19,11 @@ #include "wpi/util/json.hpp" #include "wpi/util/mpack.h" -using namespace nt; -using namespace nt::net; +using namespace wpi::nt; +using namespace wpi::nt::net; using namespace mpack; -static bool GetNumber(wpi::json& val, double* num) { +static bool GetNumber(wpi::util::json& val, double* num) { if (auto v = val.get_ptr()) { *num = *v; } else if (auto v = val.get_ptr()) { @@ -36,7 +36,7 @@ static bool GetNumber(wpi::json& val, double* num) { return true; } -static bool GetNumber(wpi::json& val, int64_t* num) { +static bool GetNumber(wpi::util::json& val, int64_t* num) { if (auto v = val.get_ptr()) { *num = *v; } else if (auto v = val.get_ptr()) { @@ -47,7 +47,7 @@ static bool GetNumber(wpi::json& val, int64_t* num) { return true; } -static std::string* ObjGetString(wpi::json::object_t& obj, std::string_view key, +static std::string* ObjGetString(wpi::util::json::object_t& obj, std::string_view key, std::string* error) { auto it = obj.find(key); if (it == obj.end()) { @@ -61,7 +61,7 @@ static std::string* ObjGetString(wpi::json::object_t& obj, std::string_view key, return val; } -static bool ObjGetNumber(wpi::json::object_t& obj, std::string_view key, +static bool ObjGetNumber(wpi::util::json::object_t& obj, std::string_view key, std::string* error, int64_t* num) { auto it = obj.find(key); if (it == obj.end()) { @@ -75,7 +75,7 @@ static bool ObjGetNumber(wpi::json::object_t& obj, std::string_view key, return true; } -static bool ObjGetStringArray(wpi::json::object_t& obj, std::string_view key, +static bool ObjGetStringArray(wpi::util::json::object_t& obj, std::string_view key, std::string* error, std::vector* out) { // prefixes @@ -84,7 +84,7 @@ static bool ObjGetStringArray(wpi::json::object_t& obj, std::string_view key, *error = fmt::format("no {} key", key); return false; } - auto jarr = it->second.get_ptr(); + auto jarr = it->second.get_ptr(); if (!jarr) { *error = fmt::format("{} must be an array", key); return false; @@ -112,11 +112,11 @@ template requires(std::same_as || std::same_as) static bool WireDecodeTextImpl(std::string_view in, T& out, - wpi::Logger& logger) { - wpi::json j; + wpi::util::Logger& logger) { + wpi::util::json j; try { - j = wpi::json::parse(in); - } catch (wpi::json::parse_error& err) { + j = wpi::util::json::parse(in); + } catch (wpi::util::json::parse_error& err) { WPI_WARNING(logger, "could not decode JSON message: {}", err.what()); return false; } @@ -132,7 +132,7 @@ static bool WireDecodeTextImpl(std::string_view in, T& out, ++i; std::string error; { - auto obj = jmsg.get_ptr(); + auto obj = jmsg.get_ptr(); if (!obj) { error = "expected message to be an object"; goto err; @@ -148,7 +148,7 @@ static bool WireDecodeTextImpl(std::string_view in, T& out, error = "no params key"; goto err; } - auto params = paramsIt->second.get_ptr(); + auto params = paramsIt->second.get_ptr(); if (!params) { error = "params must be an object"; goto err; @@ -174,14 +174,14 @@ static bool WireDecodeTextImpl(std::string_view in, T& out, goto err; } - // limit to 32-bit range and exclude endpoints used by DenseMap + // limit to 32-bit range and exclude endpoints used by wpi::util::DenseMap if (pubuid >= 0x7fffffffLL || pubuid <= (-0x7fffffffLL - 1)) { error = "pubuid out of range"; goto err; } // properties; allow missing (treated as empty) - wpi::json* properties = nullptr; + wpi::util::json* properties = nullptr; auto propertiesIt = params->find("properties"); if (propertiesIt != params->end()) { properties = &propertiesIt->second; @@ -190,9 +190,9 @@ static bool WireDecodeTextImpl(std::string_view in, T& out, goto err; } } - wpi::json propertiesEmpty; + wpi::util::json propertiesEmpty; if (!properties) { - propertiesEmpty = wpi::json::object(); + propertiesEmpty = wpi::util::json::object(); properties = &propertiesEmpty; } @@ -206,7 +206,7 @@ static bool WireDecodeTextImpl(std::string_view in, T& out, goto err; } - // limit to 32-bit range and exclude endpoints used by DenseMap + // limit to 32-bit range and exclude endpoints used by wpi::util::DenseMap if (pubuid >= 0x7fffffffLL || pubuid <= (-0x7fffffffLL - 1)) { error = "pubuid out of range"; goto err; @@ -243,7 +243,7 @@ static bool WireDecodeTextImpl(std::string_view in, T& out, goto err; } - // limit to 32-bit range and exclude endpoints used by DenseMap + // limit to 32-bit range and exclude endpoints used by wpi::util::DenseMap if (subuid >= 0x7fffffffLL || subuid <= (-0x7fffffffLL - 1)) { error = "subuid out of range"; goto err; @@ -253,7 +253,7 @@ static bool WireDecodeTextImpl(std::string_view in, T& out, PubSubOptionsImpl options; auto optionsIt = params->find("options"); if (optionsIt != params->end()) { - auto joptions = optionsIt->second.get_ptr(); + auto joptions = optionsIt->second.get_ptr(); if (!joptions) { error = "options must be an object"; goto err; @@ -321,7 +321,7 @@ static bool WireDecodeTextImpl(std::string_view in, T& out, goto err; } - // limit to 32-bit range and exclude endpoints used by DenseMap + // limit to 32-bit range and exclude endpoints used by wpi::util::DenseMap if (subuid >= 0x7fffffffLL || subuid <= (-0x7fffffffLL - 1)) { error = "pubuid out of range"; goto err; @@ -348,7 +348,7 @@ static bool WireDecodeTextImpl(std::string_view in, T& out, goto err; } - // limit to 32-bit range and exclude endpoints used by DenseMap + // limit to 32-bit range and exclude endpoints used by wpi::util::DenseMap if (id >= 0x7fffffffLL || id <= (-0x7fffffffLL - 1)) { error = "id out of range"; goto err; @@ -370,7 +370,7 @@ static bool WireDecodeTextImpl(std::string_view in, T& out, goto err; } - // limit to 32-bit range and exclude endpoints used by DenseMap + // limit to 32-bit range and exclude endpoints used by wpi::util::DenseMap if (val >= 0x7fffffffLL || val <= (-0x7fffffffLL - 1)) { error = "pubuid out of range"; goto err; @@ -388,7 +388,7 @@ static bool WireDecodeTextImpl(std::string_view in, T& out, auto properties = &propertiesIt->second; if (!properties->is_object()) { WPI_WARNING(logger, "{}: properties is not an object", *name); - *properties = wpi::json::object(); + *properties = wpi::util::json::object(); } // complete @@ -406,7 +406,7 @@ static bool WireDecodeTextImpl(std::string_view in, T& out, goto err; } - // limit to 32-bit range and exclude endpoints used by DenseMap + // limit to 32-bit range and exclude endpoints used by wpi::util::DenseMap if (id >= 0x7fffffffLL || id <= (-0x7fffffffLL - 1)) { error = "id out of range"; goto err; @@ -464,17 +464,17 @@ static bool WireDecodeTextImpl(std::string_view in, T& out, #pragma clang diagnostic pop #endif -bool nt::net::WireDecodeText(std::string_view in, ClientMessageHandler& out, - wpi::Logger& logger) { +bool wpi::nt::net::WireDecodeText(std::string_view in, ClientMessageHandler& out, + wpi::util::Logger& logger) { return ::WireDecodeTextImpl(in, out, logger); } -void nt::net::WireDecodeText(std::string_view in, ServerMessageHandler& out, - wpi::Logger& logger) { +void wpi::nt::net::WireDecodeText(std::string_view in, ServerMessageHandler& out, + wpi::util::Logger& logger) { ::WireDecodeTextImpl(in, out, logger); } -bool nt::net::WireDecodeBinary(std::span* in, int* outId, +bool wpi::nt::net::WireDecodeBinary(std::span* in, int* outId, Value* outValue, std::string* error, int64_t localTimeOffset) { mpack_reader_t reader; @@ -614,6 +614,6 @@ bool nt::net::WireDecodeBinary(std::span* in, int* outId, outValue->SetServerTime(time); outValue->SetTime(time == 0 ? 0 : time + localTimeOffset); // update input range - *in = wpi::take_back(*in, mpack_reader_remaining(&reader, nullptr)); + *in = wpi::util::take_back(*in, mpack_reader_remaining(&reader, nullptr)); return true; } diff --git a/ntcore/src/main/native/cpp/net/WireDecoder.hpp b/ntcore/src/main/native/cpp/net/WireDecoder.hpp index 3a8d421608..6b8e7bc8bc 100644 --- a/ntcore/src/main/native/cpp/net/WireDecoder.hpp +++ b/ntcore/src/main/native/cpp/net/WireDecoder.hpp @@ -10,27 +10,27 @@ #include #include -namespace wpi { +namespace wpi::util { class Logger; } // namespace wpi -namespace nt { +namespace wpi::nt { class Value; -} // namespace nt +} // namespace wpi::nt -namespace nt::net { +namespace wpi::nt::net { class ClientMessageHandler; class ServerMessageHandler; // return true if client pub/sub metadata needs updating bool WireDecodeText(std::string_view in, ClientMessageHandler& out, - wpi::Logger& logger); + wpi::util::Logger& logger); void WireDecodeText(std::string_view in, ServerMessageHandler& out, - wpi::Logger& logger); + wpi::util::Logger& logger); // returns true if successfully decoded a message bool WireDecodeBinary(std::span* in, int* outId, Value* outValue, std::string* error, int64_t localTimeOffset); -} // namespace nt::net +} // namespace wpi::nt::net diff --git a/ntcore/src/main/native/cpp/net/WireEncoder.cpp b/ntcore/src/main/native/cpp/net/WireEncoder.cpp index 907a1f50e2..0b737d389c 100644 --- a/ntcore/src/main/native/cpp/net/WireEncoder.cpp +++ b/ntcore/src/main/native/cpp/net/WireEncoder.cpp @@ -14,14 +14,14 @@ #include "wpi/util/mpack.h" #include "wpi/util/raw_ostream.hpp" -using namespace nt; -using namespace nt::net; +using namespace wpi::nt; +using namespace wpi::nt::net; using namespace mpack; -void nt::net::WireEncodePublish(wpi::raw_ostream& os, int pubuid, +void wpi::nt::net::WireEncodePublish(wpi::util::raw_ostream& os, int pubuid, std::string_view name, std::string_view typeStr, - const wpi::json& properties) { - wpi::json::serializer s{os, ' ', 0}; + const wpi::util::json& properties) { + wpi::util::json::serializer s{os, ' ', 0}; os << "{\"method\":\"" << PublishMsg::kMethodStr << "\",\"params\":{"; os << "\"name\":\""; s.dump_escaped(name, false); @@ -34,18 +34,18 @@ void nt::net::WireEncodePublish(wpi::raw_ostream& os, int pubuid, os << "\"}}"; } -void nt::net::WireEncodeUnpublish(wpi::raw_ostream& os, int pubuid) { - wpi::json::serializer s{os, ' ', 0}; +void wpi::nt::net::WireEncodeUnpublish(wpi::util::raw_ostream& os, int pubuid) { + wpi::util::json::serializer s{os, ' ', 0}; os << "{\"method\":\"" << UnpublishMsg::kMethodStr << "\",\"params\":{"; os << "\"pubuid\":"; s.dump_integer(pubuid); os << "}}"; } -void nt::net::WireEncodeSetProperties(wpi::raw_ostream& os, +void wpi::nt::net::WireEncodeSetProperties(wpi::util::raw_ostream& os, std::string_view name, - const wpi::json& update) { - wpi::json::serializer s{os, ' ', 0}; + const wpi::util::json& update) { + wpi::util::json::serializer s{os, ' ', 0}; os << "{\"method\":\"" << SetPropertiesMsg::kMethodStr << "\",\"params\":{"; os << "\"name\":\""; s.dump_escaped(name, false); @@ -55,8 +55,8 @@ void nt::net::WireEncodeSetProperties(wpi::raw_ostream& os, } template -static void EncodePrefixes(wpi::raw_ostream& os, std::span topicNames, - wpi::json::serializer& s) { +static void EncodePrefixes(wpi::util::raw_ostream& os, std::span topicNames, + wpi::util::json::serializer& s) { os << '['; bool first = true; for (auto&& name : topicNames) { @@ -73,10 +73,10 @@ static void EncodePrefixes(wpi::raw_ostream& os, std::span topicNames, } template -static void WireEncodeSubscribeImpl(wpi::raw_ostream& os, int subuid, +static void WireEncodeSubscribeImpl(wpi::util::raw_ostream& os, int subuid, std::span topicNames, const PubSubOptionsImpl& options) { - wpi::json::serializer s{os, ' ', 0}; + wpi::util::json::serializer s{os, ' ', 0}; os << "{\"method\":\"" << SubscribeMsg::kMethodStr << "\",\"params\":{"; os << "\"options\":{"; bool first = true; @@ -112,27 +112,27 @@ static void WireEncodeSubscribeImpl(wpi::raw_ostream& os, int subuid, os << "}}"; } -void nt::net::WireEncodeSubscribe(wpi::raw_ostream& os, int subuid, +void wpi::nt::net::WireEncodeSubscribe(wpi::util::raw_ostream& os, int subuid, std::span topicNames, const PubSubOptionsImpl& options) { WireEncodeSubscribeImpl(os, subuid, topicNames, options); } -void nt::net::WireEncodeSubscribe(wpi::raw_ostream& os, int subuid, +void wpi::nt::net::WireEncodeSubscribe(wpi::util::raw_ostream& os, int subuid, std::span topicNames, const PubSubOptionsImpl& options) { WireEncodeSubscribeImpl(os, subuid, topicNames, options); } -void nt::net::WireEncodeUnsubscribe(wpi::raw_ostream& os, int subuid) { - wpi::json::serializer s{os, ' ', 0}; +void wpi::nt::net::WireEncodeUnsubscribe(wpi::util::raw_ostream& os, int subuid) { + wpi::util::json::serializer s{os, ' ', 0}; os << "{\"method\":\"" << UnsubscribeMsg::kMethodStr << "\",\"params\":{"; os << "\"subuid\":"; s.dump_integer(subuid); os << "}}"; } -bool nt::net::WireEncodeText(wpi::raw_ostream& os, const ClientMessage& msg) { +bool wpi::nt::net::WireEncodeText(wpi::util::raw_ostream& os, const ClientMessage& msg) { if (auto m = std::get_if(&msg.contents)) { WireEncodePublish(os, m->pubuid, m->name, m->typeStr, m->properties); } else if (auto m = std::get_if(&msg.contents)) { @@ -149,11 +149,11 @@ bool nt::net::WireEncodeText(wpi::raw_ostream& os, const ClientMessage& msg) { return true; } -void nt::net::WireEncodeAnnounce(wpi::raw_ostream& os, std::string_view name, +void wpi::nt::net::WireEncodeAnnounce(wpi::util::raw_ostream& os, std::string_view name, int id, std::string_view typeStr, - const wpi::json& properties, + const wpi::util::json& properties, std::optional pubuid) { - wpi::json::serializer s{os, ' ', 0}; + wpi::util::json::serializer s{os, ' ', 0}; os << "{\"method\":\"" << AnnounceMsg::kMethodStr << "\",\"params\":{"; os << "\"id\":"; s.dump_integer(id); @@ -170,9 +170,9 @@ void nt::net::WireEncodeAnnounce(wpi::raw_ostream& os, std::string_view name, os << "\"}}"; } -void nt::net::WireEncodeUnannounce(wpi::raw_ostream& os, std::string_view name, +void wpi::nt::net::WireEncodeUnannounce(wpi::util::raw_ostream& os, std::string_view name, int64_t id) { - wpi::json::serializer s{os, ' ', 0}; + wpi::util::json::serializer s{os, ' ', 0}; os << "{\"method\":\"" << UnannounceMsg::kMethodStr << "\",\"params\":{"; os << "\"id\":"; s.dump_integer(id); @@ -181,10 +181,10 @@ void nt::net::WireEncodeUnannounce(wpi::raw_ostream& os, std::string_view name, os << "\"}}"; } -void nt::net::WireEncodePropertiesUpdate(wpi::raw_ostream& os, +void wpi::nt::net::WireEncodePropertiesUpdate(wpi::util::raw_ostream& os, std::string_view name, - const wpi::json& update, bool ack) { - wpi::json::serializer s{os, ' ', 0}; + const wpi::util::json& update, bool ack) { + wpi::util::json::serializer s{os, ' ', 0}; os << "{\"method\":\"" << PropertiesUpdateMsg::kMethodStr << "\",\"params\":{"; os << "\"name\":\""; @@ -197,7 +197,7 @@ void nt::net::WireEncodePropertiesUpdate(wpi::raw_ostream& os, os << "}}"; } -bool nt::net::WireEncodeText(wpi::raw_ostream& os, const ServerMessage& msg) { +bool wpi::nt::net::WireEncodeText(wpi::util::raw_ostream& os, const ServerMessage& msg) { if (auto m = std::get_if(&msg.contents)) { WireEncodeAnnounce(os, m->name, m->id, m->typeStr, m->properties, m->pubuid); @@ -211,7 +211,7 @@ bool nt::net::WireEncodeText(wpi::raw_ostream& os, const ServerMessage& msg) { return true; } -bool nt::net::WireEncodeBinary(wpi::raw_ostream& os, int id, int64_t time, +bool wpi::nt::net::WireEncodeBinary(wpi::util::raw_ostream& os, int id, int64_t time, const Value& value) { char buf[128]; mpack_writer_t writer; @@ -219,7 +219,7 @@ bool nt::net::WireEncodeBinary(wpi::raw_ostream& os, int id, int64_t time, mpack_writer_set_context(&writer, &os); mpack_writer_set_flush( &writer, [](mpack_writer_t* writer, const char* buffer, size_t count) { - static_cast(writer->context)->write(buffer, count); + static_cast(writer->context)->write(buffer, count); }); mpack_start_array(&writer, 4); mpack_write_int(&writer, id); diff --git a/ntcore/src/main/native/cpp/net/WireEncoder.hpp b/ntcore/src/main/native/cpp/net/WireEncoder.hpp index ea1b5228e1..394cc27fdd 100644 --- a/ntcore/src/main/native/cpp/net/WireEncoder.hpp +++ b/ntcore/src/main/native/cpp/net/WireEncoder.hpp @@ -11,51 +11,51 @@ #include "wpi/util/json_fwd.hpp" -namespace wpi { +namespace wpi::util { class raw_ostream; } // namespace wpi -namespace nt { +namespace wpi::nt { class PubSubOptionsImpl; class Value; -} // namespace nt +} // namespace wpi::nt -namespace nt::net { +namespace wpi::nt::net { struct ClientMessage; struct ServerMessage; // encoders for client text messages (avoids need to construct a Message struct) -void WireEncodePublish(wpi::raw_ostream& os, int pubuid, std::string_view name, - std::string_view typeStr, const wpi::json& properties); -void WireEncodeUnpublish(wpi::raw_ostream& os, int pubuid); -void WireEncodeSetProperties(wpi::raw_ostream& os, std::string_view name, - const wpi::json& update); -void WireEncodeSubscribe(wpi::raw_ostream& os, int subuid, +void WireEncodePublish(wpi::util::raw_ostream& os, int pubuid, std::string_view name, + std::string_view typeStr, const wpi::util::json& properties); +void WireEncodeUnpublish(wpi::util::raw_ostream& os, int pubuid); +void WireEncodeSetProperties(wpi::util::raw_ostream& os, std::string_view name, + const wpi::util::json& update); +void WireEncodeSubscribe(wpi::util::raw_ostream& os, int subuid, std::span topicNames, const PubSubOptionsImpl& options); -void WireEncodeSubscribe(wpi::raw_ostream& os, int subuid, +void WireEncodeSubscribe(wpi::util::raw_ostream& os, int subuid, std::span topicNames, const PubSubOptionsImpl& options); -void WireEncodeUnsubscribe(wpi::raw_ostream& os, int subuid); +void WireEncodeUnsubscribe(wpi::util::raw_ostream& os, int subuid); // encoders for server text messages (avoids need to construct a Message struct) -void WireEncodeAnnounce(wpi::raw_ostream& os, std::string_view name, int id, - std::string_view typeStr, const wpi::json& properties, +void WireEncodeAnnounce(wpi::util::raw_ostream& os, std::string_view name, int id, + std::string_view typeStr, const wpi::util::json& properties, std::optional pubuid); -void WireEncodeUnannounce(wpi::raw_ostream& os, std::string_view name, +void WireEncodeUnannounce(wpi::util::raw_ostream& os, std::string_view name, int64_t id); -void WireEncodePropertiesUpdate(wpi::raw_ostream& os, std::string_view name, - const wpi::json& update, bool ack); +void WireEncodePropertiesUpdate(wpi::util::raw_ostream& os, std::string_view name, + const wpi::util::json& update, bool ack); // Encode a single message; note text messages must be put into a // JSON array "[msg1, msg2]" for transmission. // Returns true if message was written -bool WireEncodeText(wpi::raw_ostream& os, const ClientMessage& msg); -bool WireEncodeText(wpi::raw_ostream& os, const ServerMessage& msg); +bool WireEncodeText(wpi::util::raw_ostream& os, const ClientMessage& msg); +bool WireEncodeText(wpi::util::raw_ostream& os, const ServerMessage& msg); // encoder for binary messages -bool WireEncodeBinary(wpi::raw_ostream& os, int id, int64_t time, +bool WireEncodeBinary(wpi::util::raw_ostream& os, int id, int64_t time, const Value& value); -} // namespace nt::net +} // namespace wpi::nt::net diff --git a/ntcore/src/main/native/cpp/networktables/NTSendable.cpp b/ntcore/src/main/native/cpp/networktables/NTSendable.cpp index 1901a2b463..62825dab96 100644 --- a/ntcore/src/main/native/cpp/networktables/NTSendable.cpp +++ b/ntcore/src/main/native/cpp/networktables/NTSendable.cpp @@ -7,10 +7,10 @@ #include "wpi/nt/NTSendableBuilder.hpp" #include "wpi/util/sendable/SendableBuilder.hpp" -using namespace nt; +using namespace wpi::nt; -void NTSendable::InitSendable(wpi::SendableBuilder& builder) { - if (builder.GetBackendKind() == wpi::SendableBuilder::kNetworkTables) { +void NTSendable::InitSendable(wpi::util::SendableBuilder& builder) { + if (builder.GetBackendKind() == wpi::util::SendableBuilder::kNetworkTables) { InitSendable(static_cast(builder)); } } diff --git a/ntcore/src/main/native/cpp/networktables/NTSendableBuilder.cpp b/ntcore/src/main/native/cpp/networktables/NTSendableBuilder.cpp index 0681127e7c..99b7ee7491 100644 --- a/ntcore/src/main/native/cpp/networktables/NTSendableBuilder.cpp +++ b/ntcore/src/main/native/cpp/networktables/NTSendableBuilder.cpp @@ -4,7 +4,7 @@ #include "wpi/nt/NTSendableBuilder.hpp" -using namespace nt; +using namespace wpi::nt; NTSendableBuilder::BackendKind NTSendableBuilder::GetBackendKind() const { return kNetworkTables; diff --git a/ntcore/src/main/native/cpp/networktables/NetworkTable.cpp b/ntcore/src/main/native/cpp/networktables/NetworkTable.cpp index c965ba7584..5f6f663fd4 100644 --- a/ntcore/src/main/native/cpp/networktables/NetworkTable.cpp +++ b/ntcore/src/main/native/cpp/networktables/NetworkTable.cpp @@ -30,31 +30,31 @@ #include "wpi/util/StringExtras.hpp" #include "wpi/util/StringMap.hpp" -using namespace nt; +using namespace wpi::nt; std::string_view NetworkTable::BasenameKey(std::string_view key) { size_t slash = key.rfind(PATH_SEPARATOR_CHAR); if (slash == std::string_view::npos) { return key; } - return wpi::substr(key, slash + 1); + return wpi::util::substr(key, slash + 1); } std::string NetworkTable::NormalizeKey(std::string_view key, bool withLeadingSlash) { - wpi::SmallString<128> buf; + wpi::util::SmallString<128> buf; return std::string{NormalizeKey(key, buf, withLeadingSlash)}; } std::string_view NetworkTable::NormalizeKey(std::string_view key, - wpi::SmallVectorImpl& buf, + wpi::util::SmallVectorImpl& buf, bool withLeadingSlash) { buf.clear(); if (withLeadingSlash) { buf.push_back(PATH_SEPARATOR_CHAR); } // for each path element, add it with a slash following - wpi::split(key, PATH_SEPARATOR_CHAR, -1, false, [&](auto part) { + wpi::util::split(key, PATH_SEPARATOR_CHAR, -1, false, [&](auto part) { buf.append(part.begin(), part.end()); buf.push_back(PATH_SEPARATOR_CHAR); }); @@ -69,9 +69,9 @@ std::vector NetworkTable::GetHierarchy(std::string_view key) { std::vector hierarchy; hierarchy.emplace_back(1, PATH_SEPARATOR_CHAR); // for each path element, add it to the end of what we built previously - wpi::SmallString<128> path; + wpi::util::SmallString<128> path; bool any = false; - wpi::split(key, PATH_SEPARATOR_CHAR, -1, false, [&](auto part) { + wpi::util::split(key, PATH_SEPARATOR_CHAR, -1, false, [&](auto part) { any = true; path += PATH_SEPARATOR_CHAR; path += part; @@ -101,7 +101,7 @@ NetworkTableEntry NetworkTable::GetEntry(std::string_view key) const { if (entry == 0) { fmt::memory_buffer buf; fmt::format_to(fmt::appender{buf}, "{}/{}", m_path, key); - entry = nt::GetEntry(m_inst, {buf.data(), buf.size()}); + entry = wpi::nt::GetEntry(m_inst, {buf.data(), buf.size()}); } return NetworkTableEntry{entry}; } @@ -109,7 +109,7 @@ NetworkTableEntry NetworkTable::GetEntry(std::string_view key) const { Topic NetworkTable::GetTopic(std::string_view name) const { fmt::memory_buffer buf; fmt::format_to(fmt::appender{buf}, "{}/{}", m_path, name); - return Topic{::nt::GetTopic(m_inst, {buf.data(), buf.size()})}; + return Topic{::wpi::nt::GetTopic(m_inst, {buf.data(), buf.size()})}; } BooleanTopic NetworkTable::GetBooleanTopic(std::string_view name) const { @@ -174,7 +174,7 @@ bool NetworkTable::ContainsKey(std::string_view key) const { } bool NetworkTable::ContainsSubTable(std::string_view key) const { - return !::nt::GetTopics(m_inst, fmt::format("{}/{}/", m_path, key), 0) + return !::wpi::nt::GetTopics(m_inst, fmt::format("{}/{}/", m_path, key), 0) .empty(); } @@ -182,8 +182,8 @@ std::vector NetworkTable::GetTopicInfo(int types) const { std::vector infos; size_t prefix_len = m_path.size() + 1; for (auto&& info : - ::nt::GetTopicInfo(m_inst, fmt::format("{}/", m_path), types)) { - auto relative_key = wpi::substr(info.name, prefix_len); + ::wpi::nt::GetTopicInfo(m_inst, fmt::format("{}/", m_path), types)) { + auto relative_key = wpi::util::substr(info.name, prefix_len); if (relative_key.find(PATH_SEPARATOR_CHAR) != std::string_view::npos) { continue; } @@ -196,8 +196,8 @@ std::vector NetworkTable::GetTopics(int types) const { std::vector topics; size_t prefix_len = m_path.size() + 1; for (auto&& info : - ::nt::GetTopicInfo(m_inst, fmt::format("{}/", m_path), types)) { - auto relative_key = wpi::substr(info.name, prefix_len); + ::wpi::nt::GetTopicInfo(m_inst, fmt::format("{}/", m_path), types)) { + auto relative_key = wpi::util::substr(info.name, prefix_len); if (relative_key.find(PATH_SEPARATOR_CHAR) != std::string_view::npos) { continue; } @@ -210,8 +210,8 @@ std::vector NetworkTable::GetKeys(int types) const { std::vector keys; size_t prefix_len = m_path.size() + 1; for (auto&& info : - ::nt::GetTopicInfo(m_inst, fmt::format("{}/", m_path), types)) { - auto relative_key = wpi::substr(info.name, prefix_len); + ::wpi::nt::GetTopicInfo(m_inst, fmt::format("{}/", m_path), types)) { + auto relative_key = wpi::util::substr(info.name, prefix_len); if (relative_key.find(PATH_SEPARATOR_CHAR) != std::string_view::npos) { continue; } @@ -224,13 +224,13 @@ std::vector NetworkTable::GetSubTables() const { std::vector keys; size_t prefix_len = m_path.size() + 1; for (auto&& topic : - ::nt::GetTopicInfo(m_inst, fmt::format("{}/", m_path), 0)) { - auto relative_key = wpi::substr(topic.name, prefix_len); + ::wpi::nt::GetTopicInfo(m_inst, fmt::format("{}/", m_path), 0)) { + auto relative_key = wpi::util::substr(topic.name, prefix_len); size_t end_subtable = relative_key.find(PATH_SEPARATOR_CHAR); if (end_subtable == std::string_view::npos) { continue; } - auto subTable = wpi::substr(relative_key, 0, end_subtable); + auto subTable = wpi::util::substr(relative_key, 0, end_subtable); if (keys.empty() || keys.back() != subTable) { keys.emplace_back(subTable); } @@ -384,7 +384,7 @@ NT_Listener NetworkTable::AddListener(int eventMask, } else { return; } - auto relative_key = wpi::substr(topicName, m_path.size() + 1); + auto relative_key = wpi::util::substr(topicName, m_path.size() + 1); if (relative_key.find(PATH_SEPARATOR_CHAR) != std::string_view::npos) { return; } @@ -401,9 +401,9 @@ NT_Listener NetworkTable::AddListener(std::string_view key, int eventMask, } NT_Listener NetworkTable::AddSubTableListener(SubTableListener listener) { - // The lambda needs to be copyable, but StringMap is not, so use + // The lambda needs to be copyable, but wpi::util::StringMap is not, so use // a shared_ptr to it. - auto notified_tables = std::make_shared>(); + auto notified_tables = std::make_shared>(); return NetworkTableInstance{m_inst}.AddListener( {{fmt::format("{}/", m_path)}}, NT_EVENT_PUBLISH | NT_EVENT_IMMEDIATE, @@ -412,7 +412,7 @@ NT_Listener NetworkTable::AddSubTableListener(SubTableListener listener) { if (!topicInfo) { return; } - auto relative_key = wpi::substr(topicInfo->name, m_path.size() + 1); + auto relative_key = wpi::util::substr(topicInfo->name, m_path.size() + 1); auto end_sub_table = relative_key.find(PATH_SEPARATOR_CHAR); if (end_sub_table == std::string_view::npos) { return; diff --git a/ntcore/src/main/native/cpp/networktables/NetworkTableEntry.cpp b/ntcore/src/main/native/cpp/networktables/NetworkTableEntry.cpp index 9912b46914..52c29bfdcf 100644 --- a/ntcore/src/main/native/cpp/networktables/NetworkTableEntry.cpp +++ b/ntcore/src/main/native/cpp/networktables/NetworkTableEntry.cpp @@ -7,12 +7,12 @@ #include "wpi/nt/NetworkTableInstance.hpp" #include "wpi/nt/Topic.hpp" -using namespace nt; +using namespace wpi::nt; NetworkTableInstance NetworkTableEntry::GetInstance() const { return NetworkTableInstance{GetInstanceFromHandle(m_handle)}; } Topic NetworkTableEntry::GetTopic() const { - return Topic{::nt::GetTopicFromHandle(m_handle)}; + return Topic{::wpi::nt::GetTopicFromHandle(m_handle)}; } diff --git a/ntcore/src/main/native/cpp/networktables/NetworkTableInstance.cpp b/ntcore/src/main/native/cpp/networktables/NetworkTableInstance.cpp index bee3228035..8e2e81df72 100644 --- a/ntcore/src/main/native/cpp/networktables/NetworkTableInstance.cpp +++ b/ntcore/src/main/native/cpp/networktables/NetworkTableInstance.cpp @@ -24,10 +24,10 @@ #include "wpi/util/SmallVector.hpp" #include "wpi/util/print.hpp" -using namespace nt; +using namespace wpi::nt; Topic NetworkTableInstance::GetTopic(std::string_view name) const { - return Topic{::nt::GetTopic(m_handle, name)}; + return Topic{::wpi::nt::GetTopic(m_handle, name)}; } BooleanTopic NetworkTableInstance::GetBooleanTopic( @@ -108,41 +108,41 @@ void NetworkTableInstance::SetServer(std::span servers, NT_Listener NetworkTableInstance::AddListener(Topic topic, unsigned int eventMask, ListenerCallback listener) { - if (::nt::GetInstanceFromHandle(topic.GetHandle()) != m_handle) { - wpi::print(stderr, "AddListener: topic is not from this instance\n"); + if (::wpi::nt::GetInstanceFromHandle(topic.GetHandle()) != m_handle) { + wpi::util::print(stderr, "AddListener: topic is not from this instance\n"); return 0; } - return ::nt::AddListener(topic.GetHandle(), eventMask, std::move(listener)); + return ::wpi::nt::AddListener(topic.GetHandle(), eventMask, std::move(listener)); } NT_Listener NetworkTableInstance::AddListener(Subscriber& subscriber, unsigned int eventMask, ListenerCallback listener) { - if (::nt::GetInstanceFromHandle(subscriber.GetHandle()) != m_handle) { - wpi::print(stderr, "AddListener: subscriber is not from this instance\n"); + if (::wpi::nt::GetInstanceFromHandle(subscriber.GetHandle()) != m_handle) { + wpi::util::print(stderr, "AddListener: subscriber is not from this instance\n"); return 0; } - return ::nt::AddListener(subscriber.GetHandle(), eventMask, + return ::wpi::nt::AddListener(subscriber.GetHandle(), eventMask, std::move(listener)); } NT_Listener NetworkTableInstance::AddListener(const NetworkTableEntry& entry, int eventMask, ListenerCallback listener) { - if (::nt::GetInstanceFromHandle(entry.GetHandle()) != m_handle) { - wpi::print(stderr, "AddListener: entry is not from this instance\n"); + if (::wpi::nt::GetInstanceFromHandle(entry.GetHandle()) != m_handle) { + wpi::util::print(stderr, "AddListener: entry is not from this instance\n"); return 0; } - return ::nt::AddListener(entry.GetHandle(), eventMask, std::move(listener)); + return ::wpi::nt::AddListener(entry.GetHandle(), eventMask, std::move(listener)); } NT_Listener NetworkTableInstance::AddListener(MultiSubscriber& subscriber, int eventMask, ListenerCallback listener) { - if (::nt::GetInstanceFromHandle(subscriber.GetHandle()) != m_handle) { - wpi::print(stderr, "AddListener: subscriber is not from this instance\n"); + if (::wpi::nt::GetInstanceFromHandle(subscriber.GetHandle()) != m_handle) { + wpi::util::print(stderr, "AddListener: subscriber is not from this instance\n"); return 0; } - return ::nt::AddListener(subscriber.GetHandle(), eventMask, + return ::wpi::nt::AddListener(subscriber.GetHandle(), eventMask, std::move(listener)); } diff --git a/ntcore/src/main/native/cpp/networktables/Topic.cpp b/ntcore/src/main/native/cpp/networktables/Topic.cpp index 8a92e65fb2..6e47dcefb5 100644 --- a/ntcore/src/main/native/cpp/networktables/Topic.cpp +++ b/ntcore/src/main/native/cpp/networktables/Topic.cpp @@ -8,22 +8,22 @@ #include "wpi/nt/NetworkTableInstance.hpp" #include "wpi/util/json.hpp" -using namespace nt; +using namespace wpi::nt; NetworkTableInstance Topic::GetInstance() const { return NetworkTableInstance{GetInstanceFromHandle(m_handle)}; } -wpi::json Topic::GetProperty(std::string_view name) const { - return ::nt::GetTopicProperty(m_handle, name); +wpi::util::json Topic::GetProperty(std::string_view name) const { + return ::wpi::nt::GetTopicProperty(m_handle, name); } -void Topic::SetProperty(std::string_view name, const wpi::json& value) { - ::nt::SetTopicProperty(m_handle, name, value); +void Topic::SetProperty(std::string_view name, const wpi::util::json& value) { + ::wpi::nt::SetTopicProperty(m_handle, name, value); } -wpi::json Topic::GetProperties() const { - return ::nt::GetTopicProperties(m_handle); +wpi::util::json Topic::GetProperties() const { + return ::wpi::nt::GetTopicProperties(m_handle); } GenericSubscriber Topic::GenericSubscribe(const PubSubOptions& options) { @@ -32,21 +32,21 @@ GenericSubscriber Topic::GenericSubscribe(const PubSubOptions& options) { GenericSubscriber Topic::GenericSubscribe(std::string_view typeString, const PubSubOptions& options) { - return GenericSubscriber{::nt::Subscribe( - m_handle, ::nt::GetTypeFromString(typeString), typeString, options)}; + return GenericSubscriber{::wpi::nt::Subscribe( + m_handle, ::wpi::nt::GetTypeFromString(typeString), typeString, options)}; } GenericPublisher Topic::GenericPublish(std::string_view typeString, const PubSubOptions& options) { - return GenericPublisher{::nt::Publish( - m_handle, ::nt::GetTypeFromString(typeString), typeString, options)}; + return GenericPublisher{::wpi::nt::Publish( + m_handle, ::wpi::nt::GetTypeFromString(typeString), typeString, options)}; } GenericPublisher Topic::GenericPublishEx(std::string_view typeString, - const wpi::json& properties, + const wpi::util::json& properties, const PubSubOptions& options) { - return GenericPublisher{::nt::PublishEx(m_handle, - ::nt::GetTypeFromString(typeString), + return GenericPublisher{::wpi::nt::PublishEx(m_handle, + ::wpi::nt::GetTypeFromString(typeString), typeString, properties, options)}; } @@ -56,8 +56,8 @@ GenericEntry Topic::GetGenericEntry(const PubSubOptions& options) { GenericEntry Topic::GetGenericEntry(std::string_view typeString, const PubSubOptions& options) { - return GenericEntry{::nt::GetEntry( - m_handle, ::nt::GetTypeFromString(typeString), typeString, options)}; + return GenericEntry{::wpi::nt::GetEntry( + m_handle, ::wpi::nt::GetTypeFromString(typeString), typeString, options)}; } void Publisher::anchor() {} diff --git a/ntcore/src/main/native/cpp/ntcore_c.cpp b/ntcore/src/main/native/cpp/ntcore_c.cpp index 9386ba3f94..93ea56dbc3 100644 --- a/ntcore/src/main/native/cpp/ntcore_c.cpp +++ b/ntcore/src/main/native/cpp/ntcore_c.cpp @@ -21,7 +21,7 @@ #include "wpi/util/json.hpp" #include "wpi/util/timestamp.h" -using namespace nt; +using namespace wpi::nt; // Conversion helpers @@ -138,19 +138,19 @@ extern "C" { */ NT_Inst NT_GetDefaultInstance(void) { - return nt::GetDefaultInstance(); + return wpi::nt::GetDefaultInstance(); } NT_Inst NT_CreateInstance(void) { - return nt::CreateInstance(); + return wpi::nt::CreateInstance(); } void NT_DestroyInstance(NT_Inst inst) { - return nt::DestroyInstance(inst); + return wpi::nt::DestroyInstance(inst); } NT_Inst NT_GetInstanceFromHandle(NT_Handle handle) { - return nt::GetInstanceFromHandle(handle); + return wpi::nt::GetInstanceFromHandle(handle); } /* @@ -158,19 +158,19 @@ NT_Inst NT_GetInstanceFromHandle(NT_Handle handle) { */ NT_Entry NT_GetEntry(NT_Inst inst, const struct WPI_String* name) { - return nt::GetEntry(inst, wpi::to_string_view(name)); + return wpi::nt::GetEntry(inst, wpi::util::to_string_view(name)); } void NT_GetEntryName(NT_Entry entry, struct WPI_String* name) { - nt::ConvertToC(nt::GetEntryName(entry), name); + wpi::nt::ConvertToC(wpi::nt::GetEntryName(entry), name); } enum NT_Type NT_GetEntryType(NT_Entry entry) { - return nt::GetEntryType(entry); + return wpi::nt::GetEntryType(entry); } uint64_t NT_GetEntryLastChange(NT_Entry entry) { - return nt::GetEntryLastChange(entry); + return wpi::nt::GetEntryLastChange(entry); } void NT_GetEntryValue(NT_Entry entry, struct NT_Value* value) { @@ -180,7 +180,7 @@ void NT_GetEntryValue(NT_Entry entry, struct NT_Value* value) { void NT_GetEntryValueType(NT_Entry entry, unsigned int types, struct NT_Value* value) { NT_InitValue(value); - auto v = nt::GetEntryValue(entry); + auto v = wpi::nt::GetEntryValue(entry); if (!v) { return; } @@ -192,52 +192,52 @@ void NT_GetEntryValueType(NT_Entry entry, unsigned int types, int NT_SetDefaultEntryValue(NT_Entry entry, const struct NT_Value* default_value) { - return nt::SetDefaultEntryValue(entry, ConvertFromC(*default_value)); + return wpi::nt::SetDefaultEntryValue(entry, ConvertFromC(*default_value)); } int NT_SetEntryValue(NT_Entry entry, const struct NT_Value* value) { - return nt::SetEntryValue(entry, ConvertFromC(*value)); + return wpi::nt::SetEntryValue(entry, ConvertFromC(*value)); } void NT_SetEntryFlags(NT_Entry entry, unsigned int flags) { - nt::SetEntryFlags(entry, flags); + wpi::nt::SetEntryFlags(entry, flags); } unsigned int NT_GetEntryFlags(NT_Entry entry) { - return nt::GetEntryFlags(entry); + return wpi::nt::GetEntryFlags(entry); } struct NT_Value* NT_ReadQueueValue(NT_Handle subentry, size_t* count) { - return ConvertToC(nt::ReadQueueValue(subentry), count); + return ConvertToC(wpi::nt::ReadQueueValue(subentry), count); } struct NT_Value* NT_ReadQueueValueType(NT_Handle subentry, unsigned int types, size_t* count) { - return ConvertToC(nt::ReadQueueValue(subentry, types), count); + return ConvertToC(wpi::nt::ReadQueueValue(subentry, types), count); } NT_Topic* NT_GetTopics(NT_Inst inst, const struct WPI_String* prefix, unsigned int types, size_t* count) { - auto info_v = nt::GetTopics(inst, wpi::to_string_view(prefix), types); + auto info_v = wpi::nt::GetTopics(inst, wpi::util::to_string_view(prefix), types); return ConvertToC(info_v, count); } NT_Topic* NT_GetTopicsStr(NT_Inst inst, const struct WPI_String* prefix, const struct WPI_String* types, size_t types_len, size_t* count) { - wpi::SmallVector typesCpp; + wpi::util::SmallVector typesCpp; typesCpp.reserve(types_len); for (size_t i = 0; i < types_len; ++i) { - typesCpp.emplace_back(wpi::to_string_view(&types[i])); + typesCpp.emplace_back(wpi::util::to_string_view(&types[i])); } - auto info_v = nt::GetTopics(inst, wpi::to_string_view(prefix), typesCpp); + auto info_v = wpi::nt::GetTopics(inst, wpi::util::to_string_view(prefix), typesCpp); return ConvertToC(info_v, count); } struct NT_TopicInfo* NT_GetTopicInfos(NT_Inst inst, const struct WPI_String* prefix, unsigned int types, size_t* count) { - auto info_v = nt::GetTopicInfo(inst, wpi::to_string_view(prefix), types); + auto info_v = wpi::nt::GetTopicInfo(inst, wpi::util::to_string_view(prefix), types); return ConvertToC(info_v, count); } @@ -245,17 +245,17 @@ struct NT_TopicInfo* NT_GetTopicInfosStr(NT_Inst inst, const struct WPI_String* prefix, const struct WPI_String* types, size_t types_len, size_t* count) { - wpi::SmallVector typesCpp; + wpi::util::SmallVector typesCpp; typesCpp.reserve(types_len); for (size_t i = 0; i < types_len; ++i) { - typesCpp.emplace_back(wpi::to_string_view(&types[i])); + typesCpp.emplace_back(wpi::util::to_string_view(&types[i])); } - auto info_v = nt::GetTopicInfo(inst, wpi::to_string_view(prefix), typesCpp); + auto info_v = wpi::nt::GetTopicInfo(inst, wpi::util::to_string_view(prefix), typesCpp); return ConvertToC(info_v, count); } NT_Bool NT_GetTopicInfo(NT_Topic topic, struct NT_TopicInfo* info) { - auto info_v = nt::GetTopicInfo(topic); + auto info_v = wpi::nt::GetTopicInfo(topic); if (info_v.name.empty()) { return false; } @@ -264,102 +264,102 @@ NT_Bool NT_GetTopicInfo(NT_Topic topic, struct NT_TopicInfo* info) { } NT_Topic NT_GetTopic(NT_Inst inst, const struct WPI_String* name) { - return nt::GetTopic(inst, wpi::to_string_view(name)); + return wpi::nt::GetTopic(inst, wpi::util::to_string_view(name)); } void NT_GetTopicName(NT_Topic topic, struct WPI_String* name) { - nt::ConvertToC(nt::GetTopicName(topic), name); + wpi::nt::ConvertToC(wpi::nt::GetTopicName(topic), name); } NT_Type NT_GetTopicType(NT_Topic topic) { - return nt::GetTopicType(topic); + return wpi::nt::GetTopicType(topic); } void NT_GetTopicTypeString(NT_Topic topic, struct WPI_String* type) { - nt::ConvertToC(nt::GetTopicTypeString(topic), type); + wpi::nt::ConvertToC(wpi::nt::GetTopicTypeString(topic), type); } void NT_SetTopicPersistent(NT_Topic topic, NT_Bool value) { - nt::SetTopicPersistent(topic, value); + wpi::nt::SetTopicPersistent(topic, value); } NT_Bool NT_GetTopicPersistent(NT_Topic topic) { - return nt::GetTopicPersistent(topic); + return wpi::nt::GetTopicPersistent(topic); } void NT_SetTopicRetained(NT_Topic topic, NT_Bool value) { - nt::SetTopicRetained(topic, value); + wpi::nt::SetTopicRetained(topic, value); } NT_Bool NT_GetTopicRetained(NT_Topic topic) { - return nt::GetTopicRetained(topic); + return wpi::nt::GetTopicRetained(topic); } void NT_SetTopicCached(NT_Topic topic, NT_Bool value) { - nt::SetTopicCached(topic, value); + wpi::nt::SetTopicCached(topic, value); } NT_Bool NT_GetTopicCached(NT_Topic topic) { - return nt::GetTopicCached(topic); + return wpi::nt::GetTopicCached(topic); } NT_Bool NT_GetTopicExists(NT_Handle handle) { - return nt::GetTopicExists(handle); + return wpi::nt::GetTopicExists(handle); } void NT_GetTopicProperty(NT_Topic topic, const struct WPI_String* name, struct WPI_String* prop) { - wpi::json j = nt::GetTopicProperty(topic, wpi::to_string_view(name)); - nt::ConvertToC(j.dump(), prop); + wpi::util::json j = wpi::nt::GetTopicProperty(topic, wpi::util::to_string_view(name)); + wpi::nt::ConvertToC(j.dump(), prop); } NT_Bool NT_SetTopicProperty(NT_Topic topic, const struct WPI_String* name, const struct WPI_String* value) { - wpi::json j; + wpi::util::json j; try { - j = wpi::json::parse(wpi::to_string_view(value)); - } catch (wpi::json::parse_error&) { + j = wpi::util::json::parse(wpi::util::to_string_view(value)); + } catch (wpi::util::json::parse_error&) { return false; } - nt::SetTopicProperty(topic, wpi::to_string_view(name), j); + wpi::nt::SetTopicProperty(topic, wpi::util::to_string_view(name), j); return true; } void NT_DeleteTopicProperty(NT_Topic topic, const struct WPI_String* name) { - nt::DeleteTopicProperty(topic, wpi::to_string_view(name)); + wpi::nt::DeleteTopicProperty(topic, wpi::util::to_string_view(name)); } void NT_GetTopicProperties(NT_Topic topic, struct WPI_String* property) { - wpi::json j = nt::GetTopicProperties(topic); - nt::ConvertToC(j.dump(), property); + wpi::util::json j = wpi::nt::GetTopicProperties(topic); + wpi::nt::ConvertToC(j.dump(), property); } NT_Bool NT_SetTopicProperties(NT_Topic topic, const struct WPI_String* properties) { - wpi::json j; + wpi::util::json j; try { - j = wpi::json::parse(wpi::to_string_view(properties)); - } catch (wpi::json::parse_error&) { + j = wpi::util::json::parse(wpi::util::to_string_view(properties)); + } catch (wpi::util::json::parse_error&) { return false; } - return nt::SetTopicProperties(topic, j); + return wpi::nt::SetTopicProperties(topic, j); } NT_Subscriber NT_Subscribe(NT_Topic topic, NT_Type type, const struct WPI_String* typeStr, const struct NT_PubSubOptions* options) { - return nt::Subscribe(topic, type, wpi::to_string_view(typeStr), + return wpi::nt::Subscribe(topic, type, wpi::util::to_string_view(typeStr), ConvertToCpp(options)); } void NT_Unsubscribe(NT_Subscriber sub) { - return nt::Unsubscribe(sub); + return wpi::nt::Unsubscribe(sub); } NT_Publisher NT_Publish(NT_Topic topic, NT_Type type, const struct WPI_String* typeStr, const struct NT_PubSubOptions* options) { - return nt::Publish(topic, type, wpi::to_string_view(typeStr), + return wpi::nt::Publish(topic, type, wpi::util::to_string_view(typeStr), ConvertToCpp(options)); } @@ -367,58 +367,58 @@ NT_Publisher NT_PublishEx(NT_Topic topic, NT_Type type, const struct WPI_String* typeStr, const struct WPI_String* properties, const struct NT_PubSubOptions* options) { - wpi::json j; + wpi::util::json j; if (properties->len == 0) { // gracefully handle empty string - j = wpi::json::object(); + j = wpi::util::json::object(); } else { try { - j = wpi::json::parse(wpi::to_string_view(properties)); - } catch (wpi::json::parse_error&) { + j = wpi::util::json::parse(wpi::util::to_string_view(properties)); + } catch (wpi::util::json::parse_error&) { return {}; } } - return nt::PublishEx(topic, type, wpi::to_string_view(typeStr), j, + return wpi::nt::PublishEx(topic, type, wpi::util::to_string_view(typeStr), j, ConvertToCpp(options)); } void NT_Unpublish(NT_Handle pubentry) { - return nt::Unpublish(pubentry); + return wpi::nt::Unpublish(pubentry); } NT_Entry NT_GetEntryEx(NT_Topic topic, NT_Type type, const struct WPI_String* typeStr, const struct NT_PubSubOptions* options) { - return nt::GetEntry(topic, type, wpi::to_string_view(typeStr), + return wpi::nt::GetEntry(topic, type, wpi::util::to_string_view(typeStr), ConvertToCpp(options)); } void NT_ReleaseEntry(NT_Entry entry) { - nt::ReleaseEntry(entry); + wpi::nt::ReleaseEntry(entry); } void NT_Release(NT_Handle pubsubentry) { - nt::Release(pubsubentry); + wpi::nt::Release(pubsubentry); } NT_Topic NT_GetTopicFromHandle(NT_Handle pubsubentry) { - return nt::GetTopicFromHandle(pubsubentry); + return wpi::nt::GetTopicFromHandle(pubsubentry); } NT_MultiSubscriber NT_SubscribeMultiple( NT_Inst inst, const struct WPI_String* prefixes, size_t prefixes_len, const struct NT_PubSubOptions* options) { - wpi::SmallVector p; + wpi::util::SmallVector p; p.resize_for_overwrite(prefixes_len); for (size_t i = 0; i < prefixes_len; ++i) { - p[i] = wpi::to_string_view(&prefixes[i]); + p[i] = wpi::util::to_string_view(&prefixes[i]); } - return nt::SubscribeMultiple(inst, p, ConvertToCpp(options)); + return wpi::nt::SubscribeMultiple(inst, p, ConvertToCpp(options)); } void NT_UnsubscribeMultiple(NT_MultiSubscriber sub) { - nt::UnsubscribeMultiple(sub); + wpi::nt::UnsubscribeMultiple(sub); } /* @@ -426,31 +426,31 @@ void NT_UnsubscribeMultiple(NT_MultiSubscriber sub) { */ NT_ListenerPoller NT_CreateListenerPoller(NT_Inst inst) { - return nt::CreateListenerPoller(inst); + return wpi::nt::CreateListenerPoller(inst); } void NT_DestroyListenerPoller(NT_ListenerPoller poller) { - nt::DestroyListenerPoller(poller); + wpi::nt::DestroyListenerPoller(poller); } struct NT_Event* NT_ReadListenerQueue(NT_ListenerPoller poller, size_t* len) { - auto arr_cpp = nt::ReadListenerQueue(poller); + auto arr_cpp = wpi::nt::ReadListenerQueue(poller); return ConvertToC(arr_cpp, len); } void NT_RemoveListener(NT_Listener listener) { - nt::RemoveListener(listener); + wpi::nt::RemoveListener(listener); } NT_Bool NT_WaitForListenerQueue(NT_Handle handle, double timeout) { - return nt::WaitForListenerQueue(handle, timeout); + return wpi::nt::WaitForListenerQueue(handle, timeout); } NT_Listener NT_AddListenerSingle(NT_Inst inst, const struct WPI_String* prefix, unsigned int mask, void* data, NT_ListenerCallback callback) { - std::string_view p = wpi::to_string_view(prefix); - return nt::AddListener(inst, {{p}}, mask, [=](auto& event) { + std::string_view p = wpi::util::to_string_view(prefix); + return wpi::nt::AddListener(inst, {{p}}, mask, [=](auto& event) { NT_Event event_c; ConvertToC(event, &event_c); callback(data, &event_c); @@ -462,12 +462,12 @@ NT_Listener NT_AddListenerMultiple(NT_Inst inst, const struct WPI_String* prefixes, size_t prefixes_len, unsigned int mask, void* data, NT_ListenerCallback callback) { - wpi::SmallVector p; + wpi::util::SmallVector p; p.reserve(prefixes_len); for (size_t i = 0; i < prefixes_len; ++i) { p.emplace_back(prefixes[i].str, prefixes[i].len); } - return nt::AddListener(inst, p, mask, [=](auto& event) { + return wpi::nt::AddListener(inst, p, mask, [=](auto& event) { NT_Event event_c; ConvertToC(event, &event_c); callback(data, &event_c); @@ -477,7 +477,7 @@ NT_Listener NT_AddListenerMultiple(NT_Inst inst, NT_Listener NT_AddListener(NT_Topic topic, unsigned int mask, void* data, NT_ListenerCallback callback) { - return nt::AddListener(topic, mask, [=](auto& event) { + return wpi::nt::AddListener(topic, mask, [=](auto& event) { NT_Event event_c; ConvertToC(event, &event_c); callback(data, &event_c); @@ -488,25 +488,25 @@ NT_Listener NT_AddListener(NT_Topic topic, unsigned int mask, void* data, NT_Listener NT_AddPolledListenerSingle(NT_ListenerPoller poller, const struct WPI_String* prefix, unsigned int mask) { - std::string_view p = wpi::to_string_view(prefix); - return nt::AddPolledListener(poller, {{p}}, mask); + std::string_view p = wpi::util::to_string_view(prefix); + return wpi::nt::AddPolledListener(poller, {{p}}, mask); } NT_Listener NT_AddPolledListenerMultiple(NT_ListenerPoller poller, const struct WPI_String* prefixes, size_t prefixes_len, unsigned int mask) { - wpi::SmallVector p; + wpi::util::SmallVector p; p.reserve(prefixes_len); for (size_t i = 0; i < prefixes_len; ++i) { p.emplace_back(prefixes[i].str, prefixes[i].len); } - return nt::AddPolledListener(poller, p, mask); + return wpi::nt::AddPolledListener(poller, p, mask); } NT_Listener NT_AddPolledListener(NT_ListenerPoller poller, NT_Topic topic, unsigned int mask) { - return nt::AddPolledListener(poller, topic, mask); + return wpi::nt::AddPolledListener(poller, topic, mask); } /* @@ -514,39 +514,39 @@ NT_Listener NT_AddPolledListener(NT_ListenerPoller poller, NT_Topic topic, */ unsigned int NT_GetNetworkMode(NT_Inst inst) { - return nt::GetNetworkMode(inst); + return wpi::nt::GetNetworkMode(inst); } void NT_StartLocal(NT_Inst inst) { - nt::StartLocal(inst); + wpi::nt::StartLocal(inst); } void NT_StopLocal(NT_Inst inst) { - nt::StopLocal(inst); + wpi::nt::StopLocal(inst); } void NT_StartServer(NT_Inst inst, const struct WPI_String* persist_filename, const struct WPI_String* listen_address, unsigned int port) { - nt::StartServer(inst, wpi::to_string_view(persist_filename), - wpi::to_string_view(listen_address), port); + wpi::nt::StartServer(inst, wpi::util::to_string_view(persist_filename), + wpi::util::to_string_view(listen_address), port); } void NT_StopServer(NT_Inst inst) { - nt::StopServer(inst); + wpi::nt::StopServer(inst); } void NT_StartClient(NT_Inst inst, const struct WPI_String* identity) { - nt::StartClient(inst, wpi::to_string_view(identity)); + wpi::nt::StartClient(inst, wpi::util::to_string_view(identity)); } void NT_StopClient(NT_Inst inst) { - nt::StopClient(inst); + wpi::nt::StopClient(inst); } void NT_SetServer(NT_Inst inst, const struct WPI_String* server_name, unsigned int port) { - nt::SetServer(inst, wpi::to_string_view(server_name), port); + wpi::nt::SetServer(inst, wpi::util::to_string_view(server_name), port); } void NT_SetServerMulti(NT_Inst inst, size_t count, @@ -556,46 +556,46 @@ void NT_SetServerMulti(NT_Inst inst, size_t count, servers.reserve(count); for (size_t i = 0; i < count; ++i) { servers.emplace_back( - std::pair{wpi::to_string_view(&server_names[i]), ports[i]}); + std::pair{wpi::util::to_string_view(&server_names[i]), ports[i]}); } - nt::SetServer(inst, servers); + wpi::nt::SetServer(inst, servers); } void NT_SetServerTeam(NT_Inst inst, unsigned int team, unsigned int port) { - nt::SetServerTeam(inst, team, port); + wpi::nt::SetServerTeam(inst, team, port); } void NT_Disconnect(NT_Inst inst) { - nt::Disconnect(inst); + wpi::nt::Disconnect(inst); } void NT_StartDSClient(NT_Inst inst, unsigned int port) { - nt::StartDSClient(inst, port); + wpi::nt::StartDSClient(inst, port); } void NT_StopDSClient(NT_Inst inst) { - nt::StopDSClient(inst); + wpi::nt::StopDSClient(inst); } void NT_FlushLocal(NT_Inst inst) { - nt::FlushLocal(inst); + wpi::nt::FlushLocal(inst); } void NT_Flush(NT_Inst inst) { - nt::Flush(inst); + wpi::nt::Flush(inst); } NT_Bool NT_IsConnected(NT_Inst inst) { - return nt::IsConnected(inst); + return wpi::nt::IsConnected(inst); } struct NT_ConnectionInfo* NT_GetConnections(NT_Inst inst, size_t* count) { - auto conn_v = nt::GetConnections(inst); + auto conn_v = wpi::nt::GetConnections(inst); return ConvertToC(conn_v, count); } int64_t NT_GetServerTimeOffset(NT_Inst inst, NT_Bool* valid) { - if (auto v = nt::GetServerTimeOffset(inst)) { + if (auto v = wpi::nt::GetServerTimeOffset(inst)) { *valid = true; return *v; } else { @@ -609,40 +609,40 @@ int64_t NT_GetServerTimeOffset(NT_Inst inst, NT_Bool* valid) { */ int64_t NT_Now(void) { - return nt::Now(); + return wpi::nt::Now(); } void NT_SetNow(int64_t timestamp) { - nt::SetNow(timestamp); + wpi::nt::SetNow(timestamp); } NT_DataLogger NT_StartEntryDataLog(NT_Inst inst, struct WPI_DataLog* log, const struct WPI_String* prefix, const struct WPI_String* logPrefix) { - return nt::StartEntryDataLog(inst, *reinterpret_cast(log), - wpi::to_string_view(prefix), - wpi::to_string_view(logPrefix)); + return wpi::nt::StartEntryDataLog(inst, *reinterpret_cast(log), + wpi::util::to_string_view(prefix), + wpi::util::to_string_view(logPrefix)); } void NT_StopEntryDataLog(NT_DataLogger logger) { - nt::StopEntryDataLog(logger); + wpi::nt::StopEntryDataLog(logger); } NT_ConnectionDataLogger NT_StartConnectionDataLog( NT_Inst inst, struct WPI_DataLog* log, const struct WPI_String* name) { - return nt::StartConnectionDataLog(inst, + return wpi::nt::StartConnectionDataLog(inst, *reinterpret_cast(log), - wpi::to_string_view(name)); + wpi::util::to_string_view(name)); } void NT_StopConnectionDataLog(NT_ConnectionDataLogger logger) { - nt::StopConnectionDataLog(logger); + wpi::nt::StopConnectionDataLog(logger); } NT_Listener NT_AddLogger(NT_Inst inst, unsigned int min_level, unsigned int max_level, void* data, NT_ListenerCallback func) { - return nt::AddLogger(inst, min_level, max_level, [=](auto& event) { + return wpi::nt::AddLogger(inst, min_level, max_level, [=](auto& event) { NT_Event event_c; ConvertToC(event, &event_c); func(data, &event_c); @@ -652,17 +652,17 @@ NT_Listener NT_AddLogger(NT_Inst inst, unsigned int min_level, NT_Listener NT_AddPolledLogger(NT_ListenerPoller poller, unsigned int min_level, unsigned int max_level) { - return nt::AddPolledLogger(poller, min_level, max_level); + return wpi::nt::AddPolledLogger(poller, min_level, max_level); } NT_Bool NT_HasSchema(NT_Inst inst, const struct WPI_String* name) { - return nt::HasSchema(inst, wpi::to_string_view(name)); + return wpi::nt::HasSchema(inst, wpi::util::to_string_view(name)); } void NT_AddSchema(NT_Inst inst, const struct WPI_String* name, const struct WPI_String* type, const uint8_t* schema, size_t schemaSize) { - nt::AddSchema(inst, wpi::to_string_view(name), wpi::to_string_view(type), + wpi::nt::AddSchema(inst, wpi::util::to_string_view(name), wpi::util::to_string_view(type), {schema, schemaSize}); } @@ -754,29 +754,29 @@ void NT_DisposeEvent(NT_Event* event) { /* Array and Struct Allocations */ char* NT_AllocateCharArray(size_t size) { - char* retVal = static_cast(wpi::safe_malloc(size * sizeof(char))); + char* retVal = static_cast(wpi::util::safe_malloc(size * sizeof(char))); return retVal; } int* NT_AllocateBooleanArray(size_t size) { - int* retVal = static_cast(wpi::safe_malloc(size * sizeof(int))); + int* retVal = static_cast(wpi::util::safe_malloc(size * sizeof(int))); return retVal; } int64_t* NT_AllocateIntegerArray(size_t size) { int64_t* retVal = - static_cast(wpi::safe_malloc(size * sizeof(int64_t))); + static_cast(wpi::util::safe_malloc(size * sizeof(int64_t))); return retVal; } float* NT_AllocateFloatArray(size_t size) { - float* retVal = static_cast(wpi::safe_malloc(size * sizeof(float))); + float* retVal = static_cast(wpi::util::safe_malloc(size * sizeof(float))); return retVal; } double* NT_AllocateDoubleArray(size_t size) { double* retVal = - static_cast(wpi::safe_malloc(size * sizeof(double))); + static_cast(wpi::util::safe_malloc(size * sizeof(double))); return retVal; } @@ -851,7 +851,7 @@ char* NT_GetValueString(const struct NT_Value* value, uint64_t* last_change, *last_change = value->last_change; *str_len = value->data.v_string.len; char* str = - static_cast(wpi::safe_malloc(value->data.v_string.len + 1)); + static_cast(wpi::util::safe_malloc(value->data.v_string.len + 1)); std::memcpy(str, value->data.v_string.str, value->data.v_string.len + 1); return str; } @@ -864,7 +864,7 @@ uint8_t* NT_GetValueRaw(const struct NT_Value* value, uint64_t* last_change, *last_change = value->last_change; *raw_len = value->data.v_raw.size; uint8_t* raw = - static_cast(wpi::safe_malloc(value->data.v_raw.size)); + static_cast(wpi::util::safe_malloc(value->data.v_raw.size)); std::memcpy(raw, value->data.v_raw.data, value->data.v_raw.size); return raw; } @@ -877,7 +877,7 @@ NT_Bool* NT_GetValueBooleanArray(const struct NT_Value* value, *last_change = value->last_change; *arr_size = value->data.arr_boolean.size; NT_Bool* arr = static_cast( - wpi::safe_malloc(value->data.arr_boolean.size * sizeof(NT_Bool))); + wpi::util::safe_malloc(value->data.arr_boolean.size * sizeof(NT_Bool))); std::memcpy(arr, value->data.arr_boolean.arr, value->data.arr_boolean.size * sizeof(NT_Bool)); return arr; @@ -891,7 +891,7 @@ int64_t* NT_GetValueIntegerArray(const struct NT_Value* value, *last_change = value->last_change; *arr_size = value->data.arr_int.size; int64_t* arr = static_cast( - wpi::safe_malloc(value->data.arr_int.size * sizeof(int64_t))); + wpi::util::safe_malloc(value->data.arr_int.size * sizeof(int64_t))); std::memcpy(arr, value->data.arr_int.arr, value->data.arr_int.size * sizeof(int64_t)); return arr; @@ -905,7 +905,7 @@ float* NT_GetValueFloatArray(const struct NT_Value* value, *last_change = value->last_change; *arr_size = value->data.arr_float.size; float* arr = static_cast( - wpi::safe_malloc(value->data.arr_float.size * sizeof(float))); + wpi::util::safe_malloc(value->data.arr_float.size * sizeof(float))); std::memcpy(arr, value->data.arr_float.arr, value->data.arr_float.size * sizeof(float)); return arr; @@ -919,7 +919,7 @@ double* NT_GetValueDoubleArray(const struct NT_Value* value, *last_change = value->last_change; *arr_size = value->data.arr_double.size; double* arr = static_cast( - wpi::safe_malloc(value->data.arr_double.size * sizeof(double))); + wpi::util::safe_malloc(value->data.arr_double.size * sizeof(double))); std::memcpy(arr, value->data.arr_double.arr, value->data.arr_double.size * sizeof(double)); return arr; diff --git a/ntcore/src/main/native/cpp/ntcore_cpp.cpp b/ntcore/src/main/native/cpp/ntcore_cpp.cpp index 6643b08fb2..baba9e5748 100644 --- a/ntcore/src/main/native/cpp/ntcore_cpp.cpp +++ b/ntcore/src/main/native/cpp/ntcore_cpp.cpp @@ -26,13 +26,13 @@ static std::atomic_bool gNowSet{false}; static std::atomic gNowTime; -namespace nt { +namespace wpi::nt { -wpi::json TopicInfo::GetProperties() const { +wpi::util::json TopicInfo::GetProperties() const { try { - return wpi::json::parse(properties); - } catch (wpi::json::parse_error&) { - return wpi::json::object(); + return wpi::util::json::parse(properties); + } catch (wpi::util::json::parse_error&) { + return wpi::util::json::object(); } } @@ -293,7 +293,7 @@ bool GetTopicExists(NT_Handle handle) { return false; } -wpi::json GetTopicProperty(NT_Topic topic, std::string_view name) { +wpi::util::json GetTopicProperty(NT_Topic topic, std::string_view name) { if (auto ii = InstanceImpl::GetTyped(topic, Handle::kTopic)) { return ii->localStorage.GetTopicProperty(topic, name); } else { @@ -302,7 +302,7 @@ wpi::json GetTopicProperty(NT_Topic topic, std::string_view name) { } void SetTopicProperty(NT_Topic topic, std::string_view name, - const wpi::json& value) { + const wpi::util::json& value) { if (auto ii = InstanceImpl::GetTyped(topic, Handle::kTopic)) { ii->localStorage.SetTopicProperty(topic, name, value); } else { @@ -316,7 +316,7 @@ void DeleteTopicProperty(NT_Topic topic, std::string_view name) { } } -wpi::json GetTopicProperties(NT_Topic topic) { +wpi::util::json GetTopicProperties(NT_Topic topic) { if (auto ii = InstanceImpl::GetTyped(topic, Handle::kTopic)) { return ii->localStorage.GetTopicProperties(topic); } else { @@ -324,7 +324,7 @@ wpi::json GetTopicProperties(NT_Topic topic) { } } -bool SetTopicProperties(NT_Topic topic, const wpi::json& properties) { +bool SetTopicProperties(NT_Topic topic, const wpi::util::json& properties) { if (auto ii = InstanceImpl::GetTyped(topic, Handle::kTopic)) { return ii->localStorage.SetTopicProperties(topic, properties); } else { @@ -349,11 +349,11 @@ void Unsubscribe(NT_Subscriber sub) { NT_Publisher Publish(NT_Topic topic, NT_Type type, std::string_view typeStr, const PubSubOptions& options) { - return PublishEx(topic, type, typeStr, wpi::json::object(), options); + return PublishEx(topic, type, typeStr, wpi::util::json::object(), options); } NT_Publisher PublishEx(NT_Topic topic, NT_Type type, std::string_view typeStr, - const wpi::json& properties, + const wpi::util::json& properties, const PubSubOptions& options) { if (auto ii = InstanceImpl::GetTyped(topic, Handle::kTopic)) { return ii->localStorage.Publish(topic, type, typeStr, properties, options); @@ -549,7 +549,7 @@ int64_t Now() { if (gNowSet) { return gNowTime; } - return wpi::Now(); + return wpi::util::Now(); } void SetNow(int64_t timestamp) { @@ -574,7 +574,7 @@ std::string_view GetStringFromType(NT_Type type) { } /* - * Data Logger Functions + * Data wpi::util::Logger Functions */ NT_DataLogger StartEntryDataLog(NT_Inst inst, wpi::log::DataLog& log, std::string_view prefix, @@ -813,4 +813,4 @@ void AddSchema(NT_Inst inst, std::string_view name, std::string_view type, } } -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/main/native/cpp/ntcore_meta.cpp b/ntcore/src/main/native/cpp/ntcore_meta.cpp index c49a67c79f..727fe1a234 100644 --- a/ntcore/src/main/native/cpp/ntcore_meta.cpp +++ b/ntcore/src/main/native/cpp/ntcore_meta.cpp @@ -14,7 +14,7 @@ using namespace mpack; -using namespace nt::meta; +using namespace wpi::nt::meta; static SubscriberOptions DecodeSubscriberOptions(mpack_reader_t& r) { SubscriberOptions options; @@ -39,7 +39,7 @@ static SubscriberOptions DecodeSubscriberOptions(mpack_reader_t& r) { return options; } -std::optional> nt::meta::DecodeClientPublishers( +std::optional> wpi::nt::meta::DecodeClientPublishers( std::span data) { mpack_reader_t r; mpack_reader_init_data(&r, data); @@ -71,7 +71,7 @@ std::optional> nt::meta::DecodeClientPublishers( } } -std::optional> nt::meta::DecodeClientSubscribers( +std::optional> wpi::nt::meta::DecodeClientSubscribers( std::span data) { mpack_reader_t r; mpack_reader_init_data(&r, data); @@ -113,7 +113,7 @@ std::optional> nt::meta::DecodeClientSubscribers( } } -std::optional> nt::meta::DecodeTopicPublishers( +std::optional> wpi::nt::meta::DecodeTopicPublishers( std::span data) { mpack_reader_t r; mpack_reader_init_data(&r, data); @@ -145,7 +145,7 @@ std::optional> nt::meta::DecodeTopicPublishers( } } -std::optional> nt::meta::DecodeTopicSubscribers( +std::optional> wpi::nt::meta::DecodeTopicSubscribers( std::span data) { mpack_reader_t r; mpack_reader_init_data(&r, data); @@ -179,7 +179,7 @@ std::optional> nt::meta::DecodeTopicSubscribers( } } -std::optional> nt::meta::DecodeClients( +std::optional> wpi::nt::meta::DecodeClients( std::span data) { mpack_reader_t r; mpack_reader_init_data(&r, data); diff --git a/ntcore/src/main/native/cpp/ntcore_meta_c.cpp b/ntcore/src/main/native/cpp/ntcore_meta_c.cpp index 064b9a1238..b9e407030f 100644 --- a/ntcore/src/main/native/cpp/ntcore_meta_c.cpp +++ b/ntcore/src/main/native/cpp/ntcore_meta_c.cpp @@ -8,8 +8,8 @@ #include "Value_internal.hpp" #include "wpi/nt/ntcore_cpp.hpp" -using namespace nt; -using namespace nt::meta; +using namespace wpi::nt; +using namespace wpi::nt::meta; static void ConvertToC(const SubscriberOptions& in, NT_Meta_SubscriberOptions* out) { @@ -56,7 +56,7 @@ static O* ConvertToC(const std::optional>& in, size_t* out_len) { if (O* rv = ConvertToC(*in, out_len)) { return rv; } else { - return static_cast(wpi::safe_malloc(0)); // return non-NULL + return static_cast(wpi::util::safe_malloc(0)); // return non-NULL } } else { *out_len = 0; diff --git a/ntcore/src/main/native/cpp/ntcore_test.cpp b/ntcore/src/main/native/cpp/ntcore_test.cpp index 75d8f80092..21f7894bf1 100644 --- a/ntcore/src/main/native/cpp/ntcore_test.cpp +++ b/ntcore/src/main/native/cpp/ntcore_test.cpp @@ -12,8 +12,8 @@ extern "C" { struct WPI_String* NT_GetStringForTesting(const char* str, int* struct_size) { struct WPI_String* strout = - static_cast(wpi::safe_calloc(1, sizeof(WPI_String))); - nt::ConvertToC(str, strout); + static_cast(wpi::util::safe_calloc(1, sizeof(WPI_String))); + wpi::nt::ConvertToC(str, strout); *struct_size = sizeof(WPI_String); return strout; } @@ -23,10 +23,10 @@ struct NT_TopicInfo* NT_GetTopicInfoForTesting(const char* name, const char* type_str, int* struct_size) { struct NT_TopicInfo* topic_info = - static_cast(wpi::safe_calloc(1, sizeof(NT_TopicInfo))); - nt::ConvertToC(name, &topic_info->name); + static_cast(wpi::util::safe_calloc(1, sizeof(NT_TopicInfo))); + wpi::nt::ConvertToC(name, &topic_info->name); topic_info->type = type; - nt::ConvertToC(type_str, &topic_info->type_str); + wpi::nt::ConvertToC(type_str, &topic_info->type_str); *struct_size = sizeof(NT_TopicInfo); return topic_info; } @@ -42,9 +42,9 @@ struct NT_ConnectionInfo* NT_GetConnectionInfoForTesting( const char* remote_id, const char* remote_ip, unsigned int remote_port, uint64_t last_update, unsigned int protocol_version, int* struct_size) { struct NT_ConnectionInfo* conn_info = static_cast( - wpi::safe_calloc(1, sizeof(NT_ConnectionInfo))); - nt::ConvertToC(remote_id, &conn_info->remote_id); - nt::ConvertToC(remote_ip, &conn_info->remote_ip); + wpi::util::safe_calloc(1, sizeof(NT_ConnectionInfo))); + wpi::nt::ConvertToC(remote_id, &conn_info->remote_id); + wpi::nt::ConvertToC(remote_ip, &conn_info->remote_ip); conn_info->remote_port = remote_port; conn_info->last_update = last_update; conn_info->protocol_version = protocol_version; @@ -61,7 +61,7 @@ void NT_FreeConnectionInfoForTesting(struct NT_ConnectionInfo* info) { struct NT_Value* NT_GetValueBooleanForTesting(uint64_t last_change, int val, int* struct_size) { struct NT_Value* value = - static_cast(wpi::safe_calloc(1, sizeof(NT_Value))); + static_cast(wpi::util::safe_calloc(1, sizeof(NT_Value))); value->type = NT_BOOLEAN; value->last_change = last_change; value->data.v_boolean = val; @@ -72,7 +72,7 @@ struct NT_Value* NT_GetValueBooleanForTesting(uint64_t last_change, int val, struct NT_Value* NT_GetValueDoubleForTesting(uint64_t last_change, double val, int* struct_size) { struct NT_Value* value = - static_cast(wpi::safe_calloc(1, sizeof(NT_Value))); + static_cast(wpi::util::safe_calloc(1, sizeof(NT_Value))); value->type = NT_DOUBLE; value->last_change = last_change; value->data.v_double = val; @@ -84,10 +84,10 @@ struct NT_Value* NT_GetValueStringForTesting(uint64_t last_change, const char* str, int* struct_size) { struct NT_Value* value = - static_cast(wpi::safe_calloc(1, sizeof(NT_Value))); + static_cast(wpi::util::safe_calloc(1, sizeof(NT_Value))); value->type = NT_STRING; value->last_change = last_change; - nt::ConvertToC(str, &value->data.v_string); + wpi::nt::ConvertToC(str, &value->data.v_string); *struct_size = sizeof(NT_Value); return value; } @@ -95,10 +95,10 @@ struct NT_Value* NT_GetValueStringForTesting(uint64_t last_change, struct NT_Value* NT_GetValueRawForTesting(uint64_t last_change, const char* raw, int raw_len, int* struct_size) { struct NT_Value* value = - static_cast(wpi::safe_calloc(1, sizeof(NT_Value))); + static_cast(wpi::util::safe_calloc(1, sizeof(NT_Value))); value->type = NT_RAW; value->last_change = last_change; - nt::ConvertToC(std::string_view(raw, raw_len), &value->data.v_string); + wpi::nt::ConvertToC(std::string_view(raw, raw_len), &value->data.v_string); *struct_size = sizeof(NT_Value); return value; } @@ -108,7 +108,7 @@ struct NT_Value* NT_GetValueBooleanArrayForTesting(uint64_t last_change, size_t array_len, int* struct_size) { struct NT_Value* value = - static_cast(wpi::safe_calloc(1, sizeof(NT_Value))); + static_cast(wpi::util::safe_calloc(1, sizeof(NT_Value))); value->type = NT_BOOLEAN_ARRAY; value->last_change = last_change; value->data.arr_boolean.arr = NT_AllocateBooleanArray(array_len); @@ -124,7 +124,7 @@ struct NT_Value* NT_GetValueDoubleArrayForTesting(uint64_t last_change, size_t array_len, int* struct_size) { struct NT_Value* value = - static_cast(wpi::safe_calloc(1, sizeof(NT_Value))); + static_cast(wpi::util::safe_calloc(1, sizeof(NT_Value))); value->type = NT_BOOLEAN; value->last_change = last_change; value->data.arr_double.arr = NT_AllocateDoubleArray(array_len); @@ -140,7 +140,7 @@ struct NT_Value* NT_GetValueStringArrayForTesting(uint64_t last_change, size_t array_len, int* struct_size) { struct NT_Value* value = - static_cast(wpi::safe_calloc(1, sizeof(NT_Value))); + static_cast(wpi::util::safe_calloc(1, sizeof(NT_Value))); value->type = NT_BOOLEAN; value->last_change = last_change; value->data.arr_string.arr = WPI_AllocateStringArray(array_len); diff --git a/ntcore/src/main/native/cpp/server/Constants.hpp b/ntcore/src/main/native/cpp/server/Constants.hpp index c04a7e0899..fb09ecde0a 100644 --- a/ntcore/src/main/native/cpp/server/Constants.hpp +++ b/ntcore/src/main/native/cpp/server/Constants.hpp @@ -6,8 +6,8 @@ #include -namespace nt::server { +namespace wpi::nt::server { inline constexpr uint32_t kMinPeriodMs = 5; -} // namespace nt::server +} // namespace wpi::nt::server diff --git a/ntcore/src/main/native/cpp/server/Functions.hpp b/ntcore/src/main/native/cpp/server/Functions.hpp index 89b7756863..f162f8a8d6 100644 --- a/ntcore/src/main/native/cpp/server/Functions.hpp +++ b/ntcore/src/main/native/cpp/server/Functions.hpp @@ -9,10 +9,10 @@ #include #include -namespace nt::server { +namespace wpi::nt::server { using SetPeriodicFunc = std::function; using Connected3Func = std::function; -} // namespace nt::server +} // namespace wpi::nt::server diff --git a/ntcore/src/main/native/cpp/server/MessagePackWriter.hpp b/ntcore/src/main/native/cpp/server/MessagePackWriter.hpp index 2d57b665f9..7a690165c3 100644 --- a/ntcore/src/main/native/cpp/server/MessagePackWriter.hpp +++ b/ntcore/src/main/native/cpp/server/MessagePackWriter.hpp @@ -11,7 +11,7 @@ #include "wpi/util/MessagePack.hpp" #include "wpi/util/raw_ostream.hpp" -namespace nt::server { +namespace wpi::nt::server { struct Writer : public mpack::mpack_writer_t { Writer() { @@ -19,13 +19,13 @@ struct Writer : public mpack::mpack_writer_t { mpack::mpack_writer_set_context(this, &os); mpack::mpack_writer_set_flush( this, [](mpack::mpack_writer_t* w, const char* buffer, size_t count) { - static_cast(w->context)->write(buffer, count); + static_cast(w->context)->write(buffer, count); }); } std::vector bytes; - wpi::raw_uvector_ostream os{bytes}; + wpi::util::raw_uvector_ostream os{bytes}; char buf[128]; }; -} // namespace nt::server +} // namespace wpi::nt::server diff --git a/ntcore/src/main/native/cpp/server/ServerClient.cpp b/ntcore/src/main/native/cpp/server/ServerClient.cpp index fbac6808d6..7588e99c90 100644 --- a/ntcore/src/main/native/cpp/server/ServerClient.cpp +++ b/ntcore/src/main/native/cpp/server/ServerClient.cpp @@ -11,7 +11,7 @@ #include "server/ServerStorage.hpp" #include "wpi/util/MessagePack.hpp" -using namespace nt::server; +using namespace wpi::nt::server; using namespace mpack; void ServerClient::UpdateMetaClientPub() { @@ -46,7 +46,7 @@ void ServerClient::UpdateMetaClientSub() { std::span ServerClient::GetSubscribers( std::string_view name, bool special, - wpi::SmallVectorImpl& buf) { + wpi::util::SmallVectorImpl& buf) { buf.resize(0); for (auto&& subPair : m_subscribers) { ServerSubscriber* subscriber = subPair.getSecond().get(); diff --git a/ntcore/src/main/native/cpp/server/ServerClient.hpp b/ntcore/src/main/native/cpp/server/ServerClient.hpp index 061b6c897e..b15f7cade4 100644 --- a/ntcore/src/main/native/cpp/server/ServerClient.hpp +++ b/ntcore/src/main/native/cpp/server/ServerClient.hpp @@ -19,13 +19,13 @@ #include "server/ServerSubscriber.hpp" #include "wpi/util/json_fwd.hpp" -namespace wpi { +namespace wpi::util { class Logger; template class SmallVectorImpl; } // namespace wpi -namespace nt::server { +namespace wpi::nt::server { struct ServerTopic; class ServerStorage; @@ -35,7 +35,7 @@ class ServerClient { public: ServerClient(std::string_view name, std::string_view connInfo, bool local, SetPeriodicFunc setPeriodic, ServerStorage& storage, int id, - wpi::Logger& logger) + wpi::util::Logger& logger) : m_name{name}, m_connInfo{connInfo}, m_local{local}, @@ -55,7 +55,7 @@ class ServerClient { net::ValueSendMode mode) = 0; virtual void SendAnnounce(ServerTopic* topic, std::optional pubuid) = 0; virtual void SendUnannounce(ServerTopic* topic) = 0; - virtual void SendPropertiesUpdate(ServerTopic* topic, const wpi::json& update, + virtual void SendPropertiesUpdate(ServerTopic* topic, const wpi::util::json& update, bool ack) = 0; virtual void SendOutgoing(uint64_t curTimeMs, bool flush) = 0; virtual void Flush() = 0; @@ -68,7 +68,7 @@ class ServerClient { std::span GetSubscribers( std::string_view name, bool special, - wpi::SmallVectorImpl& buf); + wpi::util::SmallVectorImpl& buf); std::string_view GetName() const { return m_name; } int GetId() const { return m_id; } @@ -86,10 +86,10 @@ class ServerClient { ServerStorage& m_storage; int m_id; - wpi::Logger& m_logger; + wpi::util::Logger& m_logger; - wpi::DenseMap> m_publishers; - wpi::DenseMap> m_subscribers; + wpi::util::DenseMap> m_publishers; + wpi::util::DenseMap> m_subscribers; public: // meta topics @@ -97,4 +97,4 @@ class ServerClient { ServerTopic* m_metaSub = nullptr; }; -} // namespace nt::server +} // namespace wpi::nt::server diff --git a/ntcore/src/main/native/cpp/server/ServerClient4.cpp b/ntcore/src/main/native/cpp/server/ServerClient4.cpp index 1ec8d88169..f0add7f7dd 100644 --- a/ntcore/src/main/native/cpp/server/ServerClient4.cpp +++ b/ntcore/src/main/native/cpp/server/ServerClient4.cpp @@ -12,13 +12,13 @@ #include "server/ServerTopic.hpp" #include "wpi/util/timestamp.h" -using namespace nt::server; +using namespace wpi::nt::server; ServerClient4::ServerClient4(std::string_view name, std::string_view connInfo, bool local, net::WireConnection& wire, SetPeriodicFunc setPeriodic, ServerStorage& storage, int id, - wpi::Logger& logger) + wpi::util::Logger& logger) : ServerClient4Base{name, connInfo, local, setPeriodic, storage, id, logger}, m_wire{wire}, @@ -67,7 +67,7 @@ bool ServerClient4::ProcessIncomingBinary(std::span data) { // respond to RTT ping if (pubuid == -1) { - auto now = wpi::Now(); + auto now = wpi::util::Now(); DEBUG4("RTT ping from {}, responding with time={}", m_id, now); m_wire.SendBinary( [&](auto& os) { net::WireEncodeBinary(os, -1, now, value); }); @@ -142,7 +142,7 @@ void ServerClient4::SendUnannounce(ServerTopic* topic) { } void ServerClient4::SendPropertiesUpdate(ServerTopic* topic, - const wpi::json& update, bool ack) { + const wpi::util::json& update, bool ack) { if (!m_announceSent.lookup(topic)) { return; } diff --git a/ntcore/src/main/native/cpp/server/ServerClient4.hpp b/ntcore/src/main/native/cpp/server/ServerClient4.hpp index 03cc44c6a6..1fcb99a5a8 100644 --- a/ntcore/src/main/native/cpp/server/ServerClient4.hpp +++ b/ntcore/src/main/native/cpp/server/ServerClient4.hpp @@ -11,13 +11,13 @@ #include "server/Functions.hpp" #include "server/ServerClient4Base.hpp" -namespace nt::server { +namespace wpi::nt::server { class ServerClient4 final : public ServerClient4Base { public: ServerClient4(std::string_view name, std::string_view connInfo, bool local, net::WireConnection& wire, SetPeriodicFunc setPeriodic, - ServerStorage& storage, int id, wpi::Logger& logger); + ServerStorage& storage, int id, wpi::util::Logger& logger); bool ProcessIncomingText(std::string_view data) final; bool ProcessIncomingBinary(std::span data) final; @@ -34,7 +34,7 @@ class ServerClient4 final : public ServerClient4Base { net::ValueSendMode mode) final; void SendAnnounce(ServerTopic* topic, std::optional pubuid) final; void SendUnannounce(ServerTopic* topic) final; - void SendPropertiesUpdate(ServerTopic* topic, const wpi::json& update, + void SendPropertiesUpdate(ServerTopic* topic, const wpi::util::json& update, bool ack) final; void SendOutgoing(uint64_t curTimeMs, bool flush) final; @@ -51,4 +51,4 @@ class ServerClient4 final : public ServerClient4Base { net::NetworkOutgoingQueue m_outgoing; }; -} // namespace nt::server +} // namespace wpi::nt::server diff --git a/ntcore/src/main/native/cpp/server/ServerClient4Base.cpp b/ntcore/src/main/native/cpp/server/ServerClient4Base.cpp index e0e5e792bc..e768d068ca 100644 --- a/ntcore/src/main/native/cpp/server/ServerClient4Base.cpp +++ b/ntcore/src/main/native/cpp/server/ServerClient4Base.cpp @@ -15,11 +15,11 @@ #include "server/ServerPublisher.hpp" #include "wpi/util/SpanExtras.hpp" -using namespace nt::server; +using namespace wpi::nt::server; void ServerClient4Base::ClientPublish(int pubuid, std::string_view name, std::string_view typeStr, - const wpi::json& properties, + const wpi::util::json& properties, const PubSubOptionsImpl& options) { DEBUG3("ClientPublish({}, {}, {}, {})", m_id, name, pubuid, typeStr); auto topic = m_storage.CreateTopic(this, name, typeStr, properties); @@ -67,7 +67,7 @@ void ServerClient4Base::ClientUnpublish(int pubuid) { } void ServerClient4Base::ClientSetProperties(std::string_view name, - const wpi::json& update) { + const wpi::util::json& update) { DEBUG4("ClientSetProperties({}, {}, {})", m_id, name, update.dump()); ServerTopic* topic = m_storage.GetTopic(name); if (!topic || !topic->IsPublished()) { @@ -205,7 +205,7 @@ bool ServerClient4Base::DoProcessIncomingMessages( DEBUG4("ProcessIncomingMessage()"); max = (std::min)(m_msgsBuf.size(), max); std::span msgs = - queue.ReadQueue(wpi::take_front(std::span{m_msgsBuf}, max)); + queue.ReadQueue(wpi::util::take_front(std::span{m_msgsBuf}, max)); // just map as a normal client into client=0 calls bool updatepub = false; diff --git a/ntcore/src/main/native/cpp/server/ServerClient4Base.hpp b/ntcore/src/main/native/cpp/server/ServerClient4Base.hpp index f80f5e6813..274546a9b2 100644 --- a/ntcore/src/main/native/cpp/server/ServerClient4Base.hpp +++ b/ntcore/src/main/native/cpp/server/ServerClient4Base.hpp @@ -12,24 +12,24 @@ #include "server/ServerClient.hpp" #include "wpi/util/DenseMap.hpp" -namespace nt::server { +namespace wpi::nt::server { class ServerClient4Base : public ServerClient, protected net::ClientMessageHandler { public: ServerClient4Base(std::string_view name, std::string_view connInfo, bool local, SetPeriodicFunc setPeriodic, - ServerStorage& storage, int id, wpi::Logger& logger) + ServerStorage& storage, int id, wpi::util::Logger& logger) : ServerClient{name, connInfo, local, setPeriodic, storage, id, logger} {} protected: // ClientMessageHandler interface void ClientPublish(int pubuid, std::string_view name, - std::string_view typeStr, const wpi::json& properties, + std::string_view typeStr, const wpi::util::json& properties, const PubSubOptionsImpl& options) final; void ClientUnpublish(int pubuid) final; void ClientSetProperties(std::string_view name, - const wpi::json& update) final; + const wpi::util::json& update) final; void ClientSubscribe(int subuid, std::span topicNames, const PubSubOptionsImpl& options) final; void ClientUnsubscribe(int subuid) final; @@ -38,10 +38,10 @@ class ServerClient4Base : public ServerClient, bool DoProcessIncomingMessages(net::ClientMessageQueue& queue, size_t max); - wpi::DenseMap m_announceSent; + wpi::util::DenseMap m_announceSent; private: std::array m_msgsBuf; }; -} // namespace nt::server +} // namespace wpi::nt::server diff --git a/ntcore/src/main/native/cpp/server/ServerClientLocal.cpp b/ntcore/src/main/native/cpp/server/ServerClientLocal.cpp index b3dca02092..004f74a289 100644 --- a/ntcore/src/main/native/cpp/server/ServerClientLocal.cpp +++ b/ntcore/src/main/native/cpp/server/ServerClientLocal.cpp @@ -6,7 +6,7 @@ #include "server/ServerImpl.hpp" -using namespace nt::server; +using namespace wpi::nt::server; // Suppress false positive -Wmaybe-uninitialized warning from GCC 14 #if defined(__GNUC__) && !defined(__clang__) @@ -14,7 +14,7 @@ using namespace nt::server; #pragma GCC diagnostic ignored "-Wmaybe-uninitialized" #endif ServerClientLocal::ServerClientLocal(ServerStorage& storage, int id, - wpi::Logger& logger) + wpi::util::Logger& logger) : ServerClient4Base{"", "", true, [](uint32_t) {}, storage, id, logger} { // create local client meta topics m_metaPub = storage.CreateMetaTopic("$serverpub"); @@ -61,7 +61,7 @@ void ServerClientLocal::SendUnannounce(ServerTopic* topic) { } void ServerClientLocal::SendPropertiesUpdate(ServerTopic* topic, - const wpi::json& update, + const wpi::util::json& update, bool ack) { if (m_local) { if (!m_announceSent.lookup(topic)) { diff --git a/ntcore/src/main/native/cpp/server/ServerClientLocal.hpp b/ntcore/src/main/native/cpp/server/ServerClientLocal.hpp index df6f6393f2..f22d4a8f4f 100644 --- a/ntcore/src/main/native/cpp/server/ServerClientLocal.hpp +++ b/ntcore/src/main/native/cpp/server/ServerClientLocal.hpp @@ -9,11 +9,11 @@ #include "server/ServerClient4Base.hpp" -namespace nt::server { +namespace wpi::nt::server { class ServerClientLocal final : public ServerClient4Base { public: - ServerClientLocal(ServerStorage& storage, int id, wpi::Logger& logger); + ServerClientLocal(ServerStorage& storage, int id, wpi::util::Logger& logger); bool ProcessIncomingText(std::string_view data) final { return false; } bool ProcessIncomingBinary(std::span data) final { @@ -31,7 +31,7 @@ class ServerClientLocal final : public ServerClient4Base { net::ValueSendMode mode) final; void SendAnnounce(ServerTopic* topic, std::optional pubuid) final; void SendUnannounce(ServerTopic* topic) final; - void SendPropertiesUpdate(ServerTopic* topic, const wpi::json& update, + void SendPropertiesUpdate(ServerTopic* topic, const wpi::util::json& update, bool ack) final; void SendOutgoing(uint64_t curTimeMs, bool flush) final {} void Flush() final {} @@ -47,4 +47,4 @@ class ServerClientLocal final : public ServerClient4Base { net::ClientMessageQueue* m_queue = nullptr; }; -} // namespace nt::server +} // namespace wpi::nt::server diff --git a/ntcore/src/main/native/cpp/server/ServerImpl.cpp b/ntcore/src/main/native/cpp/server/ServerImpl.cpp index efbd72c8ac..f94f2a9189 100644 --- a/ntcore/src/main/native/cpp/server/ServerImpl.cpp +++ b/ntcore/src/main/native/cpp/server/ServerImpl.cpp @@ -18,11 +18,11 @@ #include "server/ServerClientLocal.hpp" #include "wpi/util/MessagePack.hpp" -using namespace nt; -using namespace nt::server; +using namespace wpi::nt; +using namespace wpi::nt::server; using namespace mpack; -ServerImpl::ServerImpl(wpi::Logger& logger) +ServerImpl::ServerImpl(wpi::util::Logger& logger) : m_logger{logger}, m_storage{logger, [this](ServerTopic* topic, ServerClient* client) { SendAnnounce(topic, client); @@ -87,7 +87,7 @@ void ServerImpl::SendAnnounce(ServerTopic* topic, ServerClient* client) { } // look for subscriber matching prefixes - wpi::SmallVector subscribersBuf; + wpi::util::SmallVector subscribersBuf; auto subscribers = aClient->GetSubscribers(topic->name, topic->special, subscribersBuf); @@ -201,7 +201,7 @@ bool ServerImpl::ProcessLocalMessages(size_t max) { std::string ServerImpl::DumpPersistent() { std::string rv; - wpi::raw_string_ostream os{rv}; + wpi::util::raw_string_ostream os{rv}; m_storage.DumpPersistent(os); os.flush(); return rv; diff --git a/ntcore/src/main/native/cpp/server/ServerImpl.hpp b/ntcore/src/main/native/cpp/server/ServerImpl.hpp index 6993ce9831..af640ae9c2 100644 --- a/ntcore/src/main/native/cpp/server/ServerImpl.hpp +++ b/ntcore/src/main/native/cpp/server/ServerImpl.hpp @@ -17,29 +17,29 @@ #include "server/ServerClient.hpp" #include "server/ServerStorage.hpp" -namespace wpi { +namespace wpi::util { class Logger; } // namespace wpi -namespace nt::net { +namespace wpi::nt::net { class ClientMessageQueue; class LocalInterface; class ServerMessageHandler; class WireConnection; -} // namespace nt::net +} // namespace wpi::nt::net -namespace nt::net3 { +namespace wpi::nt::net3 { class WireConnection3; -} // namespace nt::net3 +} // namespace wpi::nt::net3 -namespace nt::server { +namespace wpi::nt::server { class ServerClientLocal; struct ServerTopic; class ServerImpl final { public: - explicit ServerImpl(wpi::Logger& logger); + explicit ServerImpl(wpi::util::Logger& logger); void SendAllOutgoing(uint64_t curTimeMs, bool flush); void SendOutgoing(int clientId, uint64_t curTimeMs); @@ -78,7 +78,7 @@ class ServerImpl final { } private: - wpi::Logger& m_logger; + wpi::util::Logger& m_logger; ServerClientLocal* m_localClient; std::vector> m_clients; @@ -94,4 +94,4 @@ class ServerImpl final { void UpdateMetaClients(const std::vector& conns); }; -} // namespace nt::server +} // namespace wpi::nt::server diff --git a/ntcore/src/main/native/cpp/server/ServerPublisher.cpp b/ntcore/src/main/native/cpp/server/ServerPublisher.cpp index 7219116c90..d507bcc83d 100644 --- a/ntcore/src/main/native/cpp/server/ServerPublisher.cpp +++ b/ntcore/src/main/native/cpp/server/ServerPublisher.cpp @@ -10,7 +10,7 @@ #include "server/ServerTopic.hpp" #include "wpi/util/MessagePack.hpp" -using namespace nt::server; +using namespace wpi::nt::server; using namespace mpack; void ServerPublisher::UpdateMeta() { diff --git a/ntcore/src/main/native/cpp/server/ServerPublisher.hpp b/ntcore/src/main/native/cpp/server/ServerPublisher.hpp index e8c0677c8c..516549600e 100644 --- a/ntcore/src/main/native/cpp/server/ServerPublisher.hpp +++ b/ntcore/src/main/native/cpp/server/ServerPublisher.hpp @@ -11,7 +11,7 @@ #include #include -namespace nt::server { +namespace wpi::nt::server { class ServerClient; struct ServerTopic; @@ -40,4 +40,4 @@ class ServerPublisher { std::vector m_metaTopic; }; -} // namespace nt::server +} // namespace wpi::nt::server diff --git a/ntcore/src/main/native/cpp/server/ServerStorage.cpp b/ntcore/src/main/native/cpp/server/ServerStorage.cpp index 9556606943..24e5c2e0b6 100644 --- a/ntcore/src/main/native/cpp/server/ServerStorage.cpp +++ b/ntcore/src/main/native/cpp/server/ServerStorage.cpp @@ -18,14 +18,14 @@ #include "wpi/util/MessagePack.hpp" #include "wpi/util/json.hpp" -using namespace nt; -using namespace nt::server; +using namespace wpi::nt; +using namespace wpi::nt::server; using namespace mpack; ServerTopic* ServerStorage::CreateTopic(ServerClient* client, std::string_view name, std::string_view typeStr, - const wpi::json& properties, + const wpi::util::json& properties, bool special) { auto& topic = m_nameTopics[name]; if (topic) { @@ -88,7 +88,7 @@ void ServerStorage::DeleteTopic(ServerTopic* topic) { } void ServerStorage::SetProperties(ServerClient* client, ServerTopic* topic, - const wpi::json& update) { + const wpi::util::json& update) { DEBUG4("SetProperties({}, {}, {})", client ? client->GetId() : -1, topic->name, update.dump()); bool wasPersistent = topic->persistent; @@ -108,11 +108,11 @@ void ServerStorage::SetFlags(ServerClient* client, ServerTopic* topic, // update persistentChanged flag if (topic->persistent != wasPersistent) { m_persistentChanged = true; - wpi::json update; + wpi::util::json update; if (topic->persistent) { update = {{"persistent", true}}; } else { - update = {{"persistent", wpi::json::object()}}; + update = {{"persistent", wpi::util::json::object()}}; } PropertiesChanged(client, topic, update); } @@ -146,7 +146,7 @@ void ServerStorage::SetValue(ServerClient* client, ServerTopic* topic, void ServerStorage::RemoveClient(ServerClient* client) { // remove all publishers and subscribers for this client - wpi::SmallVector toDelete; + wpi::util::SmallVector toDelete; for (auto&& topic : m_topics) { bool pubChanged = false; bool subChanged = false; @@ -222,7 +222,7 @@ void ServerStorage::UpdateMetaTopicSub(ServerTopic* topic) { } void ServerStorage::PropertiesChanged(ServerClient* client, ServerTopic* topic, - const wpi::json& update) { + const wpi::util::json& update) { // removing some properties can result in the topic being unpublished if (!topic->IsPublished()) { DeleteTopic(topic); @@ -234,8 +234,8 @@ void ServerStorage::PropertiesChanged(ServerClient* client, ServerTopic* topic, } } -static void DumpValue(wpi::raw_ostream& os, const Value& value, - wpi::json::serializer& s) { +static void DumpValue(wpi::util::raw_ostream& os, const Value& value, + wpi::util::json::serializer& s) { switch (value.type()) { case NT_BOOLEAN: if (value.GetBoolean()) { @@ -261,7 +261,7 @@ static void DumpValue(wpi::raw_ostream& os, const Value& value, case NT_RAW: case NT_RPC: os << '"'; - wpi::Base64Encode(os, value.GetRaw()); + wpi::util::Base64Encode(os, value.GetRaw()); os << '"'; break; case NT_BOOLEAN_ARRAY: { @@ -346,8 +346,8 @@ static void DumpValue(wpi::raw_ostream& os, const Value& value, } } -void ServerStorage::DumpPersistent(wpi::raw_ostream& os) { - wpi::json::serializer s{os, ' ', 16}; +void ServerStorage::DumpPersistent(wpi::util::raw_ostream& os) { + wpi::util::json::serializer s{os, ' ', 16}; os << "[\n"; bool first = true; for (const auto& topic : m_topics) { @@ -372,7 +372,7 @@ void ServerStorage::DumpPersistent(wpi::raw_ostream& os) { os << "\n]\n"; } -static std::string* ObjGetString(wpi::json::object_t& obj, std::string_view key, +static std::string* ObjGetString(wpi::util::json::object_t& obj, std::string_view key, std::string* error) { auto it = obj.find(key); if (it == obj.end()) { @@ -391,10 +391,10 @@ std::string ServerStorage::LoadPersistent(std::string_view in) { return {}; } - wpi::json j; + wpi::util::json j; try { - j = wpi::json::parse(in); - } catch (wpi::json::parse_error& err) { + j = wpi::util::json::parse(in); + } catch (wpi::util::json::parse_error& err) { return fmt::format("could not decode JSON: {}", err.what()); } @@ -406,12 +406,12 @@ std::string ServerStorage::LoadPersistent(std::string_view in) { std::string allerrors; int i = -1; - auto time = nt::Now(); + auto time = wpi::nt::Now(); for (auto&& jitem : j) { ++i; std::string error; { - auto obj = jitem.get_ptr(); + auto obj = jitem.get_ptr(); if (!obj) { error = "expected item to be an object"; goto err; @@ -502,7 +502,7 @@ std::string ServerStorage::LoadPersistent(std::string_view in) { goto err; } } else if (*typeStr == "boolean[]") { - auto arr = valueIt->second.get_ptr(); + auto arr = valueIt->second.get_ptr(); if (!arr) { error = "value type mismatch, expected array"; goto err; @@ -517,7 +517,7 @@ std::string ServerStorage::LoadPersistent(std::string_view in) { } value = Value::MakeBooleanArray(elems, time); } else if (*typeStr == "int[]") { - auto arr = valueIt->second.get_ptr(); + auto arr = valueIt->second.get_ptr(); if (!arr) { error = "value type mismatch, expected array"; goto err; @@ -534,7 +534,7 @@ std::string ServerStorage::LoadPersistent(std::string_view in) { } value = Value::MakeIntegerArray(elems, time); } else if (*typeStr == "double[]") { - auto arr = valueIt->second.get_ptr(); + auto arr = valueIt->second.get_ptr(); if (!arr) { error = "value type mismatch, expected array"; goto err; @@ -549,7 +549,7 @@ std::string ServerStorage::LoadPersistent(std::string_view in) { } value = Value::MakeDoubleArray(elems, time); } else if (*typeStr == "float[]") { - auto arr = valueIt->second.get_ptr(); + auto arr = valueIt->second.get_ptr(); if (!arr) { error = "value type mismatch, expected array"; goto err; @@ -564,7 +564,7 @@ std::string ServerStorage::LoadPersistent(std::string_view in) { } value = Value::MakeFloatArray(elems, time); } else if (*typeStr == "string[]") { - auto arr = valueIt->second.get_ptr(); + auto arr = valueIt->second.get_ptr(); if (!arr) { error = "value type mismatch, expected array"; goto err; @@ -582,7 +582,7 @@ std::string ServerStorage::LoadPersistent(std::string_view in) { // raw if (auto v = valueIt->second.get_ptr()) { std::vector data; - wpi::Base64Decode(*v, &data); + wpi::util::Base64Decode(*v, &data); value = Value::MakeRaw(std::move(data), time); } else { error = "value type mismatch, expected string"; diff --git a/ntcore/src/main/native/cpp/server/ServerStorage.hpp b/ntcore/src/main/native/cpp/server/ServerStorage.hpp index 8c0711740f..16f5eff2b1 100644 --- a/ntcore/src/main/native/cpp/server/ServerStorage.hpp +++ b/ntcore/src/main/native/cpp/server/ServerStorage.hpp @@ -14,18 +14,18 @@ #include "wpi/util/UidVector.hpp" #include "wpi/util/json_fwd.hpp" -namespace wpi { +namespace wpi::util { class Logger; class raw_ostream; } // namespace wpi -namespace nt::server { +namespace wpi::nt::server { class ServerClient; class ServerStorage final { public: - ServerStorage(wpi::Logger& logger, + ServerStorage(wpi::util::Logger& logger, std::function sendAnnounce) : m_logger{logger}, m_sendAnnounce{std::move(sendAnnounce)} {} @@ -34,18 +34,18 @@ class ServerStorage final { ServerTopic* CreateTopic(ServerClient* client, std::string_view name, std::string_view typeStr, - const wpi::json& properties, bool special = false); + const wpi::util::json& properties, bool special = false); ServerTopic* CreateMetaTopic(std::string_view name); void DeleteTopic(ServerTopic* topic); void SetProperties(ServerClient* client, ServerTopic* topic, - const wpi::json& update); + const wpi::util::json& update); void SetFlags(ServerClient* client, ServerTopic* topic, unsigned int flags); void SetValue(ServerClient* client, ServerTopic* topic, const Value& value); void RemoveClient(ServerClient* client); void PropertiesChanged(ServerClient* client, ServerTopic* topic, - const wpi::json& update); + const wpi::util::json& update); ServerTopic* GetTopic(unsigned int id) const { return id < m_topics.size() ? m_topics[id].get() : nullptr; @@ -78,17 +78,17 @@ class ServerStorage final { return rv; } - void DumpPersistent(wpi::raw_ostream& os); + void DumpPersistent(wpi::util::raw_ostream& os); // returns newline-separated errors std::string LoadPersistent(std::string_view in); private: - wpi::Logger& m_logger; + wpi::util::Logger& m_logger; std::function m_sendAnnounce; - wpi::UidVector, 16> m_topics; - wpi::StringMap m_nameTopics; + wpi::util::UidVector, 16> m_topics; + wpi::util::StringMap m_nameTopics; bool m_persistentChanged{false}; }; -} // namespace nt::server +} // namespace wpi::nt::server diff --git a/ntcore/src/main/native/cpp/server/ServerSubscriber.cpp b/ntcore/src/main/native/cpp/server/ServerSubscriber.cpp index efb9f2faf5..1efa89a9eb 100644 --- a/ntcore/src/main/native/cpp/server/ServerSubscriber.cpp +++ b/ntcore/src/main/native/cpp/server/ServerSubscriber.cpp @@ -11,8 +11,8 @@ #include "wpi/util/MessagePack.hpp" #include "wpi/util/StringExtras.hpp" -using namespace nt; -using namespace nt::server; +using namespace wpi::nt; +using namespace wpi::nt::server; using namespace mpack; static void WriteOptions(mpack_writer_t& w, const PubSubOptionsImpl& options) { @@ -44,7 +44,7 @@ bool ServerSubscriber::Matches(std::string_view name, bool special) { for (auto&& topicName : m_topicNames) { if ((!m_options.prefixMatch && name == topicName) || (m_options.prefixMatch && (!special || !topicName.empty()) && - wpi::starts_with(name, topicName))) { + wpi::util::starts_with(name, topicName))) { return true; } } diff --git a/ntcore/src/main/native/cpp/server/ServerSubscriber.hpp b/ntcore/src/main/native/cpp/server/ServerSubscriber.hpp index e41aa87f2a..6f278020fa 100644 --- a/ntcore/src/main/native/cpp/server/ServerSubscriber.hpp +++ b/ntcore/src/main/native/cpp/server/ServerSubscriber.hpp @@ -15,7 +15,7 @@ #include "PubSubOptions.hpp" #include "server/Constants.hpp" -namespace nt::server { +namespace wpi::nt::server { class ServerClient; struct ServerTopic; @@ -71,4 +71,4 @@ class ServerSubscriber { uint32_t m_periodMs; }; -} // namespace nt::server +} // namespace wpi::nt::server diff --git a/ntcore/src/main/native/cpp/server/ServerTopic.cpp b/ntcore/src/main/native/cpp/server/ServerTopic.cpp index 72f504913e..eaf85ddd76 100644 --- a/ntcore/src/main/native/cpp/server/ServerTopic.cpp +++ b/ntcore/src/main/native/cpp/server/ServerTopic.cpp @@ -6,9 +6,9 @@ #include "Log.hpp" -using namespace nt::server; +using namespace wpi::nt::server; -bool ServerTopic::SetProperties(const wpi::json& update) { +bool ServerTopic::SetProperties(const wpi::util::json& update) { if (!update.is_object()) { return false; } diff --git a/ntcore/src/main/native/cpp/server/ServerTopic.hpp b/ntcore/src/main/native/cpp/server/ServerTopic.hpp index 7d15feab25..42b43f8269 100644 --- a/ntcore/src/main/native/cpp/server/ServerTopic.hpp +++ b/ntcore/src/main/native/cpp/server/ServerTopic.hpp @@ -16,17 +16,17 @@ #include "wpi/util/SmallPtrSet.hpp" #include "wpi/util/json.hpp" -namespace wpi { +namespace wpi::util { class Logger; } // namespace wpi -namespace nt::server { +namespace wpi::nt::server { class ServerClient; struct TopicClientData { - wpi::SmallPtrSet publishers; - wpi::SmallPtrSet subscribers; + wpi::util::SmallPtrSet publishers; + wpi::util::SmallPtrSet subscribers; net::ValueSendMode sendMode = net::ValueSendMode::kDisabled; bool AddSubscriber(ServerSubscriber* sub) { @@ -44,11 +44,11 @@ struct TopicClientData { }; struct ServerTopic { - ServerTopic(wpi::Logger& logger, std::string_view name, + ServerTopic(wpi::util::Logger& logger, std::string_view name, std::string_view typeStr) : m_logger{logger}, name{name}, typeStr{typeStr} {} - ServerTopic(wpi::Logger& logger, std::string_view name, - std::string_view typeStr, wpi::json properties) + ServerTopic(wpi::util::Logger& logger, std::string_view name, + std::string_view typeStr, wpi::util::json properties) : m_logger{logger}, name{name}, typeStr{typeStr}, @@ -63,17 +63,17 @@ struct ServerTopic { } // returns true if properties changed - bool SetProperties(const wpi::json& update); + bool SetProperties(const wpi::util::json& update); void RefreshProperties(); bool SetFlags(unsigned int flags_); - wpi::Logger& m_logger; // Must be m_logger for WARN macro to work + wpi::util::Logger& m_logger; // Must be m_logger for WARN macro to work std::string name; unsigned int id; Value lastValue; ServerClient* lastValueClient = nullptr; std::string typeStr; - wpi::json properties = wpi::json::object(); + wpi::util::json properties = wpi::util::json::object(); unsigned int publisherCount{0}; bool persistent{false}; bool retained{false}; @@ -93,11 +93,11 @@ struct ServerTopic { } } - wpi::SmallDenseMap clients; + wpi::util::SmallDenseMap clients; // meta topics ServerTopic* metaPub = nullptr; ServerTopic* metaSub = nullptr; }; -} // namespace nt::server +} // namespace wpi::nt::server diff --git a/ntcore/src/main/native/include/wpi/nt/GenericEntry.hpp b/ntcore/src/main/native/include/wpi/nt/GenericEntry.hpp index d00b3a39da..be98524018 100644 --- a/ntcore/src/main/native/include/wpi/nt/GenericEntry.hpp +++ b/ntcore/src/main/native/include/wpi/nt/GenericEntry.hpp @@ -14,7 +14,7 @@ #include "wpi/nt/Topic.hpp" #include "wpi/nt/ntcore_cpp.hpp" -namespace nt { +namespace wpi::nt { class Value; @@ -44,7 +44,7 @@ class GenericSubscriber : public Subscriber { * * @return value */ - ValueType Get() const { return ::nt::GetEntryValue(m_subHandle); } + ValueType Get() const { return ::wpi::nt::GetEntryValue(m_subHandle); } /** * Gets the entry's value as a boolean. If the entry does not exist or is of @@ -54,7 +54,7 @@ class GenericSubscriber : public Subscriber { * @return the entry's value or the given default value */ bool GetBoolean(bool defaultValue) const { - return ::nt::GetBoolean(m_subHandle, defaultValue); + return ::wpi::nt::GetBoolean(m_subHandle, defaultValue); } /** @@ -65,7 +65,7 @@ class GenericSubscriber : public Subscriber { * @return the entry's value or the given default value */ int64_t GetInteger(int64_t defaultValue) const { - return ::nt::GetInteger(m_subHandle, defaultValue); + return ::wpi::nt::GetInteger(m_subHandle, defaultValue); } /** @@ -76,7 +76,7 @@ class GenericSubscriber : public Subscriber { * @return the entry's value or the given default value */ float GetFloat(float defaultValue) const { - return ::nt::GetFloat(m_subHandle, defaultValue); + return ::wpi::nt::GetFloat(m_subHandle, defaultValue); } /** @@ -87,7 +87,7 @@ class GenericSubscriber : public Subscriber { * @return the entry's value or the given default value */ double GetDouble(double defaultValue) const { - return ::nt::GetDouble(m_subHandle, defaultValue); + return ::wpi::nt::GetDouble(m_subHandle, defaultValue); } /** @@ -98,7 +98,7 @@ class GenericSubscriber : public Subscriber { * @return the entry's value or the given default value */ std::string GetString(std::string_view defaultValue) const { - return ::nt::GetString(m_subHandle, defaultValue); + return ::wpi::nt::GetString(m_subHandle, defaultValue); } /** @@ -109,7 +109,7 @@ class GenericSubscriber : public Subscriber { * @return the entry's value or the given default value */ std::vector GetRaw(std::span defaultValue) const { - return ::nt::GetRaw(m_subHandle, defaultValue); + return ::wpi::nt::GetRaw(m_subHandle, defaultValue); } /** @@ -127,7 +127,7 @@ class GenericSubscriber : public Subscriber { * non-zero value is true. */ std::vector GetBooleanArray(std::span defaultValue) const { - return ::nt::GetBooleanArray(m_subHandle, defaultValue); + return ::wpi::nt::GetBooleanArray(m_subHandle, defaultValue); } /** @@ -142,7 +142,7 @@ class GenericSubscriber : public Subscriber { */ std::vector GetIntegerArray( std::span defaultValue) const { - return ::nt::GetIntegerArray(m_subHandle, defaultValue); + return ::wpi::nt::GetIntegerArray(m_subHandle, defaultValue); } /** @@ -156,7 +156,7 @@ class GenericSubscriber : public Subscriber { * concern, use GetValue() instead. */ std::vector GetFloatArray(std::span defaultValue) const { - return ::nt::GetFloatArray(m_subHandle, defaultValue); + return ::wpi::nt::GetFloatArray(m_subHandle, defaultValue); } /** @@ -171,7 +171,7 @@ class GenericSubscriber : public Subscriber { */ std::vector GetDoubleArray( std::span defaultValue) const { - return ::nt::GetDoubleArray(m_subHandle, defaultValue); + return ::wpi::nt::GetDoubleArray(m_subHandle, defaultValue); } /** @@ -186,7 +186,7 @@ class GenericSubscriber : public Subscriber { */ std::vector GetStringArray( std::span defaultValue) const { - return ::nt::GetStringArray(m_subHandle, defaultValue); + return ::wpi::nt::GetStringArray(m_subHandle, defaultValue); } /** @@ -200,7 +200,7 @@ class GenericSubscriber : public Subscriber { * been published since the previous call. */ std::vector ReadQueue() { - return ::nt::ReadQueueValue(m_subHandle); + return ::wpi::nt::ReadQueueValue(m_subHandle); } /** @@ -209,7 +209,7 @@ class GenericSubscriber : public Subscriber { * @return Topic */ TopicType GetTopic() const { - return Topic{::nt::GetTopicFromHandle(m_subHandle)}; + return Topic{::wpi::nt::GetTopicFromHandle(m_subHandle)}; } }; @@ -238,79 +238,79 @@ class GenericPublisher : public Publisher { * * @param value value to publish */ - void Set(ParamType value) { ::nt::SetEntryValue(m_pubHandle, value); } + void Set(ParamType value) { ::wpi::nt::SetEntryValue(m_pubHandle, value); } /** * Sets the entry's value. * * @param value the value to set - * @param time the timestamp to set (0 = nt::Now()) + * @param time the timestamp to set (0 = wpi::nt::Now()) * @return False if the entry exists with a different type */ bool SetBoolean(bool value, int64_t time = 0) { - return nt::SetBoolean(m_pubHandle, value, time); + return wpi::nt::SetBoolean(m_pubHandle, value, time); } /** * Sets the entry's value. * * @param value the value to set - * @param time the timestamp to set (0 = nt::Now()) + * @param time the timestamp to set (0 = wpi::nt::Now()) * @return False if the entry exists with a different type */ bool SetInteger(int64_t value, int64_t time = 0) { - return nt::SetInteger(m_pubHandle, value, time); + return wpi::nt::SetInteger(m_pubHandle, value, time); } /** * Sets the entry's value. * * @param value the value to set - * @param time the timestamp to set (0 = nt::Now()) + * @param time the timestamp to set (0 = wpi::nt::Now()) * @return False if the entry exists with a different type */ bool SetFloat(float value, int64_t time = 0) { - return nt::SetFloat(m_pubHandle, value, time); + return wpi::nt::SetFloat(m_pubHandle, value, time); } /** * Sets the entry's value. * * @param value the value to set - * @param time the timestamp to set (0 = nt::Now()) + * @param time the timestamp to set (0 = wpi::nt::Now()) * @return False if the entry exists with a different type */ bool SetDouble(double value, int64_t time = 0) { - return nt::SetDouble(m_pubHandle, value, time); + return wpi::nt::SetDouble(m_pubHandle, value, time); } /** * Sets the entry's value. * * @param value the value to set - * @param time the timestamp to set (0 = nt::Now()) + * @param time the timestamp to set (0 = wpi::nt::Now()) * @return False if the entry exists with a different type */ bool SetString(std::string_view value, int64_t time = 0) { - return nt::SetString(m_pubHandle, value, time); + return wpi::nt::SetString(m_pubHandle, value, time); } /** * Sets the entry's value. * * @param value the value to set - * @param time the timestamp to set (0 = nt::Now()) + * @param time the timestamp to set (0 = wpi::nt::Now()) * @return False if the entry exists with a different type */ bool SetRaw(std::span value, int64_t time = 0) { - return nt::SetRaw(m_pubHandle, value, time); + return wpi::nt::SetRaw(m_pubHandle, value, time); } /** * Sets the entry's value. * * @param value the value to set - * @param time the timestamp to set (0 = nt::Now()) + * @param time the timestamp to set (0 = wpi::nt::Now()) * @return False if the entry exists with a different type */ bool SetBooleanArray(std::span value, int64_t time = 0) { @@ -321,55 +321,55 @@ class GenericPublisher : public Publisher { * Sets the entry's value. * * @param value the value to set - * @param time the timestamp to set (0 = nt::Now()) + * @param time the timestamp to set (0 = wpi::nt::Now()) * @return False if the entry exists with a different type */ bool SetBooleanArray(std::span value, int64_t time = 0) { - return nt::SetBooleanArray(m_pubHandle, value, time); + return wpi::nt::SetBooleanArray(m_pubHandle, value, time); } /** * Sets the entry's value. * * @param value the value to set - * @param time the timestamp to set (0 = nt::Now()) + * @param time the timestamp to set (0 = wpi::nt::Now()) * @return False if the entry exists with a different type */ bool SetIntegerArray(std::span value, int64_t time = 0) { - return nt::SetIntegerArray(m_pubHandle, value, time); + return wpi::nt::SetIntegerArray(m_pubHandle, value, time); } /** * Sets the entry's value. * * @param value the value to set - * @param time the timestamp to set (0 = nt::Now()) + * @param time the timestamp to set (0 = wpi::nt::Now()) * @return False if the entry exists with a different type */ bool SetFloatArray(std::span value, int64_t time = 0) { - return nt::SetFloatArray(m_pubHandle, value, time); + return wpi::nt::SetFloatArray(m_pubHandle, value, time); } /** * Sets the entry's value. * * @param value the value to set - * @param time the timestamp to set (0 = nt::Now()) + * @param time the timestamp to set (0 = wpi::nt::Now()) * @return False if the entry exists with a different type */ bool SetDoubleArray(std::span value, int64_t time = 0) { - return nt::SetDoubleArray(m_pubHandle, value, time); + return wpi::nt::SetDoubleArray(m_pubHandle, value, time); } /** * Sets the entry's value. * * @param value the value to set - * @param time the timestamp to set (0 = nt::Now()) + * @param time the timestamp to set (0 = wpi::nt::Now()) * @return False if the entry exists with a different type */ bool SetStringArray(std::span value, int64_t time = 0) { - return nt::SetStringArray(m_pubHandle, value, time); + return wpi::nt::SetStringArray(m_pubHandle, value, time); } /** @@ -380,7 +380,7 @@ class GenericPublisher : public Publisher { * @param value value */ void SetDefault(ParamType value) { - ::nt::SetDefaultEntryValue(m_pubHandle, value); + ::wpi::nt::SetDefaultEntryValue(m_pubHandle, value); } /** @@ -390,7 +390,7 @@ class GenericPublisher : public Publisher { * @return True if the entry did not already have a value, otherwise False */ bool SetDefaultBoolean(bool defaultValue) { - return nt::SetDefaultBoolean(m_pubHandle, defaultValue); + return wpi::nt::SetDefaultBoolean(m_pubHandle, defaultValue); } /** @@ -400,7 +400,7 @@ class GenericPublisher : public Publisher { * @return True if the entry did not already have a value, otherwise False */ bool SetDefaultInteger(int64_t defaultValue) { - return nt::SetDefaultInteger(m_pubHandle, defaultValue); + return wpi::nt::SetDefaultInteger(m_pubHandle, defaultValue); } /** @@ -410,7 +410,7 @@ class GenericPublisher : public Publisher { * @return True if the entry did not already have a value, otherwise False */ bool SetDefaultFloat(float defaultValue) { - return nt::SetDefaultFloat(m_pubHandle, defaultValue); + return wpi::nt::SetDefaultFloat(m_pubHandle, defaultValue); } /** @@ -420,7 +420,7 @@ class GenericPublisher : public Publisher { * @return True if the entry did not already have a value, otherwise False */ bool SetDefaultDouble(double defaultValue) { - return nt::SetDefaultDouble(m_pubHandle, defaultValue); + return wpi::nt::SetDefaultDouble(m_pubHandle, defaultValue); } /** @@ -430,7 +430,7 @@ class GenericPublisher : public Publisher { * @return True if the entry did not already have a value, otherwise False */ bool SetDefaultString(std::string_view defaultValue) { - return nt::SetDefaultString(m_pubHandle, defaultValue); + return wpi::nt::SetDefaultString(m_pubHandle, defaultValue); } /** @@ -440,7 +440,7 @@ class GenericPublisher : public Publisher { * @return True if the entry did not already have a value, otherwise False */ bool SetDefaultRaw(std::span defaultValue) { - return nt::SetDefaultRaw(m_pubHandle, defaultValue); + return wpi::nt::SetDefaultRaw(m_pubHandle, defaultValue); } /** @@ -450,7 +450,7 @@ class GenericPublisher : public Publisher { * @return True if the entry did not already have a value, otherwise False */ bool SetDefaultBooleanArray(std::span defaultValue) { - return nt::SetDefaultBooleanArray(m_pubHandle, defaultValue); + return wpi::nt::SetDefaultBooleanArray(m_pubHandle, defaultValue); } /** @@ -460,7 +460,7 @@ class GenericPublisher : public Publisher { * @return True if the entry did not already have a value, otherwise False */ bool SetDefaultIntegerArray(std::span defaultValue) { - return nt::SetDefaultIntegerArray(m_pubHandle, defaultValue); + return wpi::nt::SetDefaultIntegerArray(m_pubHandle, defaultValue); } /** @@ -470,7 +470,7 @@ class GenericPublisher : public Publisher { * @return True if the entry did not already have a value, otherwise False */ bool SetDefaultFloatArray(std::span defaultValue) { - return nt::SetDefaultFloatArray(m_pubHandle, defaultValue); + return wpi::nt::SetDefaultFloatArray(m_pubHandle, defaultValue); } /** @@ -480,7 +480,7 @@ class GenericPublisher : public Publisher { * @return True if the entry did not already have a value, otherwise False */ bool SetDefaultDoubleArray(std::span defaultValue) { - return nt::SetDefaultDoubleArray(m_pubHandle, defaultValue); + return wpi::nt::SetDefaultDoubleArray(m_pubHandle, defaultValue); } /** @@ -490,7 +490,7 @@ class GenericPublisher : public Publisher { * @return True if the entry did not already have a value, otherwise False */ bool SetDefaultStringArray(std::span defaultValue) { - return nt::SetDefaultStringArray(m_pubHandle, defaultValue); + return wpi::nt::SetDefaultStringArray(m_pubHandle, defaultValue); } /** @@ -499,7 +499,7 @@ class GenericPublisher : public Publisher { * @return Topic */ TopicType GetTopic() const { - return Topic{::nt::GetTopicFromHandle(m_pubHandle)}; + return Topic{::wpi::nt::GetTopicFromHandle(m_pubHandle)}; } }; @@ -548,13 +548,13 @@ class GenericEntry final : public GenericSubscriber, public GenericPublisher { * @return Topic */ TopicType GetTopic() const { - return Topic{::nt::GetTopicFromHandle(m_subHandle)}; + return Topic{::wpi::nt::GetTopicFromHandle(m_subHandle)}; } /** * Stops publishing the entry if it's published. */ - void Unpublish() { ::nt::Unpublish(m_pubHandle); } + void Unpublish() { ::wpi::nt::Unpublish(m_pubHandle); } }; -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/main/native/include/wpi/nt/MultiSubscriber.hpp b/ntcore/src/main/native/include/wpi/nt/MultiSubscriber.hpp index 54d3dcb777..eff021e223 100644 --- a/ntcore/src/main/native/include/wpi/nt/MultiSubscriber.hpp +++ b/ntcore/src/main/native/include/wpi/nt/MultiSubscriber.hpp @@ -10,7 +10,7 @@ #include "wpi/nt/NetworkTableInstance.hpp" #include "wpi/nt/ntcore_cpp.hpp" -namespace nt { +namespace wpi::nt { /** * Subscribe to multiple topics based on one or more topic name prefixes. Can be @@ -31,7 +31,7 @@ class MultiSubscriber final { MultiSubscriber(NetworkTableInstance inst, std::span prefixes, const PubSubOptions& options = kDefaultPubSubOptions) - : m_handle{::nt::SubscribeMultiple(inst.GetHandle(), prefixes, options)} { + : m_handle{::wpi::nt::SubscribeMultiple(inst.GetHandle(), prefixes, options)} { } MultiSubscriber(const MultiSubscriber&) = delete; @@ -43,7 +43,7 @@ class MultiSubscriber final { MultiSubscriber& operator=(MultiSubscriber&& rhs) { if (m_handle != 0) { - ::nt::UnsubscribeMultiple(m_handle); + ::wpi::nt::UnsubscribeMultiple(m_handle); } m_handle = rhs.m_handle; rhs.m_handle = 0; @@ -52,7 +52,7 @@ class MultiSubscriber final { ~MultiSubscriber() { if (m_handle != 0) { - ::nt::UnsubscribeMultiple(m_handle); + ::wpi::nt::UnsubscribeMultiple(m_handle); } } @@ -74,4 +74,4 @@ class MultiSubscriber final { NT_MultiSubscriber m_handle{0}; }; -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/main/native/include/wpi/nt/NTSendable.hpp b/ntcore/src/main/native/include/wpi/nt/NTSendable.hpp index 2153938c79..3e9ae3a71e 100644 --- a/ntcore/src/main/native/include/wpi/nt/NTSendable.hpp +++ b/ntcore/src/main/native/include/wpi/nt/NTSendable.hpp @@ -6,14 +6,14 @@ #include "wpi/util/sendable/Sendable.hpp" -namespace nt { +namespace wpi::nt { class NTSendableBuilder; /** * Interface for NetworkTable Sendable objects. */ -class NTSendable : public wpi::Sendable { +class NTSendable : public wpi::util::Sendable { public: /** * Initializes this Sendable object. @@ -22,7 +22,7 @@ class NTSendable : public wpi::Sendable { */ virtual void InitSendable(NTSendableBuilder& builder) = 0; - void InitSendable(wpi::SendableBuilder& builder) override; + void InitSendable(wpi::util::SendableBuilder& builder) override; }; -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/main/native/include/wpi/nt/NTSendableBuilder.hpp b/ntcore/src/main/native/include/wpi/nt/NTSendableBuilder.hpp index ebcca731ea..79a0881ba6 100644 --- a/ntcore/src/main/native/include/wpi/nt/NTSendableBuilder.hpp +++ b/ntcore/src/main/native/include/wpi/nt/NTSendableBuilder.hpp @@ -12,13 +12,13 @@ #include "wpi/util/FunctionExtras.hpp" #include "wpi/util/sendable/SendableBuilder.hpp" -namespace nt { +namespace wpi::nt { /** * Helper class for building Sendable dashboard representations for * NetworkTables. */ -class NTSendableBuilder : public wpi::SendableBuilder { +class NTSendableBuilder : public wpi::util::SendableBuilder { public: /** * Set the function that should be called to update the network table @@ -28,7 +28,7 @@ class NTSendableBuilder : public wpi::SendableBuilder { * * @param func function */ - virtual void SetUpdateTable(wpi::unique_function func) = 0; + virtual void SetUpdateTable(wpi::util::unique_function func) = 0; /** * Add a property without getters or setters. This can be used to get @@ -53,4 +53,4 @@ class NTSendableBuilder : public wpi::SendableBuilder { BackendKind GetBackendKind() const override; }; -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/main/native/include/wpi/nt/NetworkTable.hpp b/ntcore/src/main/native/include/wpi/nt/NetworkTable.hpp index 98bed3a5c4..47f3116e10 100644 --- a/ntcore/src/main/native/include/wpi/nt/NetworkTable.hpp +++ b/ntcore/src/main/native/include/wpi/nt/NetworkTable.hpp @@ -20,7 +20,7 @@ #include "wpi/util/protobuf/Protobuf.hpp" #include "wpi/util/struct/Struct.hpp" -namespace nt { +namespace wpi::nt { class BooleanArrayTopic; class BooleanTopic; @@ -31,16 +31,16 @@ class FloatTopic; class IntegerArrayTopic; class IntegerTopic; class NetworkTableInstance; -template +template class ProtobufTopic; class RawTopic; class StringArrayTopic; class StringTopic; template - requires wpi::StructSerializable + requires wpi::util::StructSerializable class StructArrayTopic; template - requires wpi::StructSerializable + requires wpi::util::StructSerializable class StructTopic; class Topic; @@ -58,8 +58,8 @@ class NetworkTable final { private: NT_Inst m_inst; std::string m_path; - mutable wpi::mutex m_mutex; - mutable wpi::StringMap m_entries; + mutable wpi::util::mutex m_mutex; + mutable wpi::util::StringMap m_entries; struct private_init {}; friend class NetworkTableInstance; @@ -94,7 +94,7 @@ class NetworkTable final { bool withLeadingSlash = true); static std::string_view NormalizeKey(std::string_view key, - wpi::SmallVectorImpl& buf, + wpi::util::SmallVectorImpl& buf, bool withLeadingSlash = true); /** @@ -236,7 +236,7 @@ class NetworkTable final { * @param name topic name * @return Topic */ - template + template ProtobufTopic GetProtobufTopic(std::string_view name) const { return ProtobufTopic{GetTopic(name)}; } @@ -249,7 +249,7 @@ class NetworkTable final { * @return Topic */ template - requires wpi::StructSerializable + requires wpi::util::StructSerializable StructTopic GetStructTopic(std::string_view name, I... info) const { return StructTopic{GetTopic(name), std::move(info)...}; } @@ -262,7 +262,7 @@ class NetworkTable final { * @return Topic */ template - requires wpi::StructSerializable + requires wpi::util::StructSerializable StructArrayTopic GetStructArrayTopic(std::string_view name, I... info) const { return StructArrayTopic{GetTopic(name), std::move(info)...}; @@ -674,4 +674,4 @@ class NetworkTable final { void RemoveListener(NT_Listener listener); }; -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/main/native/include/wpi/nt/NetworkTableEntry.hpp b/ntcore/src/main/native/include/wpi/nt/NetworkTableEntry.hpp index 3cd11c37fd..7fd4a8b14a 100644 --- a/ntcore/src/main/native/include/wpi/nt/NetworkTableEntry.hpp +++ b/ntcore/src/main/native/include/wpi/nt/NetworkTableEntry.hpp @@ -15,7 +15,7 @@ #include "wpi/nt/NetworkTableValue.hpp" #include "wpi/nt/ntcore_cpp.hpp" -namespace nt { +namespace wpi::nt { class NetworkTableInstance; class Topic; @@ -109,7 +109,7 @@ class NetworkTableEntry final { * @return the entry's value or the given default value */ bool GetBoolean(bool defaultValue) const { - return nt::GetBoolean(m_handle, defaultValue); + return wpi::nt::GetBoolean(m_handle, defaultValue); } /** @@ -120,7 +120,7 @@ class NetworkTableEntry final { * @return the entry's value or the given default value */ int64_t GetInteger(int64_t defaultValue) const { - return nt::GetInteger(m_handle, defaultValue); + return wpi::nt::GetInteger(m_handle, defaultValue); } /** @@ -131,7 +131,7 @@ class NetworkTableEntry final { * @return the entry's value or the given default value */ float GetFloat(float defaultValue) const { - return nt::GetFloat(m_handle, defaultValue); + return wpi::nt::GetFloat(m_handle, defaultValue); } /** @@ -142,7 +142,7 @@ class NetworkTableEntry final { * @return the entry's value or the given default value */ double GetDouble(double defaultValue) const { - return nt::GetDouble(m_handle, defaultValue); + return wpi::nt::GetDouble(m_handle, defaultValue); } /** @@ -153,7 +153,7 @@ class NetworkTableEntry final { * @return the entry's value or the given default value */ std::string GetString(std::string_view defaultValue) const { - return nt::GetString(m_handle, defaultValue); + return wpi::nt::GetString(m_handle, defaultValue); } /** @@ -164,7 +164,7 @@ class NetworkTableEntry final { * @return the entry's value or the given default value */ std::vector GetRaw(std::span defaultValue) const { - return nt::GetRaw(m_handle, defaultValue); + return wpi::nt::GetRaw(m_handle, defaultValue); } /** @@ -182,7 +182,7 @@ class NetworkTableEntry final { * non-zero value is true. */ std::vector GetBooleanArray(std::span defaultValue) const { - return nt::GetBooleanArray(m_handle, defaultValue); + return wpi::nt::GetBooleanArray(m_handle, defaultValue); } /** @@ -197,7 +197,7 @@ class NetworkTableEntry final { */ std::vector GetIntegerArray( std::span defaultValue) const { - return nt::GetIntegerArray(m_handle, defaultValue); + return wpi::nt::GetIntegerArray(m_handle, defaultValue); } /** @@ -211,7 +211,7 @@ class NetworkTableEntry final { * concern, use GetValue() instead. */ std::vector GetFloatArray(std::span defaultValue) const { - return nt::GetFloatArray(m_handle, defaultValue); + return wpi::nt::GetFloatArray(m_handle, defaultValue); } /** @@ -226,7 +226,7 @@ class NetworkTableEntry final { */ std::vector GetDoubleArray( std::span defaultValue) const { - return nt::GetDoubleArray(m_handle, defaultValue); + return wpi::nt::GetDoubleArray(m_handle, defaultValue); } /** @@ -241,7 +241,7 @@ class NetworkTableEntry final { */ std::vector GetStringArray( std::span defaultValue) const { - return nt::GetStringArray(m_handle, defaultValue); + return wpi::nt::GetStringArray(m_handle, defaultValue); } /** @@ -253,7 +253,7 @@ class NetworkTableEntry final { * published since the previous call. */ std::vector ReadQueue() { - return nt::ReadQueueValue(m_handle); + return wpi::nt::ReadQueueValue(m_handle); } /** @@ -273,7 +273,7 @@ class NetworkTableEntry final { * @return True if the entry did not already have a value, otherwise False */ bool SetDefaultBoolean(bool defaultValue) { - return nt::SetDefaultBoolean(m_handle, defaultValue); + return wpi::nt::SetDefaultBoolean(m_handle, defaultValue); } /** @@ -283,7 +283,7 @@ class NetworkTableEntry final { * @return True if the entry did not already have a value, otherwise False */ bool SetDefaultInteger(int64_t defaultValue) { - return nt::SetDefaultInteger(m_handle, defaultValue); + return wpi::nt::SetDefaultInteger(m_handle, defaultValue); } /** @@ -293,7 +293,7 @@ class NetworkTableEntry final { * @return True if the entry did not already have a value, otherwise False */ bool SetDefaultFloat(float defaultValue) { - return nt::SetDefaultFloat(m_handle, defaultValue); + return wpi::nt::SetDefaultFloat(m_handle, defaultValue); } /** @@ -303,7 +303,7 @@ class NetworkTableEntry final { * @return True if the entry did not already have a value, otherwise False */ bool SetDefaultDouble(double defaultValue) { - return nt::SetDefaultDouble(m_handle, defaultValue); + return wpi::nt::SetDefaultDouble(m_handle, defaultValue); } /** @@ -313,7 +313,7 @@ class NetworkTableEntry final { * @return True if the entry did not already have a value, otherwise False */ bool SetDefaultString(std::string_view defaultValue) { - return nt::SetDefaultString(m_handle, defaultValue); + return wpi::nt::SetDefaultString(m_handle, defaultValue); } /** @@ -323,7 +323,7 @@ class NetworkTableEntry final { * @return True if the entry did not already have a value, otherwise False */ bool SetDefaultRaw(std::span defaultValue) { - return nt::SetDefaultRaw(m_handle, defaultValue); + return wpi::nt::SetDefaultRaw(m_handle, defaultValue); } /** @@ -333,7 +333,7 @@ class NetworkTableEntry final { * @return True if the entry did not already have a value, otherwise False */ bool SetDefaultBooleanArray(std::span defaultValue) { - return nt::SetDefaultBooleanArray(m_handle, defaultValue); + return wpi::nt::SetDefaultBooleanArray(m_handle, defaultValue); } /** @@ -343,7 +343,7 @@ class NetworkTableEntry final { * @return True if the entry did not already have a value, otherwise False */ bool SetDefaultIntegerArray(std::span defaultValue) { - return nt::SetDefaultIntegerArray(m_handle, defaultValue); + return wpi::nt::SetDefaultIntegerArray(m_handle, defaultValue); } /** @@ -353,7 +353,7 @@ class NetworkTableEntry final { * @return True if the entry did not already have a value, otherwise False */ bool SetDefaultFloatArray(std::span defaultValue) { - return nt::SetDefaultFloatArray(m_handle, defaultValue); + return wpi::nt::SetDefaultFloatArray(m_handle, defaultValue); } /** @@ -363,7 +363,7 @@ class NetworkTableEntry final { * @return True if the entry did not already have a value, otherwise False */ bool SetDefaultDoubleArray(std::span defaultValue) { - return nt::SetDefaultDoubleArray(m_handle, defaultValue); + return wpi::nt::SetDefaultDoubleArray(m_handle, defaultValue); } /** @@ -373,7 +373,7 @@ class NetworkTableEntry final { * @return True if the entry did not already have a value, otherwise False */ bool SetDefaultStringArray(std::span defaultValue) { - return nt::SetDefaultStringArray(m_handle, defaultValue); + return wpi::nt::SetDefaultStringArray(m_handle, defaultValue); } /** @@ -388,73 +388,73 @@ class NetworkTableEntry final { * Sets the entry's value. * * @param value the value to set - * @param time the timestamp to set (0 = nt::Now()) + * @param time the timestamp to set (0 = wpi::nt::Now()) * @return False if the entry exists with a different type */ bool SetBoolean(bool value, int64_t time = 0) { - return nt::SetBoolean(m_handle, value, time); + return wpi::nt::SetBoolean(m_handle, value, time); } /** * Sets the entry's value. * * @param value the value to set - * @param time the timestamp to set (0 = nt::Now()) + * @param time the timestamp to set (0 = wpi::nt::Now()) * @return False if the entry exists with a different type */ bool SetInteger(int64_t value, int64_t time = 0) { - return nt::SetInteger(m_handle, value, time); + return wpi::nt::SetInteger(m_handle, value, time); } /** * Sets the entry's value. * * @param value the value to set - * @param time the timestamp to set (0 = nt::Now()) + * @param time the timestamp to set (0 = wpi::nt::Now()) * @return False if the entry exists with a different type */ bool SetFloat(float value, int64_t time = 0) { - return nt::SetFloat(m_handle, value, time); + return wpi::nt::SetFloat(m_handle, value, time); } /** * Sets the entry's value. * * @param value the value to set - * @param time the timestamp to set (0 = nt::Now()) + * @param time the timestamp to set (0 = wpi::nt::Now()) * @return False if the entry exists with a different type */ bool SetDouble(double value, int64_t time = 0) { - return nt::SetDouble(m_handle, value, time); + return wpi::nt::SetDouble(m_handle, value, time); } /** * Sets the entry's value. * * @param value the value to set - * @param time the timestamp to set (0 = nt::Now()) + * @param time the timestamp to set (0 = wpi::nt::Now()) * @return False if the entry exists with a different type */ bool SetString(std::string_view value, int64_t time = 0) { - return nt::SetString(m_handle, value, time); + return wpi::nt::SetString(m_handle, value, time); } /** * Sets the entry's value. * * @param value the value to set - * @param time the timestamp to set (0 = nt::Now()) + * @param time the timestamp to set (0 = wpi::nt::Now()) * @return False if the entry exists with a different type */ bool SetRaw(std::span value, int64_t time = 0) { - return nt::SetRaw(m_handle, value, time); + return wpi::nt::SetRaw(m_handle, value, time); } /** * Sets the entry's value. * * @param value the value to set - * @param time the timestamp to set (0 = nt::Now()) + * @param time the timestamp to set (0 = wpi::nt::Now()) * @return False if the entry exists with a different type */ bool SetBooleanArray(std::span value, int64_t time = 0) { @@ -465,69 +465,69 @@ class NetworkTableEntry final { * Sets the entry's value. * * @param value the value to set - * @param time the timestamp to set (0 = nt::Now()) + * @param time the timestamp to set (0 = wpi::nt::Now()) * @return False if the entry exists with a different type */ bool SetBooleanArray(std::span value, int64_t time = 0) { - return nt::SetBooleanArray(m_handle, value, time); + return wpi::nt::SetBooleanArray(m_handle, value, time); } /** * Sets the entry's value. * * @param value the value to set - * @param time the timestamp to set (0 = nt::Now()) + * @param time the timestamp to set (0 = wpi::nt::Now()) * @return False if the entry exists with a different type */ bool SetIntegerArray(std::span value, int64_t time = 0) { - return nt::SetIntegerArray(m_handle, value, time); + return wpi::nt::SetIntegerArray(m_handle, value, time); } /** * Sets the entry's value. * * @param value the value to set - * @param time the timestamp to set (0 = nt::Now()) + * @param time the timestamp to set (0 = wpi::nt::Now()) * @return False if the entry exists with a different type */ bool SetFloatArray(std::span value, int64_t time = 0) { - return nt::SetFloatArray(m_handle, value, time); + return wpi::nt::SetFloatArray(m_handle, value, time); } /** * Sets the entry's value. * * @param value the value to set - * @param time the timestamp to set (0 = nt::Now()) + * @param time the timestamp to set (0 = wpi::nt::Now()) * @return False if the entry exists with a different type */ bool SetDoubleArray(std::span value, int64_t time = 0) { - return nt::SetDoubleArray(m_handle, value, time); + return wpi::nt::SetDoubleArray(m_handle, value, time); } /** * Sets the entry's value. * * @param value the value to set - * @param time the timestamp to set (0 = nt::Now()) + * @param time the timestamp to set (0 = wpi::nt::Now()) * @return False if the entry exists with a different type */ bool SetStringArray(std::span value, int64_t time = 0) { - return nt::SetStringArray(m_handle, value, time); + return wpi::nt::SetStringArray(m_handle, value, time); } /** * Make value persistent through program restarts. */ void SetPersistent() { - nt::SetTopicPersistent(nt::GetTopicFromHandle(m_handle), true); + wpi::nt::SetTopicPersistent(wpi::nt::GetTopicFromHandle(m_handle), true); } /** * Stop making value persistent through program restarts. */ void ClearPersistent() { - nt::SetTopicPersistent(nt::GetTopicFromHandle(m_handle), false); + wpi::nt::SetTopicPersistent(wpi::nt::GetTopicFromHandle(m_handle), false); } /** @@ -536,13 +536,13 @@ class NetworkTableEntry final { * @return True if the value is persistent. */ bool IsPersistent() const { - return nt::GetTopicPersistent(nt::GetTopicFromHandle(m_handle)); + return wpi::nt::GetTopicPersistent(wpi::nt::GetTopicFromHandle(m_handle)); } /** * Stops publishing the entry if it's been published. */ - void Unpublish() { return nt::Unpublish(m_handle); } + void Unpublish() { return wpi::nt::Unpublish(m_handle); } /** * Gets the entry's topic. @@ -562,4 +562,4 @@ class NetworkTableEntry final { NT_Entry m_handle{0}; }; -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/main/native/include/wpi/nt/NetworkTableInstance.hpp b/ntcore/src/main/native/include/wpi/nt/NetworkTableInstance.hpp index fd3ec015c0..eab900ff8b 100644 --- a/ntcore/src/main/native/include/wpi/nt/NetworkTableInstance.hpp +++ b/ntcore/src/main/native/include/wpi/nt/NetworkTableInstance.hpp @@ -18,7 +18,7 @@ #include "wpi/util/protobuf/Protobuf.hpp" #include "wpi/util/struct/Struct.hpp" -namespace nt { +namespace wpi::nt { class BooleanArrayTopic; class BooleanTopic; @@ -29,16 +29,16 @@ class FloatTopic; class IntegerArrayTopic; class IntegerTopic; class MultiSubscriber; -template +template class ProtobufTopic; class RawTopic; class StringArrayTopic; class StringTopic; template - requires wpi::StructSerializable + requires wpi::util::StructSerializable class StructArrayTopic; template - requires wpi::StructSerializable + requires wpi::util::StructSerializable class StructTopic; class Subscriber; class Topic; @@ -255,7 +255,7 @@ class NetworkTableInstance final { * @param name topic name * @return Topic */ - template + template ProtobufTopic GetProtobufTopic(std::string_view name) const { return ProtobufTopic{GetTopic(name)}; } @@ -268,7 +268,7 @@ class NetworkTableInstance final { * @return Topic */ template - requires wpi::StructSerializable + requires wpi::util::StructSerializable StructTopic GetStructTopic(std::string_view name, I... info) const { return StructTopic{GetTopic(name), std::move(info)...}; } @@ -281,7 +281,7 @@ class NetworkTableInstance final { * @return Topic */ template - requires wpi::StructSerializable + requires wpi::util::StructSerializable StructArrayTopic GetStructArrayTopic(std::string_view name, I... info) const { return StructArrayTopic{GetTopic(name), std::move(info)...}; @@ -295,7 +295,7 @@ class NetworkTableInstance final { * @return Array of topics. */ std::vector GetTopics() { - auto handles = ::nt::GetTopics(m_handle, "", 0); + auto handles = ::wpi::nt::GetTopics(m_handle, "", 0); return {handles.begin(), handles.end()}; } @@ -310,7 +310,7 @@ class NetworkTableInstance final { * @return Array of topics. */ std::vector GetTopics(std::string_view prefix) { - auto handles = ::nt::GetTopics(m_handle, prefix, 0); + auto handles = ::wpi::nt::GetTopics(m_handle, prefix, 0); return {handles.begin(), handles.end()}; } @@ -327,7 +327,7 @@ class NetworkTableInstance final { * @return Array of topics. */ std::vector GetTopics(std::string_view prefix, unsigned int types) { - auto handles = ::nt::GetTopics(m_handle, prefix, types); + auto handles = ::wpi::nt::GetTopics(m_handle, prefix, types); return {handles.begin(), handles.end()}; } @@ -344,7 +344,7 @@ class NetworkTableInstance final { */ std::vector GetTopics(std::string_view prefix, std::span types) { - auto handles = ::nt::GetTopics(m_handle, prefix, types); + auto handles = ::wpi::nt::GetTopics(m_handle, prefix, types); return {handles.begin(), handles.end()}; } @@ -356,7 +356,7 @@ class NetworkTableInstance final { * @return Array of topic information. */ std::vector GetTopicInfo() { - return ::nt::GetTopicInfo(m_handle, "", 0); + return ::wpi::nt::GetTopicInfo(m_handle, "", 0); } /** @@ -371,7 +371,7 @@ class NetworkTableInstance final { * @return Array of topic information. */ std::vector GetTopicInfo(std::string_view prefix) { - return ::nt::GetTopicInfo(m_handle, prefix, 0); + return ::wpi::nt::GetTopicInfo(m_handle, prefix, 0); } /** @@ -389,7 +389,7 @@ class NetworkTableInstance final { */ std::vector GetTopicInfo(std::string_view prefix, unsigned int types) { - return ::nt::GetTopicInfo(m_handle, prefix, types); + return ::wpi::nt::GetTopicInfo(m_handle, prefix, types); } /** @@ -406,7 +406,7 @@ class NetworkTableInstance final { */ std::vector GetTopicInfo(std::string_view prefix, std::span types) { - return ::nt::GetTopicInfo(m_handle, prefix, types); + return ::wpi::nt::GetTopicInfo(m_handle, prefix, types); } /** @@ -416,7 +416,7 @@ class NetworkTableInstance final { * @return Network table entry. */ NetworkTableEntry GetEntry(std::string_view name) { - return NetworkTableEntry{::nt::GetEntry(m_handle, name)}; + return NetworkTableEntry{::wpi::nt::GetEntry(m_handle, name)}; } /** @@ -438,7 +438,7 @@ class NetworkTableInstance final { * @param listener Listener handle to remove */ static void RemoveListener(NT_Listener listener) { - ::nt::RemoveListener(listener); + ::wpi::nt::RemoveListener(listener); } /** @@ -452,7 +452,7 @@ class NetworkTableInstance final { * @return False if timed out, otherwise true. */ bool WaitForListenerQueue(double timeout) { - return ::nt::WaitForListenerQueue(m_handle, timeout); + return ::wpi::nt::WaitForListenerQueue(m_handle, timeout); } /** @@ -466,7 +466,7 @@ class NetworkTableInstance final { */ NT_Listener AddConnectionListener(bool immediate_notify, ListenerCallback callback) const { - return ::nt::AddListener( + return ::wpi::nt::AddListener( m_handle, NT_EVENT_CONNECTION | (immediate_notify ? NT_EVENT_IMMEDIATE : 0), std::move(callback)); @@ -485,7 +485,7 @@ class NetworkTableInstance final { */ NT_Listener AddTimeSyncListener(bool immediate_notify, ListenerCallback callback) const { - return ::nt::AddListener( + return ::wpi::nt::AddListener( m_handle, NT_EVENT_TIMESYNC | (immediate_notify ? NT_EVENT_IMMEDIATE : 0), std::move(callback)); @@ -566,7 +566,7 @@ class NetworkTableInstance final { */ NT_Listener AddListener(std::span prefixes, int eventMask, ListenerCallback listener) { - return ::nt::AddListener(m_handle, prefixes, eventMask, + return ::wpi::nt::AddListener(m_handle, prefixes, eventMask, std::move(listener)); } @@ -582,20 +582,20 @@ class NetworkTableInstance final { * * @return Bitmask of NetworkMode. */ - unsigned int GetNetworkMode() const { return ::nt::GetNetworkMode(m_handle); } + unsigned int GetNetworkMode() const { return ::wpi::nt::GetNetworkMode(m_handle); } /** * Starts local-only operation. Prevents calls to StartServer or StartClient * from taking effect. Has no effect if StartServer or StartClient * has already been called. */ - void StartLocal() { ::nt::StartLocal(m_handle); } + void StartLocal() { ::wpi::nt::StartLocal(m_handle); } /** * Stops local-only operation. StartServer or StartClient can be called after * this call to start a server or client. */ - void StopLocal() { ::nt::StopLocal(m_handle); } + void StopLocal() { ::wpi::nt::StopLocal(m_handle); } /** * Starts a server using the specified filename, listening address, and port. @@ -610,13 +610,13 @@ class NetworkTableInstance final { void StartServer(std::string_view persist_filename = "networktables.json", const char* listen_address = "", unsigned int port = kDefaultPort) { - ::nt::StartServer(m_handle, persist_filename, listen_address, port); + ::wpi::nt::StartServer(m_handle, persist_filename, listen_address, port); } /** * Stops the server if it is running. */ - void StopServer() { ::nt::StopServer(m_handle); } + void StopServer() { ::wpi::nt::StopServer(m_handle); } /** * Starts a client. Use SetServer or SetServerTeam to set the server name @@ -625,13 +625,13 @@ class NetworkTableInstance final { * @param identity network identity to advertise (cannot be empty string) */ void StartClient(std::string_view identity) { - ::nt::StartClient(m_handle, identity); + ::wpi::nt::StartClient(m_handle, identity); } /** * Stops the client if it is running. */ - void StopClient() { ::nt::StopClient(m_handle); } + void StopClient() { ::wpi::nt::StopClient(m_handle); } /** * Sets server address and port for client (without restarting client). @@ -640,7 +640,7 @@ class NetworkTableInstance final { * @param port port to communicate over (0 = default) */ void SetServer(std::string_view server_name, unsigned int port = 0) { - ::nt::SetServer(m_handle, server_name, port); + ::wpi::nt::SetServer(m_handle, server_name, port); } /** @@ -651,7 +651,7 @@ class NetworkTableInstance final { */ void SetServer( std::span> servers) { - ::nt::SetServer(m_handle, servers); + ::wpi::nt::SetServer(m_handle, servers); } /** @@ -672,14 +672,14 @@ class NetworkTableInstance final { * @param port port to communicate over (0 = default) */ void SetServerTeam(unsigned int team, unsigned int port = 0) { - ::nt::SetServerTeam(m_handle, team, port); + ::wpi::nt::SetServerTeam(m_handle, team, port); } /** * Disconnects the client if it's running and connected. This will * automatically start reconnection attempts to the current server list. */ - void Disconnect() { ::nt::Disconnect(m_handle); } + void Disconnect() { ::wpi::nt::Disconnect(m_handle); } /** * Starts requesting server address from Driver Station. @@ -689,19 +689,19 @@ class NetworkTableInstance final { * @param port server port to use in combination with IP from DS (0 = default) */ void StartDSClient(unsigned int port = 0) { - ::nt::StartDSClient(m_handle, port); + ::wpi::nt::StartDSClient(m_handle, port); } /** * Stops requesting server address from Driver Station. */ - void StopDSClient() { ::nt::StopDSClient(m_handle); } + void StopDSClient() { ::wpi::nt::StopDSClient(m_handle); } /** * Flushes all updated values immediately to the local client/server. This * does not flush to the network. */ - void FlushLocal() const { ::nt::FlushLocal(m_handle); } + void FlushLocal() const { ::wpi::nt::FlushLocal(m_handle); } /** * Flushes all updated values immediately to the network. @@ -709,7 +709,7 @@ class NetworkTableInstance final { * This is primarily useful for synchronizing network updates with * user code. */ - void Flush() const { ::nt::Flush(m_handle); } + void Flush() const { ::wpi::nt::Flush(m_handle); } /** * Get information on the currently established network connections. @@ -718,7 +718,7 @@ class NetworkTableInstance final { * @return array of connection information */ std::vector GetConnections() const { - return ::nt::GetConnections(m_handle); + return ::wpi::nt::GetConnections(m_handle); } /** @@ -726,7 +726,7 @@ class NetworkTableInstance final { * * @return True if connected. */ - bool IsConnected() const { return ::nt::IsConnected(m_handle); } + bool IsConnected() const { return ::wpi::nt::IsConnected(m_handle); } /** * Get the time offset between server time and local time. Add this value to @@ -740,14 +740,14 @@ class NetworkTableInstance final { * @return Time offset in microseconds (optional) */ std::optional GetServerTimeOffset() const { - return ::nt::GetServerTimeOffset(m_handle); + return ::wpi::nt::GetServerTimeOffset(m_handle); } /** @} */ /** * @{ - * @name Data Logger Functions + * @name Data wpi::util::Logger Functions */ /** @@ -763,7 +763,7 @@ class NetworkTableInstance final { NT_DataLogger StartEntryDataLog(wpi::log::DataLog& log, std::string_view prefix, std::string_view logPrefix) { - return ::nt::StartEntryDataLog(m_handle, log, prefix, logPrefix); + return ::wpi::nt::StartEntryDataLog(m_handle, log, prefix, logPrefix); } /** @@ -772,7 +772,7 @@ class NetworkTableInstance final { * @param logger data logger handle */ static void StopEntryDataLog(NT_DataLogger logger) { - ::nt::StopEntryDataLog(logger); + ::wpi::nt::StopEntryDataLog(logger); } /** @@ -785,7 +785,7 @@ class NetworkTableInstance final { */ NT_ConnectionDataLogger StartConnectionDataLog(wpi::log::DataLog& log, std::string_view name) { - return ::nt::StartConnectionDataLog(m_handle, log, name); + return ::wpi::nt::StartConnectionDataLog(m_handle, log, name); } /** @@ -794,14 +794,14 @@ class NetworkTableInstance final { * @param logger data logger handle */ static void StopConnectionDataLog(NT_ConnectionDataLogger logger) { - ::nt::StopConnectionDataLog(logger); + ::wpi::nt::StopConnectionDataLog(logger); } /** @} */ /** * @{ - * @name Logger Functions + * @name wpi::util::Logger Functions */ /** @@ -818,7 +818,7 @@ class NetworkTableInstance final { */ NT_Listener AddLogger(unsigned int minLevel, unsigned int maxLevel, ListenerCallback func) { - return ::nt::AddLogger(m_handle, minLevel, maxLevel, std::move(func)); + return ::wpi::nt::AddLogger(m_handle, minLevel, maxLevel, std::move(func)); } /** @} */ @@ -838,7 +838,7 @@ class NetworkTableInstance final { * @return True if schema already registered */ bool HasSchema(std::string_view name) const { - return ::nt::HasSchema(m_handle, name); + return ::wpi::nt::HasSchema(m_handle, name); } /** @@ -857,7 +857,7 @@ class NetworkTableInstance final { */ void AddSchema(std::string_view name, std::string_view type, std::span schema) { - ::nt::AddSchema(m_handle, name, type, schema); + ::wpi::nt::AddSchema(m_handle, name, type, schema); } /** @@ -876,7 +876,7 @@ class NetworkTableInstance final { */ void AddSchema(std::string_view name, std::string_view type, std::string_view schema) { - ::nt::AddSchema(m_handle, name, type, schema); + ::wpi::nt::AddSchema(m_handle, name, type, schema); } // Suppress unused-lambda-capture warning on AddSchema() call @@ -892,8 +892,8 @@ class NetworkTableInstance final { * @tparam T protobuf serializable type * @param msg protobuf message */ - template - void AddProtobufSchema(wpi::ProtobufMessage& msg) { + template + void AddProtobufSchema(wpi::util::ProtobufMessage& msg) { msg.ForEachProtobufDescriptor( [this](auto typeString) { return HasSchema(typeString); }, [this](auto typeString, auto schema) { @@ -909,9 +909,9 @@ class NetworkTableInstance final { * @param info optional struct type info */ template - requires wpi::StructSerializable + requires wpi::util::StructSerializable void AddStructSchema(const I&... info) { - wpi::ForEachStructSchema( + wpi::util::ForEachStructSchema( [this](auto typeString, auto schema) { AddSchema(typeString, "structschema", schema); }, @@ -933,4 +933,4 @@ class NetworkTableInstance final { NT_Inst m_handle{0}; }; -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/main/native/include/wpi/nt/NetworkTableListener.hpp b/ntcore/src/main/native/include/wpi/nt/NetworkTableListener.hpp index 6f989048a8..244423c325 100644 --- a/ntcore/src/main/native/include/wpi/nt/NetworkTableListener.hpp +++ b/ntcore/src/main/native/include/wpi/nt/NetworkTableListener.hpp @@ -15,7 +15,7 @@ #include "wpi/nt/Topic.hpp" #include "wpi/nt/ntcore_cpp.hpp" -namespace nt { +namespace wpi::nt { class MultiSubscriber; class NetworkTableEntry; @@ -47,7 +47,7 @@ class NetworkTableListener final { static NetworkTableListener CreateListener( NetworkTableInstance inst, std::span prefixes, unsigned int mask, ListenerCallback listener) { - return NetworkTableListener{::nt::AddListener(inst.GetHandle(), prefixes, + return NetworkTableListener{::wpi::nt::AddListener(inst.GetHandle(), prefixes, mask, std::move(listener))}; } @@ -63,7 +63,7 @@ class NetworkTableListener final { static NetworkTableListener CreateListener(Topic topic, unsigned int mask, ListenerCallback listener) { return NetworkTableListener{ - nt::AddListener(topic.GetHandle(), mask, std::move(listener))}; + wpi::nt::AddListener(topic.GetHandle(), mask, std::move(listener))}; } /** @@ -79,7 +79,7 @@ class NetworkTableListener final { unsigned int mask, ListenerCallback listener) { return NetworkTableListener{ - ::nt::AddListener(subscriber.GetHandle(), mask, std::move(listener))}; + ::wpi::nt::AddListener(subscriber.GetHandle(), mask, std::move(listener))}; } /** @@ -95,7 +95,7 @@ class NetworkTableListener final { unsigned int mask, ListenerCallback listener) { return NetworkTableListener{ - ::nt::AddListener(subscriber.GetHandle(), mask, std::move(listener))}; + ::wpi::nt::AddListener(subscriber.GetHandle(), mask, std::move(listener))}; } /** @@ -110,7 +110,7 @@ class NetworkTableListener final { unsigned int mask, ListenerCallback listener) { return NetworkTableListener{ - ::nt::AddListener(entry.GetHandle(), mask, std::move(listener))}; + ::wpi::nt::AddListener(entry.GetHandle(), mask, std::move(listener))}; } /** @@ -124,7 +124,7 @@ class NetworkTableListener final { static NetworkTableListener CreateConnectionListener( NetworkTableInstance inst, bool immediate_notify, ListenerCallback listener) { - return NetworkTableListener{::nt::AddListener( + return NetworkTableListener{::wpi::nt::AddListener( inst.GetHandle(), NT_EVENT_CONNECTION | (immediate_notify ? NT_EVENT_IMMEDIATE : 0), std::move(listener))}; @@ -142,7 +142,7 @@ class NetworkTableListener final { static NetworkTableListener CreateTimeSyncListener( NetworkTableInstance inst, bool immediate_notify, ListenerCallback listener) { - return NetworkTableListener{::nt::AddListener( + return NetworkTableListener{::wpi::nt::AddListener( inst.GetHandle(), NT_EVENT_TIMESYNC | (immediate_notify ? NT_EVENT_IMMEDIATE : 0), std::move(listener))}; @@ -166,7 +166,7 @@ class NetworkTableListener final { unsigned int minLevel, unsigned int maxLevel, ListenerCallback listener) { - return NetworkTableListener{::nt::AddLogger(inst.GetHandle(), minLevel, + return NetworkTableListener{::wpi::nt::AddLogger(inst.GetHandle(), minLevel, maxLevel, std::move(listener))}; } @@ -179,7 +179,7 @@ class NetworkTableListener final { NetworkTableListener& operator=(NetworkTableListener&& rhs) { if (m_handle != 0) { - nt::RemoveListener(m_handle); + wpi::nt::RemoveListener(m_handle); } m_handle = rhs.m_handle; rhs.m_handle = 0; @@ -188,7 +188,7 @@ class NetworkTableListener final { ~NetworkTableListener() { if (m_handle != 0) { - nt::RemoveListener(m_handle); + wpi::nt::RemoveListener(m_handle); } } @@ -213,7 +213,7 @@ class NetworkTableListener final { */ bool WaitForQueue(double timeout) { if (m_handle != 0) { - return nt::WaitForListenerQueue(m_handle, timeout); + return wpi::nt::WaitForListenerQueue(m_handle, timeout); } else { return false; } @@ -240,7 +240,7 @@ class NetworkTableListenerPoller final { * @param inst Instance */ explicit NetworkTableListenerPoller(NetworkTableInstance inst) - : m_handle(nt::CreateListenerPoller(inst.GetHandle())) {} + : m_handle(wpi::nt::CreateListenerPoller(inst.GetHandle())) {} NetworkTableListenerPoller(const NetworkTableListenerPoller&) = delete; NetworkTableListenerPoller& operator=(const NetworkTableListenerPoller&) = @@ -253,7 +253,7 @@ class NetworkTableListenerPoller final { NetworkTableListenerPoller& operator=(NetworkTableListenerPoller&& rhs) { if (m_handle != 0) { - nt::DestroyListenerPoller(m_handle); + wpi::nt::DestroyListenerPoller(m_handle); } m_handle = rhs.m_handle; rhs.m_handle = 0; @@ -262,7 +262,7 @@ class NetworkTableListenerPoller final { ~NetworkTableListenerPoller() { if (m_handle != 0) { - nt::DestroyListenerPoller(m_handle); + wpi::nt::DestroyListenerPoller(m_handle); } } @@ -286,7 +286,7 @@ class NetworkTableListenerPoller final { */ NT_Listener AddListener(std::span prefixes, unsigned int mask) { - return nt::AddPolledListener(m_handle, prefixes, mask); + return wpi::nt::AddPolledListener(m_handle, prefixes, mask); } /** @@ -298,7 +298,7 @@ class NetworkTableListenerPoller final { * @return Listener handle */ NT_Listener AddListener(Topic topic, unsigned int mask) { - return ::nt::AddPolledListener(m_handle, topic.GetHandle(), mask); + return ::wpi::nt::AddPolledListener(m_handle, topic.GetHandle(), mask); } /** @@ -310,7 +310,7 @@ class NetworkTableListenerPoller final { * @return Listener handle */ NT_Listener AddListener(Subscriber& subscriber, unsigned int mask) { - return ::nt::AddPolledListener(m_handle, subscriber.GetHandle(), mask); + return ::wpi::nt::AddPolledListener(m_handle, subscriber.GetHandle(), mask); } /** @@ -322,7 +322,7 @@ class NetworkTableListenerPoller final { * @return Listener handle */ NT_Listener AddListener(MultiSubscriber& subscriber, unsigned int mask) { - return ::nt::AddPolledListener(m_handle, subscriber.GetHandle(), mask); + return ::wpi::nt::AddPolledListener(m_handle, subscriber.GetHandle(), mask); } /** @@ -333,7 +333,7 @@ class NetworkTableListenerPoller final { * @return Listener handle */ NT_Listener AddListener(NetworkTableEntry& entry, unsigned int mask) { - return ::nt::AddPolledListener(m_handle, entry.GetHandle(), mask); + return ::wpi::nt::AddPolledListener(m_handle, entry.GetHandle(), mask); } /** @@ -345,8 +345,8 @@ class NetworkTableListenerPoller final { * @return Listener handle */ NT_Listener AddConnectionListener(bool immediate_notify) { - return ::nt::AddPolledListener( - m_handle, ::nt::GetInstanceFromHandle(m_handle), + return ::wpi::nt::AddPolledListener( + m_handle, ::wpi::nt::GetInstanceFromHandle(m_handle), NT_EVENT_CONNECTION | (immediate_notify ? NT_EVENT_IMMEDIATE : 0)); } @@ -361,8 +361,8 @@ class NetworkTableListenerPoller final { * @return Listener handle */ NT_Listener AddTimeSyncListener(bool immediate_notify) { - return ::nt::AddPolledListener( - m_handle, ::nt::GetInstanceFromHandle(m_handle), + return ::wpi::nt::AddPolledListener( + m_handle, ::wpi::nt::GetInstanceFromHandle(m_handle), NT_EVENT_TIMESYNC | (immediate_notify ? NT_EVENT_IMMEDIATE : 0)); } @@ -378,7 +378,7 @@ class NetworkTableListenerPoller final { * @return Listener handle */ NT_Listener AddLogger(unsigned int minLevel, unsigned int maxLevel) { - return ::nt::AddPolledLogger(m_handle, minLevel, maxLevel); + return ::wpi::nt::AddPolledLogger(m_handle, minLevel, maxLevel); } /** @@ -386,17 +386,17 @@ class NetworkTableListenerPoller final { * * @param listener Listener handle */ - void RemoveListener(NT_Listener listener) { ::nt::RemoveListener(listener); } + void RemoveListener(NT_Listener listener) { ::wpi::nt::RemoveListener(listener); } /** * Read events. * * @return Events since the previous call to ReadQueue() */ - std::vector ReadQueue() { return ::nt::ReadListenerQueue(m_handle); } + std::vector ReadQueue() { return ::wpi::nt::ReadListenerQueue(m_handle); } private: NT_ListenerPoller m_handle{0}; }; -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/main/native/include/wpi/nt/NetworkTableType.hpp b/ntcore/src/main/native/include/wpi/nt/NetworkTableType.hpp index df384346a0..7d3cd78b35 100644 --- a/ntcore/src/main/native/include/wpi/nt/NetworkTableType.hpp +++ b/ntcore/src/main/native/include/wpi/nt/NetworkTableType.hpp @@ -6,7 +6,7 @@ #include "wpi/nt/ntcore_c.h" -namespace nt { +namespace wpi::nt { /** * NetworkTable entry type. @@ -39,4 +39,4 @@ enum class NetworkTableType { kFloatArray = NT_FLOAT_ARRAY }; -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/main/native/include/wpi/nt/NetworkTableValue.hpp b/ntcore/src/main/native/include/wpi/nt/NetworkTableValue.hpp index 726643ecdc..b17a37d2db 100644 --- a/ntcore/src/main/native/include/wpi/nt/NetworkTableValue.hpp +++ b/ntcore/src/main/native/include/wpi/nt/NetworkTableValue.hpp @@ -18,7 +18,7 @@ #include "wpi/nt/ntcore_c.h" -namespace nt { +namespace wpi::nt { // Forward declare here to avoid circular dependency on ntcore_cpp.h int64_t Now(); @@ -91,14 +91,14 @@ class Value final { /** * Get the creation time of the value, in local time. * - * @return The time, in the units returned by nt::Now(). + * @return The time, in the units returned by wpi::nt::Now(). */ int64_t last_change() const { return m_val.last_change; } /** * Get the creation time of the value, in local time. * - * @return The time, in the units returned by nt::Now(). + * @return The time, in the units returned by wpi::nt::Now(). */ int64_t time() const { return m_val.last_change; } @@ -695,4 +695,4 @@ bool operator==(const Value& lhs, const Value& rhs); */ using NetworkTableValue = Value; -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/main/native/include/wpi/nt/ProtobufTopic.hpp b/ntcore/src/main/native/include/wpi/nt/ProtobufTopic.hpp index fdddb241e9..3b2e0a8a2f 100644 --- a/ntcore/src/main/native/include/wpi/nt/ProtobufTopic.hpp +++ b/ntcore/src/main/native/include/wpi/nt/ProtobufTopic.hpp @@ -19,15 +19,15 @@ #include "wpi/util/mutex.hpp" #include "wpi/util/protobuf/Protobuf.hpp" -namespace nt { +namespace wpi::nt { -template +template class ProtobufTopic; /** * NetworkTables protobuf-encoded value subscriber. */ -template +template class ProtobufSubscriber : public Subscriber { public: using TopicType = ProtobufTopic; @@ -45,7 +45,7 @@ class ProtobufSubscriber : public Subscriber { * @param msg Protobuf message * @param defaultValue Default value */ - ProtobufSubscriber(NT_Subscriber handle, wpi::ProtobufMessage msg, + ProtobufSubscriber(NT_Subscriber handle, wpi::util::ProtobufMessage msg, T defaultValue) : Subscriber{handle}, m_msg{std::move(msg)}, @@ -96,8 +96,8 @@ class ProtobufSubscriber : public Subscriber { * @return true if successful */ bool GetInto(T* out) { - wpi::SmallVector buf; - TimestampedRawView view = ::nt::GetAtomicRaw(m_subHandle, buf, {}); + wpi::util::SmallVector buf; + TimestampedRawView view = ::wpi::nt::GetAtomicRaw(m_subHandle, buf, {}); if (view.value.empty()) { return false; } else { @@ -124,8 +124,8 @@ class ProtobufSubscriber : public Subscriber { * @return timestamped value */ TimestampedValueType GetAtomic(const T& defaultValue) const { - wpi::SmallVector buf; - TimestampedRawView view = ::nt::GetAtomicRaw(m_subHandle, buf, {}); + wpi::util::SmallVector buf; + TimestampedRawView view = ::wpi::nt::GetAtomicRaw(m_subHandle, buf, {}); if (!view.value.empty()) { std::scoped_lock lock{m_mutex}; if (auto optval = m_msg.Unpack(view.value)) { @@ -147,7 +147,7 @@ class ProtobufSubscriber : public Subscriber { * have been published since the previous call. */ std::vector ReadQueue() { - auto raw = ::nt::ReadQueueRaw(m_subHandle); + auto raw = ::wpi::nt::ReadQueueRaw(m_subHandle); std::vector rv; rv.reserve(raw.size()); std::scoped_lock lock{m_mutex}; @@ -165,19 +165,19 @@ class ProtobufSubscriber : public Subscriber { * @return Topic */ TopicType GetTopic() const { - return ProtobufTopic{::nt::GetTopicFromHandle(m_subHandle)}; + return ProtobufTopic{::wpi::nt::GetTopicFromHandle(m_subHandle)}; } private: - mutable wpi::mutex m_mutex; - mutable wpi::ProtobufMessage m_msg; + mutable wpi::util::mutex m_mutex; + mutable wpi::util::ProtobufMessage m_msg; ValueType m_defaultValue; }; /** * NetworkTables protobuf-encoded value publisher. */ -template +template class ProtobufPublisher : public Publisher { public: using TopicType = ProtobufTopic; @@ -195,7 +195,7 @@ class ProtobufPublisher : public Publisher { * @param handle Native handle * @param msg Protobuf message */ - explicit ProtobufPublisher(NT_Publisher handle, wpi::ProtobufMessage msg) + explicit ProtobufPublisher(NT_Publisher handle, wpi::util::ProtobufMessage msg) : Publisher{handle}, m_msg{std::move(msg)} {} ProtobufPublisher(const ProtobufPublisher&) = delete; @@ -222,7 +222,7 @@ class ProtobufPublisher : public Publisher { * @param time timestamp; 0 indicates current NT time should be used */ void Set(const T& value, int64_t time = 0) { - wpi::SmallVector buf; + wpi::util::SmallVector buf; { std::scoped_lock lock{m_mutex}; if (!m_schemaPublished.exchange(true, std::memory_order_relaxed)) { @@ -230,7 +230,7 @@ class ProtobufPublisher : public Publisher { } m_msg.Pack(buf, value); } - ::nt::SetRaw(m_pubHandle, buf, time); + ::wpi::nt::SetRaw(m_pubHandle, buf, time); } /** @@ -241,7 +241,7 @@ class ProtobufPublisher : public Publisher { * @param value value */ void SetDefault(const T& value) { - wpi::SmallVector buf; + wpi::util::SmallVector buf; { std::scoped_lock lock{m_mutex}; if (!m_schemaPublished.exchange(true, std::memory_order_relaxed)) { @@ -249,7 +249,7 @@ class ProtobufPublisher : public Publisher { } m_msg.Pack(buf, value); } - ::nt::SetDefaultRaw(m_pubHandle, buf); + ::wpi::nt::SetDefaultRaw(m_pubHandle, buf); } /** @@ -258,12 +258,12 @@ class ProtobufPublisher : public Publisher { * @return Topic */ TopicType GetTopic() const { - return ProtobufTopic{::nt::GetTopicFromHandle(m_pubHandle)}; + return ProtobufTopic{::wpi::nt::GetTopicFromHandle(m_pubHandle)}; } private: - wpi::mutex m_mutex; - wpi::ProtobufMessage m_msg; + wpi::util::mutex m_mutex; + wpi::util::ProtobufMessage m_msg; std::atomic_bool m_schemaPublished{false}; }; @@ -272,7 +272,7 @@ class ProtobufPublisher : public Publisher { * * @note Unlike NetworkTableEntry, the entry goes away when this is destroyed. */ -template +template class ProtobufEntry final : public ProtobufSubscriber, public ProtobufPublisher { public: @@ -294,9 +294,9 @@ class ProtobufEntry final : public ProtobufSubscriber, * @param msg Protobuf message * @param defaultValue Default value */ - ProtobufEntry(NT_Entry handle, wpi::ProtobufMessage msg, T defaultValue) + ProtobufEntry(NT_Entry handle, wpi::util::ProtobufMessage msg, T defaultValue) : ProtobufSubscriber{handle, std::move(msg), std::move(defaultValue)}, - ProtobufPublisher{handle, wpi::ProtobufMessage{}} {} + ProtobufPublisher{handle, wpi::util::ProtobufMessage{}} {} /** * Determines if the native handle is valid. @@ -318,19 +318,19 @@ class ProtobufEntry final : public ProtobufSubscriber, * @return Topic */ TopicType GetTopic() const { - return ProtobufTopic{::nt::GetTopicFromHandle(this->m_subHandle)}; + return ProtobufTopic{::wpi::nt::GetTopicFromHandle(this->m_subHandle)}; } /** * Stops publishing the entry if it's published. */ - void Unpublish() { ::nt::Unpublish(this->m_pubHandle); } + void Unpublish() { ::wpi::nt::Unpublish(this->m_pubHandle); } }; /** * NetworkTables protobuf-encoded value topic. */ -template +template class ProtobufTopic final : public Topic { public: using SubscriberType = ProtobufSubscriber; @@ -375,10 +375,10 @@ class ProtobufTopic final : public Topic { [[nodiscard]] SubscriberType Subscribe( T defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { - wpi::ProtobufMessage msg; + wpi::util::ProtobufMessage msg; auto typeString = msg.GetTypeString(); return ProtobufSubscriber{ - ::nt::Subscribe(m_handle, NT_RAW, typeString, options), std::move(msg), + ::wpi::nt::Subscribe(m_handle, NT_RAW, typeString, options), std::move(msg), std::move(defaultValue)}; } @@ -399,10 +399,10 @@ class ProtobufTopic final : public Topic { */ [[nodiscard]] PublisherType Publish(const PubSubOptions& options = kDefaultPubSubOptions) { - wpi::ProtobufMessage msg; + wpi::util::ProtobufMessage msg; auto typeString = msg.GetTypeString(); return ProtobufPublisher{ - ::nt::Publish(m_handle, NT_RAW, typeString, options), std::move(msg)}; + ::wpi::nt::Publish(m_handle, NT_RAW, typeString, options), std::move(msg)}; } /** @@ -424,12 +424,12 @@ class ProtobufTopic final : public Topic { */ [[nodiscard]] PublisherType PublishEx( - const wpi::json& properties, + const wpi::util::json& properties, const PubSubOptions& options = kDefaultPubSubOptions) { - wpi::ProtobufMessage msg; + wpi::util::ProtobufMessage msg; auto typeString = msg.GetTypeString(); return ProtobufPublisher{ - ::nt::PublishEx(m_handle, NT_RAW, typeString, properties, options), + ::wpi::nt::PublishEx(m_handle, NT_RAW, typeString, properties, options), std::move(msg)}; } @@ -456,12 +456,12 @@ class ProtobufTopic final : public Topic { [[nodiscard]] EntryType GetEntry(T defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { - wpi::ProtobufMessage msg; + wpi::util::ProtobufMessage msg; auto typeString = msg.GetTypeString(); return ProtobufEntry{ - ::nt::GetEntry(m_handle, NT_RAW, typeString, options), std::move(msg), + ::wpi::nt::GetEntry(m_handle, NT_RAW, typeString, options), std::move(msg), std::move(defaultValue)}; } }; -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/main/native/include/wpi/nt/StructArrayTopic.hpp b/ntcore/src/main/native/include/wpi/nt/StructArrayTopic.hpp index 17257eea13..50e91012f2 100644 --- a/ntcore/src/main/native/include/wpi/nt/StructArrayTopic.hpp +++ b/ntcore/src/main/native/include/wpi/nt/StructArrayTopic.hpp @@ -23,19 +23,19 @@ #include "wpi/util/mutex.hpp" #include "wpi/util/struct/Struct.hpp" -namespace nt { +namespace wpi::nt { template - requires wpi::StructSerializable + requires wpi::util::StructSerializable class StructArrayTopic; /** * NetworkTables struct-encoded value array subscriber. */ template - requires wpi::StructSerializable + requires wpi::util::StructSerializable class StructArraySubscriber : public Subscriber { - using S = wpi::Struct; + using S = wpi::util::Struct; public: using TopicType = StructArrayTopic; @@ -125,9 +125,9 @@ class StructArraySubscriber : public Subscriber { std::convertible_to, T> #endif TimestampedValueType GetAtomic(U&& defaultValue) const { - wpi::SmallVector buf; + wpi::util::SmallVector buf; size_t size = std::apply(S::GetSize, m_info); - TimestampedRawView view = ::nt::GetAtomicRaw(m_subHandle, buf, {}); + TimestampedRawView view = ::wpi::nt::GetAtomicRaw(m_subHandle, buf, {}); if (view.value.size() == 0 || (view.value.size() % size) != 0) { return {0, 0, std::forward(defaultValue)}; } @@ -154,9 +154,9 @@ class StructArraySubscriber : public Subscriber { * @return timestamped value */ TimestampedValueType GetAtomic(std::span defaultValue) const { - wpi::SmallVector buf; + wpi::util::SmallVector buf; size_t size = std::apply(S::GetSize, m_info); - TimestampedRawView view = ::nt::GetAtomicRaw(m_subHandle, buf, {}); + TimestampedRawView view = ::wpi::nt::GetAtomicRaw(m_subHandle, buf, {}); if (view.value.size() == 0 || (view.value.size() % size) != 0) { return {0, 0, {defaultValue.begin(), defaultValue.end()}}; } @@ -186,7 +186,7 @@ class StructArraySubscriber : public Subscriber { * have been published since the previous call. */ std::vector ReadQueue() { - auto raw = ::nt::ReadQueueRaw(m_subHandle); + auto raw = ::wpi::nt::ReadQueueRaw(m_subHandle); std::vector rv; rv.reserve(raw.size()); size_t size = std::apply(S::GetSize, m_info); @@ -220,7 +220,7 @@ class StructArraySubscriber : public Subscriber { return std::apply( [&](const I&... info) { return StructArrayTopic{ - ::nt::GetTopicFromHandle(m_subHandle), info...}; + ::wpi::nt::GetTopicFromHandle(m_subHandle), info...}; }, m_info); } @@ -235,9 +235,9 @@ class StructArraySubscriber : public Subscriber { * NetworkTables struct-encoded value array publisher. */ template - requires wpi::StructSerializable + requires wpi::util::StructSerializable class StructArrayPublisher : public Publisher { - using S = wpi::Struct; + using S = wpi::util::Struct; public: using TopicType = StructArrayTopic; @@ -297,7 +297,7 @@ class StructArrayPublisher : public Publisher { } m_buf.Write( std::forward(value), - [&](auto bytes) { ::nt::SetRaw(m_pubHandle, bytes, time); }, + [&](auto bytes) { ::wpi::nt::SetRaw(m_pubHandle, bytes, time); }, info...); }, m_info); @@ -317,7 +317,7 @@ class StructArrayPublisher : public Publisher { } m_buf.Write( value, - [&](auto bytes) { ::nt::SetRaw(m_pubHandle, bytes, time); }, + [&](auto bytes) { ::wpi::nt::SetRaw(m_pubHandle, bytes, time); }, info...); }, m_info); @@ -343,7 +343,7 @@ class StructArrayPublisher : public Publisher { } m_buf.Write( std::forward(value), - [&](auto bytes) { ::nt::SetDefaultRaw(m_pubHandle, bytes); }, + [&](auto bytes) { ::wpi::nt::SetDefaultRaw(m_pubHandle, bytes); }, info...); }, m_info); @@ -364,7 +364,7 @@ class StructArrayPublisher : public Publisher { } m_buf.Write( value, - [&](auto bytes) { ::nt::SetDefaultRaw(m_pubHandle, bytes); }, + [&](auto bytes) { ::wpi::nt::SetDefaultRaw(m_pubHandle, bytes); }, info...); }, m_info); @@ -379,13 +379,13 @@ class StructArrayPublisher : public Publisher { return std::apply( [&](const I&... info) { return StructArrayTopic{ - ::nt::GetTopicFromHandle(m_pubHandle), info...}; + ::wpi::nt::GetTopicFromHandle(m_pubHandle), info...}; }, m_info); } private: - wpi::StructArrayBuffer m_buf; + wpi::util::StructArrayBuffer m_buf; std::atomic_bool m_schemaPublished{false}; [[no_unique_address]] std::tuple m_info; @@ -397,7 +397,7 @@ class StructArrayPublisher : public Publisher { * @note Unlike NetworkTableEntry, the entry goes away when this is destroyed. */ template - requires wpi::StructSerializable + requires wpi::util::StructSerializable class StructArrayEntry final : public StructArraySubscriber, public StructArrayPublisher { public: @@ -455,14 +455,14 @@ class StructArrayEntry final : public StructArraySubscriber, /** * Stops publishing the entry if it's published. */ - void Unpublish() { ::nt::Unpublish(this->m_pubHandle); } + void Unpublish() { ::wpi::nt::Unpublish(this->m_pubHandle); } }; /** * NetworkTables struct-encoded value array topic. */ template - requires wpi::StructSerializable + requires wpi::util::StructSerializable class StructArrayTopic final : public Topic { public: using SubscriberType = StructArraySubscriber; @@ -519,9 +519,9 @@ class StructArrayTopic final : public Topic { return std::apply( [&](const I&... info) { return StructArraySubscriber{ - ::nt::Subscribe( + ::wpi::nt::Subscribe( m_handle, NT_RAW, - wpi::MakeStructArrayTypeString( + wpi::util::MakeStructArrayTypeString( info...), options), defaultValue, info...}; @@ -551,9 +551,9 @@ class StructArrayTopic final : public Topic { return std::apply( [&](const I&... info) { return StructArraySubscriber{ - ::nt::Subscribe( + ::wpi::nt::Subscribe( m_handle, NT_RAW, - wpi::MakeStructArrayTypeString( + wpi::util::MakeStructArrayTypeString( info...), options), defaultValue, info...}; @@ -581,9 +581,9 @@ class StructArrayTopic final : public Topic { return std::apply( [&](const I&... info) { return StructArrayPublisher{ - ::nt::Publish( + ::wpi::nt::Publish( m_handle, NT_RAW, - wpi::MakeStructArrayTypeString( + wpi::util::MakeStructArrayTypeString( info...), options), info...}; @@ -610,14 +610,14 @@ class StructArrayTopic final : public Topic { */ [[nodiscard]] PublisherType PublishEx( - const wpi::json& properties, + const wpi::util::json& properties, const PubSubOptions& options = kDefaultPubSubOptions) { return std::apply( [&](const I&... info) { return StructArrayPublisher{ - ::nt::PublishEx( + ::wpi::nt::PublishEx( m_handle, NT_RAW, - wpi::MakeStructArrayTypeString( + wpi::util::MakeStructArrayTypeString( info...), properties, options), info...}; @@ -656,9 +656,9 @@ class StructArrayTopic final : public Topic { return std::apply( [&](const I&... info) { return StructArrayEntry{ - ::nt::GetEntry( + ::wpi::nt::GetEntry( m_handle, NT_RAW, - wpi::MakeStructArrayTypeString( + wpi::util::MakeStructArrayTypeString( info...), options), defaultValue, info...}; @@ -692,9 +692,9 @@ class StructArrayTopic final : public Topic { return std::apply( [&](const I&... info) { return StructArrayEntry{ - ::nt::GetEntry( + ::wpi::nt::GetEntry( m_handle, NT_RAW, - wpi::MakeStructArrayTypeString( + wpi::util::MakeStructArrayTypeString( info...), options), defaultValue, info...}; @@ -707,4 +707,4 @@ class StructArrayTopic final : public Topic { std::tuple m_info; }; -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/main/native/include/wpi/nt/StructTopic.hpp b/ntcore/src/main/native/include/wpi/nt/StructTopic.hpp index 95ea213f94..ee7d22a470 100644 --- a/ntcore/src/main/native/include/wpi/nt/StructTopic.hpp +++ b/ntcore/src/main/native/include/wpi/nt/StructTopic.hpp @@ -22,19 +22,19 @@ #include "wpi/util/json_fwd.hpp" #include "wpi/util/struct/Struct.hpp" -namespace nt { +namespace wpi::nt { template - requires wpi::StructSerializable + requires wpi::util::StructSerializable class StructTopic; /** * NetworkTables struct-encoded value subscriber. */ template - requires wpi::StructSerializable + requires wpi::util::StructSerializable class StructSubscriber : public Subscriber { - using S = wpi::Struct; + using S = wpi::util::Struct; public: using TopicType = StructTopic; @@ -87,14 +87,14 @@ class StructSubscriber : public Subscriber { * @return true if successful */ bool GetInto(T* out) { - wpi::SmallVector buf; - TimestampedRawView view = ::nt::GetAtomicRaw(m_subHandle, buf, {}); + wpi::util::SmallVector buf; + TimestampedRawView view = ::wpi::nt::GetAtomicRaw(m_subHandle, buf, {}); if (view.value.size() < std::apply(S::GetSize, m_info)) { return false; } else { std::apply( [&](const I&... info) { - wpi::UnpackStructInto(out, view.value, info...); + wpi::util::UnpackStructInto(out, view.value, info...); }, m_info); return true; @@ -119,8 +119,8 @@ class StructSubscriber : public Subscriber { * @return timestamped value */ TimestampedValueType GetAtomic(const T& defaultValue) const { - wpi::SmallVector buf; - TimestampedRawView view = ::nt::GetAtomicRaw(m_subHandle, buf, {}); + wpi::util::SmallVector buf; + TimestampedRawView view = ::wpi::nt::GetAtomicRaw(m_subHandle, buf, {}); if (view.value.size() < std::apply(S::GetSize, m_info)) { return {0, 0, defaultValue}; } else { @@ -144,7 +144,7 @@ class StructSubscriber : public Subscriber { * have been published since the previous call. */ std::vector ReadQueue() { - auto raw = ::nt::ReadQueueRaw(m_subHandle); + auto raw = ::wpi::nt::ReadQueueRaw(m_subHandle); std::vector rv; rv.reserve(raw.size()); for (auto&& r : raw) { @@ -171,7 +171,7 @@ class StructSubscriber : public Subscriber { TopicType GetTopic() const { return std::apply( [&](const I&... info) { - return StructTopic{::nt::GetTopicFromHandle(m_subHandle), + return StructTopic{::wpi::nt::GetTopicFromHandle(m_subHandle), info...}; }, m_info); @@ -187,9 +187,9 @@ class StructSubscriber : public Subscriber { * NetworkTables struct-encoded value publisher. */ template - requires wpi::StructSerializable + requires wpi::util::StructSerializable class StructPublisher : public Publisher { - using S = wpi::Struct; + using S = wpi::util::Struct; public: using TopicType = StructTopic; @@ -243,17 +243,17 @@ class StructPublisher : public Publisher { m_info); } if constexpr (sizeof...(I) == 0) { - if constexpr (wpi::is_constexpr([] { S::GetSize(); })) { + if constexpr (wpi::util::is_constexpr([] { S::GetSize(); })) { uint8_t buf[S::GetSize()]; S::Pack(buf, value); - ::nt::SetRaw(m_pubHandle, buf, time); + ::wpi::nt::SetRaw(m_pubHandle, buf, time); return; } } - wpi::SmallVector buf; + wpi::util::SmallVector buf; buf.resize_for_overwrite(std::apply(S::GetSize, m_info)); std::apply([&](const I&... info) { S::Pack(buf, value, info...); }, m_info); - ::nt::SetRaw(m_pubHandle, buf, time); + ::wpi::nt::SetRaw(m_pubHandle, buf, time); } /** @@ -272,17 +272,17 @@ class StructPublisher : public Publisher { m_info); } if constexpr (sizeof...(I) == 0) { - if constexpr (wpi::is_constexpr([] { S::GetSize(); })) { + if constexpr (wpi::util::is_constexpr([] { S::GetSize(); })) { uint8_t buf[S::GetSize()]; S::Pack(buf, value); - ::nt::SetDefaultRaw(m_pubHandle, buf); + ::wpi::nt::SetDefaultRaw(m_pubHandle, buf); return; } } - wpi::SmallVector buf; + wpi::util::SmallVector buf; buf.resize_for_overwrite(std::apply(S::GetSize, m_info)); std::apply([&](const I&... info) { S::Pack(buf, value, info...); }, m_info); - ::nt::SetDefaultRaw(m_pubHandle, buf); + ::wpi::nt::SetDefaultRaw(m_pubHandle, buf); } /** @@ -293,7 +293,7 @@ class StructPublisher : public Publisher { TopicType GetTopic() const { return std::apply( [&](const I&... info) { - return StructTopic{::nt::GetTopicFromHandle(m_pubHandle), + return StructTopic{::wpi::nt::GetTopicFromHandle(m_pubHandle), info...}; }, m_info); @@ -311,7 +311,7 @@ class StructPublisher : public Publisher { * @note Unlike NetworkTableEntry, the entry goes away when this is destroyed. */ template - requires wpi::StructSerializable + requires wpi::util::StructSerializable class StructEntry final : public StructSubscriber, public StructPublisher { public: @@ -361,14 +361,14 @@ class StructEntry final : public StructSubscriber, /** * Stops publishing the entry if it's published. */ - void Unpublish() { ::nt::Unpublish(this->m_pubHandle); } + void Unpublish() { ::wpi::nt::Unpublish(this->m_pubHandle); } }; /** * NetworkTables struct-encoded value topic. */ template - requires wpi::StructSerializable + requires wpi::util::StructSerializable class StructTopic final : public Topic { public: using SubscriberType = StructSubscriber; @@ -420,8 +420,8 @@ class StructTopic final : public Topic { return std::apply( [&](const I&... info) { return StructSubscriber{ - ::nt::Subscribe(m_handle, NT_RAW, - wpi::GetStructTypeString(info...), + ::wpi::nt::Subscribe(m_handle, NT_RAW, + wpi::util::GetStructTypeString(info...), options), std::move(defaultValue), info...}; }, @@ -448,8 +448,8 @@ class StructTopic final : public Topic { return std::apply( [&](const I&... info) { return StructPublisher{ - ::nt::Publish(m_handle, NT_RAW, - wpi::GetStructTypeString(info...), + ::wpi::nt::Publish(m_handle, NT_RAW, + wpi::util::GetStructTypeString(info...), options), info...}; }, @@ -475,13 +475,13 @@ class StructTopic final : public Topic { */ [[nodiscard]] PublisherType PublishEx( - const wpi::json& properties, + const wpi::util::json& properties, const PubSubOptions& options = kDefaultPubSubOptions) { return std::apply( [&](const I&... info) { return StructPublisher{ - ::nt::PublishEx(m_handle, NT_RAW, - wpi::GetStructTypeString(info...), + ::wpi::nt::PublishEx(m_handle, NT_RAW, + wpi::util::GetStructTypeString(info...), properties, options), info...}; }, @@ -514,8 +514,8 @@ class StructTopic final : public Topic { return std::apply( [&](const I&... info) { return StructEntry{ - ::nt::GetEntry(m_handle, NT_RAW, - wpi::GetStructTypeString(info...), + ::wpi::nt::GetEntry(m_handle, NT_RAW, + wpi::util::GetStructTypeString(info...), options), std::move(defaultValue), info...}; }, @@ -527,4 +527,4 @@ class StructTopic final : public Topic { std::tuple m_info; }; -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/main/native/include/wpi/nt/Topic.hpp b/ntcore/src/main/native/include/wpi/nt/Topic.hpp index d8dcd7cd4c..fd2055d714 100644 --- a/ntcore/src/main/native/include/wpi/nt/Topic.hpp +++ b/ntcore/src/main/native/include/wpi/nt/Topic.hpp @@ -16,7 +16,7 @@ #include "wpi/nt/ntcore_cpp.hpp" #include "wpi/util/json_fwd.hpp" -namespace nt { +namespace wpi::nt { class GenericEntry; class GenericPublisher; @@ -55,7 +55,7 @@ class Topic { * * @return the topic's name */ - std::string GetName() const { return ::nt::GetTopicName(m_handle); } + std::string GetName() const { return ::wpi::nt::GetTopicName(m_handle); } /** * Gets the type of the topic. @@ -63,7 +63,7 @@ class Topic { * @return the topic's type */ NetworkTableType GetType() const { - return static_cast(::nt::GetTopicType(m_handle)); + return static_cast(::wpi::nt::GetTopicType(m_handle)); } /** @@ -73,7 +73,7 @@ class Topic { * @return the topic's type */ std::string GetTypeString() const { - return ::nt::GetTopicTypeString(m_handle); + return ::wpi::nt::GetTopicTypeString(m_handle); } /** @@ -82,7 +82,7 @@ class Topic { * @param persistent True for persistent, false for not persistent. */ void SetPersistent(bool persistent) { - ::nt::SetTopicPersistent(m_handle, persistent); + ::wpi::nt::SetTopicPersistent(m_handle, persistent); } /** @@ -90,7 +90,7 @@ class Topic { * * @return True if the value is persistent. */ - bool IsPersistent() const { return ::nt::GetTopicPersistent(m_handle); } + bool IsPersistent() const { return ::wpi::nt::GetTopicPersistent(m_handle); } /** * Make the server retain the topic even when there are no publishers. @@ -98,7 +98,7 @@ class Topic { * @param retained True for retained, false for not retained. */ void SetRetained(bool retained) { - ::nt::SetTopicRetained(m_handle, retained); + ::wpi::nt::SetTopicRetained(m_handle, retained); } /** @@ -107,7 +107,7 @@ class Topic { * * @return True if the topic is retained. */ - bool IsRetained() const { return ::nt::GetTopicRetained(m_handle); } + bool IsRetained() const { return ::wpi::nt::GetTopicRetained(m_handle); } /** * Allow storage of the topic's last value, allowing the value to be read (and @@ -115,21 +115,21 @@ class Topic { * * @param cached True for cached, false for not cached. */ - void SetCached(bool cached) { ::nt::SetTopicCached(m_handle, cached); } + void SetCached(bool cached) { ::wpi::nt::SetTopicCached(m_handle, cached); } /** * Returns whether the topic's last value is stored. * * @return True if the topic is cached. */ - bool IsCached() const { return ::nt::GetTopicCached(m_handle); } + bool IsCached() const { return ::wpi::nt::GetTopicCached(m_handle); } /** * Determines if the topic is currently being published. * * @return True if the topic exists, false otherwise. */ - bool Exists() const { return nt::GetTopicExists(m_handle); } + bool Exists() const { return wpi::nt::GetTopicExists(m_handle); } /** * Gets the current value of a property (as a JSON object). @@ -137,7 +137,7 @@ class Topic { * @param name property name * @return JSON object; null object if the property does not exist. */ - wpi::json GetProperty(std::string_view name) const; + wpi::util::json GetProperty(std::string_view name) const; /** * Sets a property value. @@ -145,7 +145,7 @@ class Topic { * @param name property name * @param value property value */ - void SetProperty(std::string_view name, const wpi::json& value); + void SetProperty(std::string_view name, const wpi::util::json& value); /** * Deletes a property. Has no effect if the property does not exist. @@ -153,7 +153,7 @@ class Topic { * @param name property name */ void DeleteProperty(std::string_view name) { - ::nt::DeleteTopicProperty(m_handle, name); + ::wpi::nt::DeleteTopicProperty(m_handle, name); } /** @@ -162,7 +162,7 @@ class Topic { * * @return JSON object */ - wpi::json GetProperties() const; + wpi::util::json GetProperties() const; /** * Updates multiple topic properties. Each key in the passed-in object is @@ -173,8 +173,8 @@ class Topic { * @param properties JSON object with keys to add/update/delete * @return False if properties is not an object */ - bool SetProperties(const wpi::json& properties) { - return ::nt::SetTopicProperties(m_handle, properties); + bool SetProperties(const wpi::util::json& properties) { + return ::wpi::nt::SetTopicProperties(m_handle, properties); } /** @@ -182,7 +182,7 @@ class Topic { * * @return Topic information */ - TopicInfo GetInfo() const { return ::nt::GetTopicInfo(m_handle); } + TopicInfo GetInfo() const { return ::wpi::nt::GetTopicInfo(m_handle); } /** * Create a new subscriber to the topic. @@ -257,7 +257,7 @@ class Topic { */ [[nodiscard]] GenericPublisher GenericPublishEx( - std::string_view typeString, const wpi::json& properties, + std::string_view typeString, const wpi::util::json& properties, const PubSubOptions& options = kDefaultPubSubOptions); /** @@ -319,7 +319,7 @@ class Topic { /** NetworkTables subscriber. */ class Subscriber { public: - virtual ~Subscriber() { ::nt::Release(m_subHandle); } + virtual ~Subscriber() { ::wpi::nt::Release(m_subHandle); } Subscriber(const Subscriber&) = delete; Subscriber& operator=(const Subscriber&) = delete; @@ -330,7 +330,7 @@ class Subscriber { Subscriber& operator=(Subscriber&& rhs) { if (m_subHandle != 0) { - ::nt::Release(m_subHandle); + ::wpi::nt::Release(m_subHandle); } m_subHandle = rhs.m_subHandle; rhs.m_subHandle = 0; @@ -356,7 +356,7 @@ class Subscriber { * * @return True if the topic exists, false otherwise. */ - bool Exists() const { return nt::GetTopicExists(m_subHandle); } + bool Exists() const { return wpi::nt::GetTopicExists(m_subHandle); } /** * Gets the last time the value was changed. @@ -366,7 +366,7 @@ class Subscriber { * @return Topic last change time */ int64_t GetLastChange() const { - return ::nt::GetEntryLastChange(m_subHandle); + return ::wpi::nt::GetEntryLastChange(m_subHandle); } /** @@ -375,7 +375,7 @@ class Subscriber { * @return Topic */ Topic GetTopic() const { - return Topic{::nt::GetTopicFromHandle(m_subHandle)}; + return Topic{::wpi::nt::GetTopicFromHandle(m_subHandle)}; } protected: @@ -391,7 +391,7 @@ class Subscriber { /** NetworkTables publisher. */ class Publisher { public: - virtual ~Publisher() { ::nt::Release(m_pubHandle); } + virtual ~Publisher() { ::wpi::nt::Release(m_pubHandle); } Publisher(const Publisher&) = delete; Publisher& operator=(const Publisher&) = delete; @@ -402,7 +402,7 @@ class Publisher { Publisher& operator=(Publisher&& rhs) { if (m_pubHandle != 0) { - ::nt::Release(m_pubHandle); + ::wpi::nt::Release(m_pubHandle); } m_pubHandle = rhs.m_pubHandle; rhs.m_pubHandle = 0; @@ -429,7 +429,7 @@ class Publisher { * @return Topic */ Topic GetTopic() const { - return Topic{::nt::GetTopicFromHandle(m_pubHandle)}; + return Topic{::wpi::nt::GetTopicFromHandle(m_pubHandle)}; } protected: @@ -443,4 +443,4 @@ class Publisher { void anchor(); }; -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/main/native/include/wpi/nt/UnitTopic.hpp b/ntcore/src/main/native/include/wpi/nt/UnitTopic.hpp index 1ed11525b0..cc9d99acea 100644 --- a/ntcore/src/main/native/include/wpi/nt/UnitTopic.hpp +++ b/ntcore/src/main/native/include/wpi/nt/UnitTopic.hpp @@ -13,7 +13,7 @@ #include "wpi/nt/ntcore_cpp.hpp" #include "wpi/util/json.hpp" -namespace nt { +namespace wpi::nt { template class UnitTopic; @@ -21,7 +21,7 @@ class UnitTopic; /** * Timestamped unit. * - * @tparam T unit type, e.g. units::meter_t + * @tparam T unit type, e.g. wpi::units::meter_t */ template struct TimestampedUnit { @@ -48,7 +48,7 @@ struct TimestampedUnit { /** * NetworkTables unit-typed subscriber. * - * @tparam T unit type, e.g. units::meter_t + * @tparam T unit type, e.g. wpi::units::meter_t */ template class UnitSubscriber : public Subscriber { @@ -86,7 +86,7 @@ class UnitSubscriber : public Subscriber { * @return value */ ValueType Get(ParamType defaultValue) const { - return T{::nt::GetDouble(m_subHandle, defaultValue.value())}; + return T{::wpi::nt::GetDouble(m_subHandle, defaultValue.value())}; } /** @@ -107,7 +107,7 @@ class UnitSubscriber : public Subscriber { * @return timestamped value */ TimestampedValueType GetAtomic(ParamType defaultValue) const { - auto doubleVal = ::nt::GetAtomicDouble(m_subHandle, defaultValue.value()); + auto doubleVal = ::wpi::nt::GetAtomicDouble(m_subHandle, defaultValue.value()); return {doubleVal.time, doubleVal.serverTime, doubleVal.value}; } @@ -123,7 +123,7 @@ class UnitSubscriber : public Subscriber { */ std::vector ReadQueue() { std::vector> vals; - auto doubleVals = ::nt::ReadQueueDouble(m_subHandle); + auto doubleVals = ::wpi::nt::ReadQueueDouble(m_subHandle); vals.reserve(doubleVals.size()); for (auto&& val : doubleVals) { vals.emplace_back(val.time, val.serverTime, val.value); @@ -136,7 +136,7 @@ class UnitSubscriber : public Subscriber { * @return Topic */ TopicType GetTopic() const { - return UnitTopic{::nt::GetTopicFromHandle(m_subHandle)}; + return UnitTopic{::wpi::nt::GetTopicFromHandle(m_subHandle)}; } private: @@ -146,7 +146,7 @@ class UnitSubscriber : public Subscriber { /** * NetworkTables unit-typed publisher. * - * @tparam T unit type, e.g. units::meter_t + * @tparam T unit type, e.g. wpi::units::meter_t */ template class UnitPublisher : public Publisher { @@ -174,7 +174,7 @@ class UnitPublisher : public Publisher { * @param time timestamp; 0 indicates current NT time should be used */ void Set(ParamType value, int64_t time = 0) { - ::nt::SetDouble(m_pubHandle, value.value(), time); + ::wpi::nt::SetDouble(m_pubHandle, value.value(), time); } /** @@ -185,7 +185,7 @@ class UnitPublisher : public Publisher { * @param value value */ void SetDefault(ParamType value) { - ::nt::SetDefaultDouble(m_pubHandle, value.value()); + ::wpi::nt::SetDefaultDouble(m_pubHandle, value.value()); } /** @@ -194,7 +194,7 @@ class UnitPublisher : public Publisher { * @return Topic */ TopicType GetTopic() const { - return UnitTopic{::nt::GetTopicFromHandle(m_pubHandle)}; + return UnitTopic{::wpi::nt::GetTopicFromHandle(m_pubHandle)}; } }; @@ -203,7 +203,7 @@ class UnitPublisher : public Publisher { * * @note Unlike NetworkTableEntry, the entry goes away when this is destroyed. * - * @tparam T unit type, e.g. units::meter_t + * @tparam T unit type, e.g. wpi::units::meter_t */ template class UnitEntry final : public UnitSubscriber, public UnitPublisher { @@ -248,13 +248,13 @@ class UnitEntry final : public UnitSubscriber, public UnitPublisher { * @return Topic */ TopicType GetTopic() const { - return UnitTopic{::nt::GetTopicFromHandle(this->m_subHandle)}; + return UnitTopic{::wpi::nt::GetTopicFromHandle(this->m_subHandle)}; } /** * Stops publishing the entry if it's published. */ - void Unpublish() { ::nt::Unpublish(this->m_pubHandle); } + void Unpublish() { ::wpi::nt::Unpublish(this->m_pubHandle); } }; /** @@ -263,7 +263,7 @@ class UnitEntry final : public UnitSubscriber, public UnitPublisher { * correct behavior the publisher and subscriber must use the same unit type, * but this can be checked at runtime using IsMatchingUnit(). * - * @tparam T unit type, e.g. units::meter_t + * @tparam T unit type, e.g. wpi::units::meter_t */ template class UnitTopic final : public Topic { @@ -320,7 +320,7 @@ class UnitTopic final : public Topic { ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return UnitSubscriber{ - ::nt::Subscribe(m_handle, NT_DOUBLE, "double", options), defaultValue}; + ::wpi::nt::Subscribe(m_handle, NT_DOUBLE, "double", options), defaultValue}; } /** @@ -344,7 +344,7 @@ class UnitTopic final : public Topic { std::string_view typeString, ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return UnitSubscriber{ - ::nt::Subscribe(m_handle, NT_DOUBLE, typeString, options), + ::wpi::nt::Subscribe(m_handle, NT_DOUBLE, typeString, options), defaultValue}; } @@ -365,7 +365,7 @@ class UnitTopic final : public Topic { */ [[nodiscard]] PublisherType Publish(const PubSubOptions& options = kDefaultPubSubOptions) { - return UnitPublisher{::nt::PublishEx(m_handle, NT_DOUBLE, "double", + return UnitPublisher{::wpi::nt::PublishEx(m_handle, NT_DOUBLE, "double", {{"unit", T{}.name()}}, options)}; } @@ -389,12 +389,12 @@ class UnitTopic final : public Topic { */ [[nodiscard]] PublisherType PublishEx( - std::string_view typeString, const wpi::json& properties, + std::string_view typeString, const wpi::util::json& properties, const PubSubOptions& options = kDefaultPubSubOptions) { - wpi::json props = properties; + wpi::util::json props = properties; props["unit"] = T{}.name(); return UnitPublisher{ - ::nt::PublishEx(m_handle, NT_DOUBLE, typeString, props, options)}; + ::wpi::nt::PublishEx(m_handle, NT_DOUBLE, typeString, props, options)}; } /** @@ -420,7 +420,7 @@ class UnitTopic final : public Topic { [[nodiscard]] EntryType GetEntry(ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { - return UnitEntry{::nt::GetEntry(m_handle, NT_DOUBLE, "double", options), + return UnitEntry{::wpi::nt::GetEntry(m_handle, NT_DOUBLE, "double", options), defaultValue}; } @@ -449,8 +449,8 @@ class UnitTopic final : public Topic { EntryType GetEntryEx(std::string_view typeString, ParamType defaultValue, const PubSubOptions& options = kDefaultPubSubOptions) { return UnitEntry{ - ::nt::GetEntry(m_handle, NT_DOUBLE, typeString, options), defaultValue}; + ::wpi::nt::GetEntry(m_handle, NT_DOUBLE, typeString, options), defaultValue}; } }; -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/main/native/include/wpi/nt/ntcore_c.h b/ntcore/src/main/native/include/wpi/nt/ntcore_c.h index ad77fa76c7..75794081bd 100644 --- a/ntcore/src/main/native/include/wpi/nt/ntcore_c.h +++ b/ntcore/src/main/native/include/wpi/nt/ntcore_c.h @@ -198,7 +198,7 @@ struct NT_ConnectionInfo { /** * The last time any update was received from the remote node (same scale as - * returned by nt::Now()). + * returned by wpi::nt::Now()). */ uint64_t last_update; @@ -1364,7 +1364,7 @@ void NT_SetNow(int64_t timestamp); /** @} */ /** - * @defgroup ntcore_data_logger_cfunc Data Logger Functions + * @defgroup ntcore_data_logger_cfunc Data wpi::util::Logger Functions * @{ */ @@ -1412,7 +1412,7 @@ void NT_StopConnectionDataLog(NT_ConnectionDataLogger logger); /** @} */ /** - * @defgroup ntcore_logger_cfunc Logger Functions + * @defgroup ntcore_logger_cfunc wpi::util::Logger Functions * @{ */ diff --git a/ntcore/src/main/native/include/wpi/nt/ntcore_cpp.hpp b/ntcore/src/main/native/include/wpi/nt/ntcore_cpp.hpp index 86ff330694..64b3d6ac82 100644 --- a/ntcore/src/main/native/include/wpi/nt/ntcore_cpp.hpp +++ b/ntcore/src/main/native/include/wpi/nt/ntcore_cpp.hpp @@ -22,7 +22,7 @@ #include "wpi/nt/ntcore_cpp_types.hpp" #include "wpi/util/json_fwd.hpp" -namespace wpi { +namespace wpi::util { template class SmallVectorImpl; } // namespace wpi @@ -32,7 +32,7 @@ class DataLog; } // namespace wpi::log /** NetworkTables (ntcore) namespace */ -namespace nt { +namespace wpi::nt { /** * @defgroup ntcore_cpp_handle_api ntcore C++ API @@ -103,7 +103,7 @@ struct TopicInfo { std::string properties; /** Get topic properties as a JSON object. */ - wpi::json GetProperties() const; + wpi::util::json GetProperties() const; friend void swap(TopicInfo& first, TopicInfo& second) { using std::swap; @@ -119,7 +119,7 @@ struct TopicInfo { struct ConnectionInfo { /** * The remote identifier (as set on the remote node by - * NetworkTableInstance::StartClient() or nt::StartClient()). + * NetworkTableInstance::StartClient() or wpi::nt::StartClient()). */ std::string remote_id; @@ -131,7 +131,7 @@ struct ConnectionInfo { /** * The last time any update was received from the remote node (same scale as - * returned by nt::Now()). + * returned by wpi::nt::Now()). */ int64_t last_update{0}; @@ -733,7 +733,7 @@ bool GetTopicExists(NT_Handle handle); * @param name property name * @return JSON object; null object if the property does not exist. */ -wpi::json GetTopicProperty(NT_Topic topic, std::string_view name); +wpi::util::json GetTopicProperty(NT_Topic topic, std::string_view name); /** * Sets a property value. @@ -743,7 +743,7 @@ wpi::json GetTopicProperty(NT_Topic topic, std::string_view name); * @param value property value */ void SetTopicProperty(NT_Topic topic, std::string_view name, - const wpi::json& value); + const wpi::util::json& value); /** * Deletes a property. Has no effect if the property does not exist. @@ -760,7 +760,7 @@ void DeleteTopicProperty(NT_Topic topic, std::string_view name); * @param topic topic handle * @return JSON object */ -wpi::json GetTopicProperties(NT_Topic topic); +wpi::util::json GetTopicProperties(NT_Topic topic); /** * Updates multiple topic properties. Each key in the passed-in object is @@ -772,7 +772,7 @@ wpi::json GetTopicProperties(NT_Topic topic); * @param update JSON object with keys to add/update/delete * @return False if update is not a JSON object */ -bool SetTopicProperties(NT_Topic topic, const wpi::json& update); +bool SetTopicProperties(NT_Topic topic, const wpi::util::json& update); /** * Creates a new subscriber to value changes on a topic. @@ -816,7 +816,7 @@ NT_Publisher Publish(NT_Topic topic, NT_Type type, std::string_view typeStr, * @return Publisher handle */ NT_Publisher PublishEx(NT_Topic topic, NT_Type type, std::string_view typeStr, - const wpi::json& properties, + const wpi::util::json& properties, const PubSubOptions& options = kDefaultPubSubOptions); /** @@ -1207,7 +1207,7 @@ std::optional GetServerTimeOffset(NT_Inst inst); /** * Returns monotonic current time in 1 us increments. * This is the same time base used for value and connection timestamps. - * This function by default simply wraps wpi::Now(), but if SetNow() is + * This function by default simply wraps wpi::util::Now(), but if SetNow() is * called, this function instead returns the value passed to SetNow(); * this can be used to reduce overhead. * @@ -1219,8 +1219,8 @@ int64_t Now(); * Sets the current timestamp used for timestamping values that do not * provide a timestamp (e.g. a value of 0 is passed). For consistency, * it also results in Now() returning the set value. This should generally - * be used only if the overhead of calling wpi::Now() is a concern. - * If used, it should be called periodically with the value of wpi::Now(). + * be used only if the overhead of calling wpi::util::Now() is a concern. + * If used, it should be called periodically with the value of wpi::util::Now(). * * @param timestamp timestamp (1 us increments) */ @@ -1245,7 +1245,7 @@ std::string_view GetStringFromType(NT_Type type); /** @} */ /** - * @defgroup ntcore_data_logger_func Data Logger Functions + * @defgroup ntcore_data_logger_func Data wpi::util::Logger Functions * @{ */ @@ -1294,7 +1294,7 @@ void StopConnectionDataLog(NT_ConnectionDataLogger logger); /** @} */ /** - * @defgroup ntcore_logger_func Logger Functions + * @defgroup ntcore_logger_func wpi::util::Logger Functions * @{ */ @@ -1322,7 +1322,7 @@ NT_Listener AddLogger(NT_Inst inst, unsigned int min_level, * @param poller poller handle * @param min_level minimum log level * @param max_level maximum log level - * @return Logger handle + * @return wpi::util::Logger handle */ NT_Listener AddPolledLogger(NT_ListenerPoller poller, unsigned int min_level, unsigned int max_level); @@ -1505,4 +1505,4 @@ std::optional> DecodeClients(std::span data); /** @} */ } // namespace meta -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/main/python/ntcore/src/NetworkTable.cpp.inl b/ntcore/src/main/python/ntcore/src/NetworkTable.cpp.inl index 1c127232e1..0d9ff95d19 100644 --- a/ntcore/src/main/python/ntcore/src/NetworkTable.cpp.inl +++ b/ntcore/src/main/python/ntcore/src/NetworkTable.cpp.inl @@ -1,6 +1,6 @@ cls_NetworkTable .def("getValue", [](const NetworkTable &self, std::string_view key, py::object defaultValue) -> py::object { - nt::NetworkTableEntry entry; + wpi::nt::NetworkTableEntry entry; { py::gil_scoped_release release; entry = self.GetEntry(key); @@ -9,48 +9,48 @@ cls_NetworkTable }, py::arg("key"), py::arg("value")) // double overload must come before boolean version - .def("putValue", [](nt::NetworkTable *self, std::string_view key, double value) { - return self->PutValue(key, nt::Value::MakeDouble(value)); + .def("putValue", [](wpi::nt::NetworkTable *self, std::string_view key, double value) { + return self->PutValue(key, wpi::nt::Value::MakeDouble(value)); }, py::arg("key"), py::arg("value"), release_gil()) - .def("putValue", [](nt::NetworkTable *self, std::string_view key, bool value) { - return self->PutValue(key, nt::Value::MakeBoolean(value)); + .def("putValue", [](wpi::nt::NetworkTable *self, std::string_view key, bool value) { + return self->PutValue(key, wpi::nt::Value::MakeBoolean(value)); }, py::arg("key"), py::arg("value"), release_gil()) - .def("putValue", [](nt::NetworkTable *self, std::string_view key, py::bytes value) { - auto v = nt::Value::MakeRaw(value.cast>()); + .def("putValue", [](wpi::nt::NetworkTable *self, std::string_view key, py::bytes value) { + auto v = wpi::nt::Value::MakeRaw(value.cast>()); py::gil_scoped_release release; return self->PutValue(key, v); }, py::arg("key"), py::arg("value")) - .def("putValue", [](nt::NetworkTable *self, std::string_view key, std::string value) { - return self->PutValue(key, nt::Value::MakeString(std::move(value))); + .def("putValue", [](wpi::nt::NetworkTable *self, std::string_view key, std::string value) { + return self->PutValue(key, wpi::nt::Value::MakeString(std::move(value))); }, py::arg("key"), py::arg("value"), release_gil()) - .def("putValue", [](nt::NetworkTable *self, std::string_view key, py::sequence value) { + .def("putValue", [](wpi::nt::NetworkTable *self, std::string_view key, py::sequence value) { auto v = pyntcore::py2ntvalue(value); py::gil_scoped_release release; return self->PutValue(key, v); }, py::arg("key"), py::arg("value")) // double overload must come before boolean version - .def("setDefaultValue", [](nt::NetworkTable *self, std::string_view key, double value) { - return self->SetDefaultValue(key, nt::Value::MakeDouble(value)); + .def("setDefaultValue", [](wpi::nt::NetworkTable *self, std::string_view key, double value) { + return self->SetDefaultValue(key, wpi::nt::Value::MakeDouble(value)); }, py::arg("key"), py::arg("value"), release_gil()) - .def("setDefaultValue", [](nt::NetworkTable *self, std::string_view key, bool value) { - return self->SetDefaultValue(key, nt::Value::MakeBoolean(value)); + .def("setDefaultValue", [](wpi::nt::NetworkTable *self, std::string_view key, bool value) { + return self->SetDefaultValue(key, wpi::nt::Value::MakeBoolean(value)); }, py::arg("key"), py::arg("value"), release_gil()) - .def("setDefaultValue", [](nt::NetworkTable *self, std::string_view key, py::bytes value) { - auto v = nt::Value::MakeRaw(value.cast>()); + .def("setDefaultValue", [](wpi::nt::NetworkTable *self, std::string_view key, py::bytes value) { + auto v = wpi::nt::Value::MakeRaw(value.cast>()); py::gil_scoped_release release; return self->SetDefaultValue(key, v); }, py::arg("key"), py::arg("value")) - .def("setDefaultValue", [](nt::NetworkTable *self, std::string_view key, std::string value) { - return self->SetDefaultValue(key, nt::Value::MakeString(std::move(value))); + .def("setDefaultValue", [](wpi::nt::NetworkTable *self, std::string_view key, std::string value) { + return self->SetDefaultValue(key, wpi::nt::Value::MakeString(std::move(value))); }, py::arg("key"), py::arg("value"), release_gil()) - .def("setDefaultValue", [](nt::NetworkTable *self, std::string_view key, py::sequence value) { + .def("setDefaultValue", [](wpi::nt::NetworkTable *self, std::string_view key, py::sequence value) { auto v = pyntcore::py2ntvalue(value); py::gil_scoped_release release; return self->SetDefaultValue(key, v); }, py::arg("key"), py::arg("value")) - .def("__contains__", [](const nt::NetworkTable &self, std::string_view key) -> bool { + .def("__contains__", [](const wpi::nt::NetworkTable &self, std::string_view key) -> bool { return self.ContainsKey(key); }, release_gil()) ; diff --git a/ntcore/src/main/python/ntcore/src/NetworkTableEntry.cpp.inl b/ntcore/src/main/python/ntcore/src/NetworkTableEntry.cpp.inl index a0e0e60a0e..12ab7ab4f1 100644 --- a/ntcore/src/main/python/ntcore/src/NetworkTableEntry.cpp.inl +++ b/ntcore/src/main/python/ntcore/src/NetworkTableEntry.cpp.inl @@ -1,6 +1,6 @@ cls_NetworkTableEntry - .def_property_readonly("value", [](const nt::NetworkTableEntry &self) { - nt::Value v; + .def_property_readonly("value", [](const wpi::nt::NetworkTableEntry &self) { + wpi::nt::Value v; { py::gil_scoped_release release; v = self.GetValue(); @@ -9,40 +9,40 @@ cls_NetworkTableEntry }) // double overload must come before boolean version - .def("setValue", [](nt::NetworkTableEntry *self, double value) { - return self->SetValue(nt::Value::MakeDouble(value)); + .def("setValue", [](wpi::nt::NetworkTableEntry *self, double value) { + return self->SetValue(wpi::nt::Value::MakeDouble(value)); }, py::arg("value"), release_gil()) - .def("setValue", [](nt::NetworkTableEntry *self, bool value) { - return self->SetValue(nt::Value::MakeBoolean(value)); + .def("setValue", [](wpi::nt::NetworkTableEntry *self, bool value) { + return self->SetValue(wpi::nt::Value::MakeBoolean(value)); }, py::arg("value"), release_gil()) - .def("setValue", [](nt::NetworkTableEntry *self, py::bytes value) { - auto v = nt::Value::MakeRaw(value.cast>()); + .def("setValue", [](wpi::nt::NetworkTableEntry *self, py::bytes value) { + auto v = wpi::nt::Value::MakeRaw(value.cast>()); py::gil_scoped_release release; return self->SetValue(v); }, py::arg("value")) - .def("setValue", [](nt::NetworkTableEntry *self, std::string value) { - return self->SetValue(nt::Value::MakeString(value)); + .def("setValue", [](wpi::nt::NetworkTableEntry *self, std::string value) { + return self->SetValue(wpi::nt::Value::MakeString(value)); }, py::arg("value"), release_gil()) - .def("setValue", [](nt::NetworkTableEntry *self, py::sequence value) { + .def("setValue", [](wpi::nt::NetworkTableEntry *self, py::sequence value) { return self->SetValue(pyntcore::py2ntvalue(value)); }, py::arg("value")) // double overload must come before boolean version - .def("setDefaultValue", [](nt::NetworkTableEntry *self, double value) { - return self->SetDefaultValue(nt::Value::MakeDouble(value)); + .def("setDefaultValue", [](wpi::nt::NetworkTableEntry *self, double value) { + return self->SetDefaultValue(wpi::nt::Value::MakeDouble(value)); }, py::arg("value"), release_gil()) - .def("setDefaultValue", [](nt::NetworkTableEntry *self, bool value) { - return self->SetDefaultValue(nt::Value::MakeBoolean(value)); + .def("setDefaultValue", [](wpi::nt::NetworkTableEntry *self, bool value) { + return self->SetDefaultValue(wpi::nt::Value::MakeBoolean(value)); }, py::arg("value"), release_gil()) - .def("setDefaultValue", [](nt::NetworkTableEntry *self, py::bytes value) { - auto v = nt::Value::MakeRaw(value.cast>()); + .def("setDefaultValue", [](wpi::nt::NetworkTableEntry *self, py::bytes value) { + auto v = wpi::nt::Value::MakeRaw(value.cast>()); py::gil_scoped_release release; return self->SetDefaultValue(v); }, py::arg("value")) - .def("setDefaultValue", [](nt::NetworkTableEntry *self, std::string value) { - return self->SetDefaultValue(nt::Value::MakeString(value)); + .def("setDefaultValue", [](wpi::nt::NetworkTableEntry *self, std::string value) { + return self->SetDefaultValue(wpi::nt::Value::MakeString(value)); }, py::arg("value"), release_gil()) - .def("setDefaultValue", [](nt::NetworkTableEntry *self, py::sequence value) { + .def("setDefaultValue", [](wpi::nt::NetworkTableEntry *self, py::sequence value) { return self->SetDefaultValue(pyntcore::py2ntvalue(value)); }, py::arg("value")) ; diff --git a/ntcore/src/main/python/ntcore/src/nt_instance.cpp b/ntcore/src/main/python/ntcore/src/nt_instance.cpp index f42cfd40a7..27eddf868c 100644 --- a/ntcore/src/main/python/ntcore/src/nt_instance.cpp +++ b/ntcore/src/main/python/ntcore/src/nt_instance.cpp @@ -9,24 +9,24 @@ static std::set g_known_instances; namespace pyntcore { -void onInstanceStart(nt::NetworkTableInstance *instance) { +void onInstanceStart(wpi::nt::NetworkTableInstance *instance) { g_known_instances.emplace(instance->GetHandle()); py::module::import("ntcore._logutil") .attr("NtLogForwarder").attr("onInstanceStart")(instance); } -void onInstancePreReset(nt::NetworkTableInstance *instance) { +void onInstancePreReset(wpi::nt::NetworkTableInstance *instance) { py::module::import("ntcore._logutil") .attr("NtLogForwarder").attr("onInstanceDestroy")(instance); } -void onInstancePostReset(nt::NetworkTableInstance *instance) { +void onInstancePostReset(wpi::nt::NetworkTableInstance *instance) { py::module::import("ntcore.util") .attr("_NtProperty").attr("onInstancePostReset")(instance); } -void onInstanceDestroy(nt::NetworkTableInstance *instance) { +void onInstanceDestroy(wpi::nt::NetworkTableInstance *instance) { py::module::import("ntcore._logutil") .attr("NtLogForwarder").attr("onInstanceDestroy")(instance); py::module::import("ntcore.util") @@ -43,12 +43,12 @@ void resetAllInstances() known_instances.swap(g_known_instances); // always reset the default instance - known_instances.emplace(nt::GetDefaultInstance()); + known_instances.emplace(wpi::nt::GetDefaultInstance()); py::gil_scoped_release unlock; for (auto &inst: known_instances) { - nt::ResetInstance(inst); + wpi::nt::ResetInstance(inst); } } diff --git a/ntcore/src/main/python/ntcore/src/nt_instance.h b/ntcore/src/main/python/ntcore/src/nt_instance.h index 7f93a8b625..087d9b2e21 100644 --- a/ntcore/src/main/python/ntcore/src/nt_instance.h +++ b/ntcore/src/main/python/ntcore/src/nt_instance.h @@ -6,10 +6,10 @@ namespace pyntcore { -void onInstanceStart(nt::NetworkTableInstance *instance); -void onInstancePreReset(nt::NetworkTableInstance *instance); -void onInstancePostReset(nt::NetworkTableInstance *instance); -void onInstanceDestroy(nt::NetworkTableInstance *instance); +void onInstanceStart(wpi::nt::NetworkTableInstance *instance); +void onInstancePreReset(wpi::nt::NetworkTableInstance *instance); +void onInstancePostReset(wpi::nt::NetworkTableInstance *instance); +void onInstanceDestroy(wpi::nt::NetworkTableInstance *instance); void resetAllInstances(); diff --git a/ntcore/src/main/python/ntcore/src/py2value.cpp b/ntcore/src/main/python/ntcore/src/py2value.cpp index 0634c40f6f..1dcb4a4bdf 100644 --- a/ntcore/src/main/python/ntcore/src/py2value.cpp +++ b/ntcore/src/main/python/ntcore/src/py2value.cpp @@ -41,7 +41,7 @@ const char * nttype2str(NT_Type type) { } -py::object ntvalue2py(const nt::Value &ntvalue) { +py::object ntvalue2py(const wpi::nt::Value &ntvalue) { auto &v = ntvalue.value(); switch (v.type) { case NT_BOOLEAN: @@ -109,17 +109,17 @@ py::object ntvalue2py(const nt::Value &ntvalue) { } } -nt::Value py2ntvalue(py::handle h) { +wpi::nt::Value py2ntvalue(py::handle h) { if (py::isinstance(h)) { - return nt::Value::MakeBoolean(h.cast()); + return wpi::nt::Value::MakeBoolean(h.cast()); } else if (py::isinstance(h)) { - return nt::Value::MakeDouble(h.cast()); + return wpi::nt::Value::MakeDouble(h.cast()); } else if (py::isinstance(h)) { - return nt::Value::MakeInteger(h.cast()); + return wpi::nt::Value::MakeInteger(h.cast()); } else if (py::isinstance(h)) { - return nt::Value::MakeString(h.cast()); + return wpi::nt::Value::MakeString(h.cast()); } else if (py::isinstance(h)) { - return nt::Value::MakeRaw(h.cast>()); + return wpi::nt::Value::MakeRaw(h.cast>()); } else if (py::isinstance(h)) { throw py::value_error("Cannot put None into NetworkTable"); } @@ -132,45 +132,45 @@ nt::Value py2ntvalue(py::handle h) { auto i1 = seq[0]; if (py::isinstance(i1)) { auto v = h.cast>(); - return nt::Value::MakeBooleanArray(v); + return wpi::nt::Value::MakeBooleanArray(v); } else if (py::isinstance(i1)) { auto v = h.cast>(); - return nt::Value::MakeDoubleArray(v); + return wpi::nt::Value::MakeDoubleArray(v); } else if (py::isinstance(i1)) { auto v = h.cast>(); - return nt::Value::MakeIntegerArray(v); + return wpi::nt::Value::MakeIntegerArray(v); } else if (py::isinstance(i1)) { auto v = h.cast>(); - return nt::Value::MakeStringArray(v); + return wpi::nt::Value::MakeStringArray(v); } else { throw py::value_error("Can only put bool/int/float/str/bytes or lists/tuples of them"); } } -py::function valueFactoryByType(nt::NetworkTableType type) { +py::function valueFactoryByType(wpi::nt::NetworkTableType type) { py::object PyNtValue = py::module::import("ntcore").attr("Value"); switch (type) { - case nt::NetworkTableType::kBoolean: + case wpi::nt::NetworkTableType::kBoolean: return PyNtValue.attr("makeBoolean"); - case nt::NetworkTableType::kDouble: + case wpi::nt::NetworkTableType::kDouble: return PyNtValue.attr("makeDouble"); - case nt::NetworkTableType::kString: + case wpi::nt::NetworkTableType::kString: return PyNtValue.attr("makeString"); - case nt::NetworkTableType::kRaw: + case wpi::nt::NetworkTableType::kRaw: return PyNtValue.attr("makeRaw"); - case nt::NetworkTableType::kBooleanArray: + case wpi::nt::NetworkTableType::kBooleanArray: return PyNtValue.attr("makeBooleanArray"); - case nt::NetworkTableType::kDoubleArray: + case wpi::nt::NetworkTableType::kDoubleArray: return PyNtValue.attr("makeDoubleArray"); - case nt::NetworkTableType::kStringArray: + case wpi::nt::NetworkTableType::kStringArray: return PyNtValue.attr("makeStringArray"); - case nt::NetworkTableType::kInteger: + case wpi::nt::NetworkTableType::kInteger: return PyNtValue.attr("makeInteger"); - case nt::NetworkTableType::kFloat: + case wpi::nt::NetworkTableType::kFloat: return PyNtValue.attr("makeFloat"); - case nt::NetworkTableType::kIntegerArray: + case wpi::nt::NetworkTableType::kIntegerArray: return PyNtValue.attr("makeIntegerArray"); - case nt::NetworkTableType::kFloatArray: + case wpi::nt::NetworkTableType::kFloatArray: return PyNtValue.attr("makeFloatArray"); default: throw py::type_error("empty nt value"); diff --git a/ntcore/src/main/python/ntcore/src/py2value.h b/ntcore/src/main/python/ntcore/src/py2value.h index 7858cb5e05..53f144c730 100644 --- a/ntcore/src/main/python/ntcore/src/py2value.h +++ b/ntcore/src/main/python/ntcore/src/py2value.h @@ -8,13 +8,13 @@ namespace pyntcore { const char * nttype2str(NT_Type type); -py::object ntvalue2py(const nt::Value &ntvalue); +py::object ntvalue2py(const wpi::nt::Value &ntvalue); -nt::Value py2ntvalue(py::handle h); +wpi::nt::Value py2ntvalue(py::handle h); -py::function valueFactoryByType(nt::NetworkTableType type); +py::function valueFactoryByType(wpi::nt::NetworkTableType type); -inline void ensure_value_is(NT_Type expected, nt::Value *v) { +inline void ensure_value_is(NT_Type expected, wpi::nt::Value *v) { if (v->type() != expected) { throw py::value_error(fmt::format( "Value type is {}, not {}", nttype2str(v->type()), nttype2str(expected) diff --git a/ntcore/src/main/python/ntcore/src/pyentry.cpp b/ntcore/src/main/python/ntcore/src/pyentry.cpp index f9cad5b33e..c4147953fa 100644 --- a/ntcore/src/main/python/ntcore/src/pyentry.cpp +++ b/ntcore/src/main/python/ntcore/src/pyentry.cpp @@ -7,73 +7,73 @@ namespace pyntcore { -py::object GetBooleanEntry(const nt::NetworkTableEntry &entry, py::object defaultValue) { - nt::Value value; +py::object GetBooleanEntry(const wpi::nt::NetworkTableEntry &entry, py::object defaultValue) { + wpi::nt::Value value; { py::gil_scoped_release release; - value = nt::GetEntryValue(entry.GetHandle()); + value = wpi::nt::GetEntryValue(entry.GetHandle()); } if (!value || value.type() != NT_BOOLEAN) return defaultValue; return py::cast(value.GetBoolean()); } -py::object GetDoubleEntry(const nt::NetworkTableEntry &entry, py::object defaultValue) { - nt::Value value; +py::object GetDoubleEntry(const wpi::nt::NetworkTableEntry &entry, py::object defaultValue) { + wpi::nt::Value value; { py::gil_scoped_release release; - value = nt::GetEntryValue(entry.GetHandle()); + value = wpi::nt::GetEntryValue(entry.GetHandle()); } if (!value || value.type() != NT_DOUBLE) return defaultValue; return py::cast(value.GetDouble()); } -py::object GetFloatEntry(const nt::NetworkTableEntry &entry, py::object defaultValue) { - nt::Value value; +py::object GetFloatEntry(const wpi::nt::NetworkTableEntry &entry, py::object defaultValue) { + wpi::nt::Value value; { py::gil_scoped_release release; - value = nt::GetEntryValue(entry.GetHandle()); + value = wpi::nt::GetEntryValue(entry.GetHandle()); } if (!value || value.type() != NT_FLOAT) return defaultValue; return py::cast(value.GetFloat()); } -py::object GetIntegerEntry(const nt::NetworkTableEntry &entry, py::object defaultValue) { - nt::Value value; +py::object GetIntegerEntry(const wpi::nt::NetworkTableEntry &entry, py::object defaultValue) { + wpi::nt::Value value; { py::gil_scoped_release release; - value = nt::GetEntryValue(entry.GetHandle()); + value = wpi::nt::GetEntryValue(entry.GetHandle()); } if (!value || value.type() != NT_INTEGER) return defaultValue; return py::cast(value.GetInteger()); } -py::object GetStringEntry(const nt::NetworkTableEntry &entry, py::object defaultValue) { - nt::Value value; +py::object GetStringEntry(const wpi::nt::NetworkTableEntry &entry, py::object defaultValue) { + wpi::nt::Value value; { py::gil_scoped_release release; - value = nt::GetEntryValue(entry.GetHandle()); + value = wpi::nt::GetEntryValue(entry.GetHandle()); } if (!value || value.type() != NT_STRING) return defaultValue; auto s = value.GetString(); return py::str(s.data(), s.size()); } -py::object GetRawEntry(const nt::NetworkTableEntry &entry, py::object defaultValue) { - nt::Value value; +py::object GetRawEntry(const wpi::nt::NetworkTableEntry &entry, py::object defaultValue) { + wpi::nt::Value value; { py::gil_scoped_release release; - value = nt::GetEntryValue(entry.GetHandle()); + value = wpi::nt::GetEntryValue(entry.GetHandle()); } if (!value || value.type() != NT_RAW) return defaultValue; return py::cast(value.GetRaw()); } -py::object GetBooleanArrayEntry(const nt::NetworkTableEntry &entry, py::object defaultValue) { - nt::Value value; +py::object GetBooleanArrayEntry(const wpi::nt::NetworkTableEntry &entry, py::object defaultValue) { + wpi::nt::Value value; { py::gil_scoped_release release; - value = nt::GetEntryValue(entry.GetHandle()); + value = wpi::nt::GetEntryValue(entry.GetHandle()); } if (!value || value.type() != NT_BOOLEAN_ARRAY) return defaultValue; // ntcore will return bit vector by default. Convert to List[bool] @@ -86,52 +86,52 @@ py::object GetBooleanArrayEntry(const nt::NetworkTableEntry &entry, py::object d return std::move(l); } -py::object GetDoubleArrayEntry(const nt::NetworkTableEntry &entry, py::object defaultValue) { - nt::Value value; +py::object GetDoubleArrayEntry(const wpi::nt::NetworkTableEntry &entry, py::object defaultValue) { + wpi::nt::Value value; { py::gil_scoped_release release; - value = nt::GetEntryValue(entry.GetHandle()); + value = wpi::nt::GetEntryValue(entry.GetHandle()); } if (!value || value.type() != NT_DOUBLE_ARRAY) return defaultValue; return py::cast(value.GetDoubleArray()); } -py::object GetFloatArrayEntry(const nt::NetworkTableEntry &entry, py::object defaultValue) { - nt::Value value; +py::object GetFloatArrayEntry(const wpi::nt::NetworkTableEntry &entry, py::object defaultValue) { + wpi::nt::Value value; { py::gil_scoped_release release; - value = nt::GetEntryValue(entry.GetHandle()); + value = wpi::nt::GetEntryValue(entry.GetHandle()); } if (!value || value.type() != NT_FLOAT_ARRAY) return defaultValue; return py::cast(value.GetFloatArray()); } -py::object GetIntegerArrayEntry(const nt::NetworkTableEntry &entry, py::object defaultValue) { - nt::Value value; +py::object GetIntegerArrayEntry(const wpi::nt::NetworkTableEntry &entry, py::object defaultValue) { + wpi::nt::Value value; { py::gil_scoped_release release; - value = nt::GetEntryValue(entry.GetHandle()); + value = wpi::nt::GetEntryValue(entry.GetHandle()); } if (!value || value.type() != NT_INTEGER_ARRAY) return defaultValue; return py::cast(value.GetIntegerArray()); } -py::object GetStringArrayEntry(const nt::NetworkTableEntry &entry, py::object defaultValue) { - nt::Value value; +py::object GetStringArrayEntry(const wpi::nt::NetworkTableEntry &entry, py::object defaultValue) { + wpi::nt::Value value; { py::gil_scoped_release release; - value = nt::GetEntryValue(entry.GetHandle()); + value = wpi::nt::GetEntryValue(entry.GetHandle()); } if (!value || value.type() != NT_STRING_ARRAY) return defaultValue; std::span rval = value.GetStringArray(); return py::cast(rval); } -py::object GetValueEntry(const nt::NetworkTableEntry &entry, py::object defaultValue) { - nt::Value value; +py::object GetValueEntry(const wpi::nt::NetworkTableEntry &entry, py::object defaultValue) { + wpi::nt::Value value; { py::gil_scoped_release release; - value = nt::GetEntryValue(entry.GetHandle()); + value = wpi::nt::GetEntryValue(entry.GetHandle()); } if (!value) return defaultValue; return ntvalue2py(value); diff --git a/ntcore/src/main/python/ntcore/src/pyentry.h b/ntcore/src/main/python/ntcore/src/pyentry.h index b3ca524a61..9c2d715635 100644 --- a/ntcore/src/main/python/ntcore/src/pyentry.h +++ b/ntcore/src/main/python/ntcore/src/pyentry.h @@ -5,17 +5,17 @@ namespace pyntcore { -py::object GetBooleanEntry(const nt::NetworkTableEntry &entry, py::object defaultValue); -py::object GetDoubleEntry(const nt::NetworkTableEntry &entry, py::object defaultValue); -py::object GetFloatEntry(const nt::NetworkTableEntry &entry, py::object defaultValue); -py::object GetIntegerEntry(const nt::NetworkTableEntry &entry, py::object defaultValue); -py::object GetStringEntry(const nt::NetworkTableEntry &entry, py::object defaultValue); -py::object GetRawEntry(const nt::NetworkTableEntry &entry, py::object defaultValue); -py::object GetBooleanArrayEntry(const nt::NetworkTableEntry &entry, py::object defaultValue); -py::object GetDoubleArrayEntry(const nt::NetworkTableEntry &entry, py::object defaultValue); -py::object GetFloatArrayEntry(const nt::NetworkTableEntry &entry, py::object defaultValue); -py::object GetIntegerArrayEntry(const nt::NetworkTableEntry &entry, py::object defaultValue); -py::object GetStringArrayEntry(const nt::NetworkTableEntry &entry, py::object defaultValue); -py::object GetValueEntry(const nt::NetworkTableEntry &entry, py::object defaultValue); +py::object GetBooleanEntry(const wpi::nt::NetworkTableEntry &entry, py::object defaultValue); +py::object GetDoubleEntry(const wpi::nt::NetworkTableEntry &entry, py::object defaultValue); +py::object GetFloatEntry(const wpi::nt::NetworkTableEntry &entry, py::object defaultValue); +py::object GetIntegerEntry(const wpi::nt::NetworkTableEntry &entry, py::object defaultValue); +py::object GetStringEntry(const wpi::nt::NetworkTableEntry &entry, py::object defaultValue); +py::object GetRawEntry(const wpi::nt::NetworkTableEntry &entry, py::object defaultValue); +py::object GetBooleanArrayEntry(const wpi::nt::NetworkTableEntry &entry, py::object defaultValue); +py::object GetDoubleArrayEntry(const wpi::nt::NetworkTableEntry &entry, py::object defaultValue); +py::object GetFloatArrayEntry(const wpi::nt::NetworkTableEntry &entry, py::object defaultValue); +py::object GetIntegerArrayEntry(const wpi::nt::NetworkTableEntry &entry, py::object defaultValue); +py::object GetStringArrayEntry(const wpi::nt::NetworkTableEntry &entry, py::object defaultValue); +py::object GetValueEntry(const wpi::nt::NetworkTableEntry &entry, py::object defaultValue); }; diff --git a/ntcore/src/main/python/semiwrap/BooleanArrayTopic.yml b/ntcore/src/main/python/semiwrap/BooleanArrayTopic.yml index 0133c4ad7d..e2d79b0bdf 100644 --- a/ntcore/src/main/python/semiwrap/BooleanArrayTopic.yml +++ b/ntcore/src/main/python/semiwrap/BooleanArrayTopic.yml @@ -1,5 +1,5 @@ classes: - nt::BooleanArraySubscriber: + wpi::nt::BooleanArraySubscriber: methods: BooleanArraySubscriber: overloads: @@ -11,17 +11,17 @@ classes: overloads: '[const]': ParamType [const]: - wpi::SmallVectorImpl& [const]: + wpi::util::SmallVectorImpl& [const]: ignore: true - wpi::SmallVectorImpl&, ParamType [const]: + wpi::util::SmallVectorImpl&, ParamType [const]: ignore: true GetAtomic: overloads: '[const]': ParamType [const]: - wpi::SmallVectorImpl& [const]: + wpi::util::SmallVectorImpl& [const]: ignore: true - wpi::SmallVectorImpl&, ParamType [const]: + wpi::util::SmallVectorImpl&, ParamType [const]: ignore: true ReadQueue: GetTopic: @@ -37,7 +37,7 @@ classes: py::gil_scoped_release release; *self = BooleanArraySubscriber(); }) - nt::BooleanArrayPublisher: + wpi::nt::BooleanArrayPublisher: methods: BooleanArrayPublisher: overloads: @@ -60,7 +60,7 @@ classes: py::gil_scoped_release release; *self = BooleanArrayPublisher(); }) - nt::BooleanArrayEntry: + wpi::nt::BooleanArrayEntry: methods: BooleanArrayEntry: overloads: @@ -84,7 +84,7 @@ classes: py::gil_scoped_release release; *self = BooleanArrayEntry(); }) - nt::BooleanArrayTopic: + wpi::nt::BooleanArrayTopic: attributes: kTypeString: methods: diff --git a/ntcore/src/main/python/semiwrap/BooleanTopic.yml b/ntcore/src/main/python/semiwrap/BooleanTopic.yml index 8a4d3ddef5..2de884de87 100644 --- a/ntcore/src/main/python/semiwrap/BooleanTopic.yml +++ b/ntcore/src/main/python/semiwrap/BooleanTopic.yml @@ -1,5 +1,5 @@ classes: - nt::BooleanSubscriber: + wpi::nt::BooleanSubscriber: methods: BooleanSubscriber: overloads: @@ -29,7 +29,7 @@ classes: py::gil_scoped_release release; *self = BooleanSubscriber(); }) - nt::BooleanPublisher: + wpi::nt::BooleanPublisher: methods: BooleanPublisher: overloads: @@ -52,7 +52,7 @@ classes: py::gil_scoped_release release; *self = BooleanPublisher(); }) - nt::BooleanEntry: + wpi::nt::BooleanEntry: methods: BooleanEntry: overloads: @@ -76,7 +76,7 @@ classes: py::gil_scoped_release release; *self = BooleanEntry(); }) - nt::BooleanTopic: + wpi::nt::BooleanTopic: attributes: kTypeString: methods: diff --git a/ntcore/src/main/python/semiwrap/DoubleArrayTopic.yml b/ntcore/src/main/python/semiwrap/DoubleArrayTopic.yml index 52892083ff..a72335071a 100644 --- a/ntcore/src/main/python/semiwrap/DoubleArrayTopic.yml +++ b/ntcore/src/main/python/semiwrap/DoubleArrayTopic.yml @@ -1,5 +1,5 @@ classes: - nt::DoubleArraySubscriber: + wpi::nt::DoubleArraySubscriber: methods: DoubleArraySubscriber: overloads: @@ -11,17 +11,17 @@ classes: overloads: '[const]': ParamType [const]: - wpi::SmallVectorImpl& [const]: + wpi::util::SmallVectorImpl& [const]: ignore: true - wpi::SmallVectorImpl&, ParamType [const]: + wpi::util::SmallVectorImpl&, ParamType [const]: ignore: true GetAtomic: overloads: '[const]': ParamType [const]: - wpi::SmallVectorImpl& [const]: + wpi::util::SmallVectorImpl& [const]: ignore: true - wpi::SmallVectorImpl&, ParamType [const]: + wpi::util::SmallVectorImpl&, ParamType [const]: ignore: true ReadQueue: GetTopic: @@ -37,7 +37,7 @@ classes: py::gil_scoped_release release; *self = DoubleArraySubscriber(); }) - nt::DoubleArrayPublisher: + wpi::nt::DoubleArrayPublisher: methods: DoubleArrayPublisher: overloads: @@ -60,7 +60,7 @@ classes: py::gil_scoped_release release; *self = DoubleArrayPublisher(); }) - nt::DoubleArrayEntry: + wpi::nt::DoubleArrayEntry: methods: DoubleArrayEntry: overloads: @@ -84,7 +84,7 @@ classes: py::gil_scoped_release release; *self = DoubleArrayEntry(); }) - nt::DoubleArrayTopic: + wpi::nt::DoubleArrayTopic: attributes: kTypeString: methods: diff --git a/ntcore/src/main/python/semiwrap/DoubleTopic.yml b/ntcore/src/main/python/semiwrap/DoubleTopic.yml index de572d690e..2a7bb47e7f 100644 --- a/ntcore/src/main/python/semiwrap/DoubleTopic.yml +++ b/ntcore/src/main/python/semiwrap/DoubleTopic.yml @@ -1,5 +1,5 @@ classes: - nt::DoubleSubscriber: + wpi::nt::DoubleSubscriber: methods: DoubleSubscriber: overloads: @@ -29,7 +29,7 @@ classes: py::gil_scoped_release release; *self = DoubleSubscriber(); }) - nt::DoublePublisher: + wpi::nt::DoublePublisher: methods: DoublePublisher: overloads: @@ -52,7 +52,7 @@ classes: py::gil_scoped_release release; *self = DoublePublisher(); }) - nt::DoubleEntry: + wpi::nt::DoubleEntry: methods: DoubleEntry: overloads: @@ -76,7 +76,7 @@ classes: py::gil_scoped_release release; *self = DoubleEntry(); }) - nt::DoubleTopic: + wpi::nt::DoubleTopic: attributes: kTypeString: methods: diff --git a/ntcore/src/main/python/semiwrap/FloatArrayTopic.yml b/ntcore/src/main/python/semiwrap/FloatArrayTopic.yml index a00b48bb94..7d4f3eec1a 100644 --- a/ntcore/src/main/python/semiwrap/FloatArrayTopic.yml +++ b/ntcore/src/main/python/semiwrap/FloatArrayTopic.yml @@ -1,5 +1,5 @@ classes: - nt::FloatArraySubscriber: + wpi::nt::FloatArraySubscriber: methods: FloatArraySubscriber: overloads: @@ -11,17 +11,17 @@ classes: overloads: '[const]': ParamType [const]: - wpi::SmallVectorImpl& [const]: + wpi::util::SmallVectorImpl& [const]: ignore: true - wpi::SmallVectorImpl&, ParamType [const]: + wpi::util::SmallVectorImpl&, ParamType [const]: ignore: true GetAtomic: overloads: '[const]': ParamType [const]: - wpi::SmallVectorImpl& [const]: + wpi::util::SmallVectorImpl& [const]: ignore: true - wpi::SmallVectorImpl&, ParamType [const]: + wpi::util::SmallVectorImpl&, ParamType [const]: ignore: true ReadQueue: GetTopic: @@ -37,7 +37,7 @@ classes: py::gil_scoped_release release; *self = FloatArraySubscriber(); }) - nt::FloatArrayPublisher: + wpi::nt::FloatArrayPublisher: methods: FloatArrayPublisher: overloads: @@ -60,7 +60,7 @@ classes: py::gil_scoped_release release; *self = FloatArrayPublisher(); }) - nt::FloatArrayEntry: + wpi::nt::FloatArrayEntry: methods: FloatArrayEntry: overloads: @@ -84,7 +84,7 @@ classes: py::gil_scoped_release release; *self = FloatArrayEntry(); }) - nt::FloatArrayTopic: + wpi::nt::FloatArrayTopic: attributes: kTypeString: methods: diff --git a/ntcore/src/main/python/semiwrap/FloatTopic.yml b/ntcore/src/main/python/semiwrap/FloatTopic.yml index c0f3e192b3..9d66609c03 100644 --- a/ntcore/src/main/python/semiwrap/FloatTopic.yml +++ b/ntcore/src/main/python/semiwrap/FloatTopic.yml @@ -1,5 +1,5 @@ classes: - nt::FloatSubscriber: + wpi::nt::FloatSubscriber: methods: FloatSubscriber: overloads: @@ -29,7 +29,7 @@ classes: py::gil_scoped_release release; *self = FloatSubscriber(); }) - nt::FloatPublisher: + wpi::nt::FloatPublisher: methods: FloatPublisher: overloads: @@ -52,7 +52,7 @@ classes: py::gil_scoped_release release; *self = FloatPublisher(); }) - nt::FloatEntry: + wpi::nt::FloatEntry: methods: FloatEntry: overloads: @@ -76,7 +76,7 @@ classes: py::gil_scoped_release release; *self = FloatEntry(); }) - nt::FloatTopic: + wpi::nt::FloatTopic: attributes: kTypeString: methods: diff --git a/ntcore/src/main/python/semiwrap/GenericEntry.yml b/ntcore/src/main/python/semiwrap/GenericEntry.yml index 3b7335d5c6..643c966371 100644 --- a/ntcore/src/main/python/semiwrap/GenericEntry.yml +++ b/ntcore/src/main/python/semiwrap/GenericEntry.yml @@ -2,7 +2,7 @@ extra_includes: - src/nt_type_caster.h classes: - nt::GenericSubscriber: + wpi::nt::GenericSubscriber: methods: GenericSubscriber: overloads: @@ -24,7 +24,7 @@ classes: GetStringArray: ReadQueue: GetTopic: - nt::GenericPublisher: + wpi::nt::GenericPublisher: methods: GenericPublisher: overloads: @@ -60,7 +60,7 @@ classes: SetDefaultDoubleArray: SetDefaultStringArray: GetTopic: - nt::GenericEntry: + wpi::nt::GenericEntry: methods: GenericEntry: overloads: diff --git a/ntcore/src/main/python/semiwrap/IntegerArrayTopic.yml b/ntcore/src/main/python/semiwrap/IntegerArrayTopic.yml index 2582c32de9..9816cf3db7 100644 --- a/ntcore/src/main/python/semiwrap/IntegerArrayTopic.yml +++ b/ntcore/src/main/python/semiwrap/IntegerArrayTopic.yml @@ -1,5 +1,5 @@ classes: - nt::IntegerArraySubscriber: + wpi::nt::IntegerArraySubscriber: methods: IntegerArraySubscriber: overloads: @@ -11,17 +11,17 @@ classes: overloads: '[const]': ParamType [const]: - wpi::SmallVectorImpl& [const]: + wpi::util::SmallVectorImpl& [const]: ignore: true - wpi::SmallVectorImpl&, ParamType [const]: + wpi::util::SmallVectorImpl&, ParamType [const]: ignore: true GetAtomic: overloads: '[const]': ParamType [const]: - wpi::SmallVectorImpl& [const]: + wpi::util::SmallVectorImpl& [const]: ignore: true - wpi::SmallVectorImpl&, ParamType [const]: + wpi::util::SmallVectorImpl&, ParamType [const]: ignore: true ReadQueue: GetTopic: @@ -37,7 +37,7 @@ classes: py::gil_scoped_release release; *self = IntegerArraySubscriber(); }) - nt::IntegerArrayPublisher: + wpi::nt::IntegerArrayPublisher: methods: IntegerArrayPublisher: overloads: @@ -60,7 +60,7 @@ classes: py::gil_scoped_release release; *self = IntegerArrayPublisher(); }) - nt::IntegerArrayEntry: + wpi::nt::IntegerArrayEntry: methods: IntegerArrayEntry: overloads: @@ -84,7 +84,7 @@ classes: py::gil_scoped_release release; *self = IntegerArrayEntry(); }) - nt::IntegerArrayTopic: + wpi::nt::IntegerArrayTopic: attributes: kTypeString: methods: diff --git a/ntcore/src/main/python/semiwrap/IntegerTopic.yml b/ntcore/src/main/python/semiwrap/IntegerTopic.yml index 07b6859cd0..f39a7aa003 100644 --- a/ntcore/src/main/python/semiwrap/IntegerTopic.yml +++ b/ntcore/src/main/python/semiwrap/IntegerTopic.yml @@ -1,5 +1,5 @@ classes: - nt::IntegerSubscriber: + wpi::nt::IntegerSubscriber: methods: IntegerSubscriber: overloads: @@ -29,7 +29,7 @@ classes: py::gil_scoped_release release; *self = IntegerSubscriber(); }) - nt::IntegerPublisher: + wpi::nt::IntegerPublisher: methods: IntegerPublisher: overloads: @@ -52,7 +52,7 @@ classes: py::gil_scoped_release release; *self = IntegerPublisher(); }) - nt::IntegerEntry: + wpi::nt::IntegerEntry: methods: IntegerEntry: overloads: @@ -76,7 +76,7 @@ classes: py::gil_scoped_release release; *self = IntegerEntry(); }) - nt::IntegerTopic: + wpi::nt::IntegerTopic: attributes: kTypeString: methods: diff --git a/ntcore/src/main/python/semiwrap/MultiSubscriber.yml b/ntcore/src/main/python/semiwrap/MultiSubscriber.yml index a980e9b5a5..1c0dd49196 100644 --- a/ntcore/src/main/python/semiwrap/MultiSubscriber.yml +++ b/ntcore/src/main/python/semiwrap/MultiSubscriber.yml @@ -1,5 +1,5 @@ classes: - nt::MultiSubscriber: + wpi::nt::MultiSubscriber: methods: MultiSubscriber: overloads: diff --git a/ntcore/src/main/python/semiwrap/NTSendable.yml b/ntcore/src/main/python/semiwrap/NTSendable.yml index 57ad364839..7ec37cc71a 100644 --- a/ntcore/src/main/python/semiwrap/NTSendable.yml +++ b/ntcore/src/main/python/semiwrap/NTSendable.yml @@ -2,7 +2,7 @@ extra_includes: - wpi/nt/NTSendableBuilder.hpp classes: - nt::NTSendable: + wpi::nt::NTSendable: methods: InitSendable: overloads: @@ -12,7 +12,7 @@ classes: auto builderHandle = py::cast(builder, py::return_value_policy::reference); fn(builderHandle); } - wpi::SendableBuilder&: + wpi::util::SendableBuilder&: virtual_xform: | [&](py::function fn) { auto builderHandle = py::cast(builder, py::return_value_policy::reference); diff --git a/ntcore/src/main/python/semiwrap/NTSendableBuilder.yml b/ntcore/src/main/python/semiwrap/NTSendableBuilder.yml index afa178a30b..ac842df6d9 100644 --- a/ntcore/src/main/python/semiwrap/NTSendableBuilder.yml +++ b/ntcore/src/main/python/semiwrap/NTSendableBuilder.yml @@ -1,9 +1,9 @@ classes: - nt::NTSendableBuilder: + wpi::nt::NTSendableBuilder: force_type_casters: - std::function typealias: - - BackendKind = wpi::SendableBuilder::BackendKind + - BackendKind = wpi::util::SendableBuilder::BackendKind methods: SetUpdateTable: cpp_code: | diff --git a/ntcore/src/main/python/semiwrap/NetworkTable.yml b/ntcore/src/main/python/semiwrap/NetworkTable.yml index 9967873efe..09f0649cab 100644 --- a/ntcore/src/main/python/semiwrap/NetworkTable.yml +++ b/ntcore/src/main/python/semiwrap/NetworkTable.yml @@ -19,7 +19,7 @@ extra_includes: - wpystruct.h classes: - nt::NetworkTable: + wpi::nt::NetworkTable: attributes: PATH_SEPARATOR_CHAR: methods: @@ -27,7 +27,7 @@ classes: NormalizeKey: overloads: std::string_view, bool: - std::string_view, wpi::SmallVectorImpl&, bool: + std::string_view, wpi::util::SmallVectorImpl&, bool: ignore: true GetHierarchy: NetworkTable: @@ -81,7 +81,7 @@ classes: GetNumber: cpp_code: | [](NetworkTable * table, std::string_view key, py::object defaultValue) -> py::object { - nt::NetworkTableEntry entry; + wpi::nt::NetworkTableEntry entry; { py::gil_scoped_release release; entry = table->GetEntry(key); @@ -93,7 +93,7 @@ classes: GetString: cpp_code: | [](NetworkTable * table, std::string_view key, py::object defaultValue) -> py::object { - nt::NetworkTableEntry entry; + wpi::nt::NetworkTableEntry entry; { py::gil_scoped_release release; entry = table->GetEntry(key); @@ -105,7 +105,7 @@ classes: GetBoolean: cpp_code: | [](NetworkTable * table, std::string_view key, py::object defaultValue) -> py::object { - nt::NetworkTableEntry entry; + wpi::nt::NetworkTableEntry entry; { py::gil_scoped_release release; entry = table->GetEntry(key); @@ -117,7 +117,7 @@ classes: GetBooleanArray: cpp_code: | [](NetworkTable * table, std::string_view key, py::object defaultValue) -> py::object { - nt::NetworkTableEntry entry; + wpi::nt::NetworkTableEntry entry; { py::gil_scoped_release release; entry = table->GetEntry(key); @@ -129,7 +129,7 @@ classes: GetNumberArray: cpp_code: | [](NetworkTable * table, std::string_view key, py::object defaultValue) -> py::object { - nt::NetworkTableEntry entry; + wpi::nt::NetworkTableEntry entry; { py::gil_scoped_release release; entry = table->GetEntry(key); @@ -141,7 +141,7 @@ classes: GetStringArray: cpp_code: | [](NetworkTable * table, std::string_view key, py::object defaultValue) -> py::object { - nt::NetworkTableEntry entry; + wpi::nt::NetworkTableEntry entry; { py::gil_scoped_release release; entry = table->GetEntry(key); @@ -153,7 +153,7 @@ classes: GetRaw: cpp_code: | [](NetworkTable * table, std::string_view key, py::object defaultValue) -> py::object { - nt::NetworkTableEntry entry; + wpi::nt::NetworkTableEntry entry; { py::gil_scoped_release release; entry = table->GetEntry(key); diff --git a/ntcore/src/main/python/semiwrap/NetworkTableEntry.yml b/ntcore/src/main/python/semiwrap/NetworkTableEntry.yml index 8ba9f8788c..d38054f9f4 100644 --- a/ntcore/src/main/python/semiwrap/NetworkTableEntry.yml +++ b/ntcore/src/main/python/semiwrap/NetworkTableEntry.yml @@ -7,7 +7,7 @@ extra_includes: inline_code: | #include classes: - nt::NetworkTableEntry: + wpi::nt::NetworkTableEntry: methods: NetworkTableEntry: overloads: diff --git a/ntcore/src/main/python/semiwrap/NetworkTableInstance.yml b/ntcore/src/main/python/semiwrap/NetworkTableInstance.yml index 84f7e39f7f..2bf33daa1b 100644 --- a/ntcore/src/main/python/semiwrap/NetworkTableInstance.yml +++ b/ntcore/src/main/python/semiwrap/NetworkTableInstance.yml @@ -20,7 +20,7 @@ extra_includes: - wpystruct.h classes: - nt::NetworkTableInstance: + wpi::nt::NetworkTableInstance: force_type_casters: - std::function attributes: @@ -29,7 +29,7 @@ classes: NetworkMode: arithmetic: true inline_code: | - .value("kNetModeStarting", (nt::NetworkTableInstance::NetworkMode)NT_NET_MODE_STARTING) + .value("kNetModeStarting", (wpi::nt::NetworkTableInstance::NetworkMode)NT_NET_MODE_STARTING) LogLevel: methods: NetworkTableInstance: @@ -175,7 +175,7 @@ classes: pyntcore::onInstancePreReset(self); { py::gil_scoped_release release; - nt::ResetInstance(self->GetHandle()); + wpi::nt::ResetInstance(self->GetHandle()); } pyntcore::onInstancePostReset(self); }) diff --git a/ntcore/src/main/python/semiwrap/NetworkTableListener.yml b/ntcore/src/main/python/semiwrap/NetworkTableListener.yml index e96cfabe8f..daa8537e72 100644 --- a/ntcore/src/main/python/semiwrap/NetworkTableListener.yml +++ b/ntcore/src/main/python/semiwrap/NetworkTableListener.yml @@ -1,5 +1,5 @@ classes: - nt::NetworkTableListener: + wpi::nt::NetworkTableListener: force_type_casters: - std::function methods: @@ -30,7 +30,7 @@ classes: py::gil_scoped_release release; *self = NetworkTableListener(); }) - nt::NetworkTableListenerPoller: + wpi::nt::NetworkTableListenerPoller: methods: NetworkTableListenerPoller: overloads: diff --git a/ntcore/src/main/python/semiwrap/NetworkTableValue.yml b/ntcore/src/main/python/semiwrap/NetworkTableValue.yml index f114ecfa49..f1317289ce 100644 --- a/ntcore/src/main/python/semiwrap/NetworkTableValue.yml +++ b/ntcore/src/main/python/semiwrap/NetworkTableValue.yml @@ -7,7 +7,7 @@ functions: ignore: true classes: - nt::Value: + wpi::nt::Value: methods: Value: overloads: @@ -174,7 +174,7 @@ classes: .def_static("makeValue", [](py::handle value) { return pyntcore::py2ntvalue(value); }, py::arg("value")) - .def_static("getFactoryByType", [](nt::NetworkTableType type) { + .def_static("getFactoryByType", [](wpi::nt::NetworkTableType type) { return pyntcore::valueFactoryByType(type); }, py::arg("type")) .def("__repr__", [](const Value &self) -> py::str { diff --git a/ntcore/src/main/python/semiwrap/RawTopic.yml b/ntcore/src/main/python/semiwrap/RawTopic.yml index a7a844d4c3..66329b62c1 100644 --- a/ntcore/src/main/python/semiwrap/RawTopic.yml +++ b/ntcore/src/main/python/semiwrap/RawTopic.yml @@ -2,7 +2,7 @@ extra_includes: - src/nt_type_caster.h classes: - nt::RawSubscriber: + wpi::nt::RawSubscriber: methods: RawSubscriber: overloads: @@ -14,17 +14,17 @@ classes: overloads: '[const]': ParamType [const]: - wpi::SmallVectorImpl& [const]: + wpi::util::SmallVectorImpl& [const]: ignore: true - wpi::SmallVectorImpl&, ParamType [const]: + wpi::util::SmallVectorImpl&, ParamType [const]: ignore: true GetAtomic: overloads: '[const]': ParamType [const]: - wpi::SmallVectorImpl& [const]: + wpi::util::SmallVectorImpl& [const]: ignore: true - wpi::SmallVectorImpl&, ParamType [const]: + wpi::util::SmallVectorImpl&, ParamType [const]: ignore: true ReadQueue: GetTopic: @@ -40,7 +40,7 @@ classes: py::gil_scoped_release release; *self = RawSubscriber(); }) - nt::RawPublisher: + wpi::nt::RawPublisher: methods: RawPublisher: overloads: @@ -63,7 +63,7 @@ classes: py::gil_scoped_release release; *self = RawPublisher(); }) - nt::RawEntry: + wpi::nt::RawEntry: methods: RawEntry: overloads: @@ -87,7 +87,7 @@ classes: py::gil_scoped_release release; *self = RawEntry(); }) - nt::RawTopic: + wpi::nt::RawTopic: methods: RawTopic: overloads: diff --git a/ntcore/src/main/python/semiwrap/StringArrayTopic.yml b/ntcore/src/main/python/semiwrap/StringArrayTopic.yml index c55444273e..0ac466ed6f 100644 --- a/ntcore/src/main/python/semiwrap/StringArrayTopic.yml +++ b/ntcore/src/main/python/semiwrap/StringArrayTopic.yml @@ -1,5 +1,5 @@ classes: - nt::StringArraySubscriber: + wpi::nt::StringArraySubscriber: methods: StringArraySubscriber: overloads: @@ -29,7 +29,7 @@ classes: py::gil_scoped_release release; *self = StringArraySubscriber(); }) - nt::StringArrayPublisher: + wpi::nt::StringArrayPublisher: methods: StringArrayPublisher: overloads: @@ -52,7 +52,7 @@ classes: py::gil_scoped_release release; *self = StringArrayPublisher(); }) - nt::StringArrayEntry: + wpi::nt::StringArrayEntry: methods: StringArrayEntry: overloads: @@ -76,7 +76,7 @@ classes: py::gil_scoped_release release; *self = StringArrayEntry(); }) - nt::StringArrayTopic: + wpi::nt::StringArrayTopic: attributes: kTypeString: methods: diff --git a/ntcore/src/main/python/semiwrap/StringTopic.yml b/ntcore/src/main/python/semiwrap/StringTopic.yml index fc908747e5..aae37909b4 100644 --- a/ntcore/src/main/python/semiwrap/StringTopic.yml +++ b/ntcore/src/main/python/semiwrap/StringTopic.yml @@ -1,5 +1,5 @@ classes: - nt::StringSubscriber: + wpi::nt::StringSubscriber: methods: StringSubscriber: overloads: @@ -11,17 +11,17 @@ classes: overloads: '[const]': ParamType [const]: - wpi::SmallVectorImpl& [const]: + wpi::util::SmallVectorImpl& [const]: ignore: true - wpi::SmallVectorImpl&, ParamType [const]: + wpi::util::SmallVectorImpl&, ParamType [const]: ignore: true GetAtomic: overloads: '[const]': ParamType [const]: - wpi::SmallVectorImpl& [const]: + wpi::util::SmallVectorImpl& [const]: ignore: true - wpi::SmallVectorImpl&, ParamType [const]: + wpi::util::SmallVectorImpl&, ParamType [const]: ignore: true ReadQueue: GetTopic: @@ -37,7 +37,7 @@ classes: py::gil_scoped_release release; *self = StringSubscriber(); }) - nt::StringPublisher: + wpi::nt::StringPublisher: methods: StringPublisher: overloads: @@ -60,7 +60,7 @@ classes: py::gil_scoped_release release; *self = StringPublisher(); }) - nt::StringEntry: + wpi::nt::StringEntry: methods: StringEntry: overloads: @@ -84,7 +84,7 @@ classes: py::gil_scoped_release release; *self = StringEntry(); }) - nt::StringTopic: + wpi::nt::StringTopic: attributes: kTypeString: methods: diff --git a/ntcore/src/main/python/semiwrap/StructArrayTopic.yml b/ntcore/src/main/python/semiwrap/StructArrayTopic.yml index 88960b4992..57e538fd9d 100644 --- a/ntcore/src/main/python/semiwrap/StructArrayTopic.yml +++ b/ntcore/src/main/python/semiwrap/StructArrayTopic.yml @@ -1,5 +1,5 @@ classes: - nt::StructArraySubscriber: + wpi::nt::StructArraySubscriber: template_params: - T - I @@ -25,18 +25,18 @@ classes: ReadQueue: GetTopic: inline_code: | - .def("close", [](nt::StructArraySubscriber *self) { + .def("close", [](wpi::nt::StructArraySubscriber *self) { py::gil_scoped_release release; - *self = nt::StructArraySubscriber(); + *self = wpi::nt::StructArraySubscriber(); }, py::doc("Destroys the subscriber")) - .def("__enter__", [](nt::StructArraySubscriber *self) { + .def("__enter__", [](wpi::nt::StructArraySubscriber *self) { return self; }) - .def("__exit__", [](nt::StructArraySubscriber *self, py::args args) { + .def("__exit__", [](wpi::nt::StructArraySubscriber *self, py::args args) { py::gil_scoped_release release; - *self = nt::StructArraySubscriber(); + *self = wpi::nt::StructArraySubscriber(); }) - nt::StructArrayPublisher: + wpi::nt::StructArrayPublisher: template_params: - T - I @@ -59,24 +59,24 @@ classes: std::span: GetTopic: inline_code: | - .def("close", [](nt::StructArrayPublisher *self) { + .def("close", [](wpi::nt::StructArrayPublisher *self) { py::gil_scoped_release release; - *self = nt::StructArrayPublisher(); + *self = wpi::nt::StructArrayPublisher(); }, py::doc("Destroys the publisher")) - .def("__enter__", [](nt::StructArrayPublisher *self) { + .def("__enter__", [](wpi::nt::StructArrayPublisher *self) { return self; }) - .def("__exit__", [](nt::StructArrayPublisher *self, py::args args) { + .def("__exit__", [](wpi::nt::StructArrayPublisher *self, py::args args) { py::gil_scoped_release release; - *self = nt::StructArrayPublisher(); + *self = wpi::nt::StructArrayPublisher(); }) - nt::StructArrayEntry: + wpi::nt::StructArrayEntry: template_params: - T - I base_qualnames: - StructArraySubscriber: nt::StructArraySubscriber - StructArrayPublisher: nt::StructArrayPublisher + StructArraySubscriber: wpi::nt::StructArraySubscriber + StructArrayPublisher: wpi::nt::StructArrayPublisher methods: StructArrayEntry: overloads: @@ -89,18 +89,18 @@ classes: GetTopic: Unpublish: inline_code: | - .def("close", [](nt::StructArrayEntry *self) { + .def("close", [](wpi::nt::StructArrayEntry *self) { py::gil_scoped_release release; - *self = nt::StructArrayEntry(); + *self = wpi::nt::StructArrayEntry(); }, py::doc("Destroys the entry")) - .def("__enter__", [](nt::StructArrayEntry *self) { + .def("__enter__", [](wpi::nt::StructArrayEntry *self) { return self; }) - .def("__exit__", [](nt::StructArrayEntry *self, py::args args) { + .def("__exit__", [](wpi::nt::StructArrayEntry *self, py::args args) { py::gil_scoped_release release; - *self = nt::StructArrayEntry(); + *self = wpi::nt::StructArrayEntry(); }) - nt::StructArrayTopic: + wpi::nt::StructArrayTopic: template_params: - T - I @@ -118,7 +118,7 @@ classes: cpp_code: | [](Topic topic, const py::type &t) { WPyStructInfo info(t); - return nt::StructArrayTopic(topic, info); + return wpi::nt::StructArrayTopic(topic, info); } Subscribe: overloads: @@ -133,35 +133,35 @@ classes: ignore: true std::span, const PubSubOptions&: inline_code: | - .def("close", [](nt::StructArrayTopic *self) { + .def("close", [](wpi::nt::StructArrayTopic *self) { py::gil_scoped_release release; - *self = nt::StructArrayTopic(); + *self = wpi::nt::StructArrayTopic(); }, py::doc("Destroys the topic")) - .def("__enter__", [](nt::StructArrayTopic *self) { + .def("__enter__", [](wpi::nt::StructArrayTopic *self) { return self; }) - .def("__exit__", [](nt::StructArrayTopic *self, py::args args) { + .def("__exit__", [](wpi::nt::StructArrayTopic *self, py::args args) { py::gil_scoped_release release; - *self = nt::StructArrayTopic(); + *self = wpi::nt::StructArrayTopic(); }) templates: StructArraySubscriber: - qualname: nt::StructArraySubscriber + qualname: wpi::nt::StructArraySubscriber params: - WPyStruct - WPyStructInfo StructArrayPublisher: - qualname: nt::StructArrayPublisher + qualname: wpi::nt::StructArrayPublisher params: - WPyStruct - WPyStructInfo StructArrayEntry: - qualname: nt::StructArrayEntry + qualname: wpi::nt::StructArrayEntry params: - WPyStruct - WPyStructInfo StructArrayTopic: - qualname: nt::StructArrayTopic + qualname: wpi::nt::StructArrayTopic params: - WPyStruct - WPyStructInfo diff --git a/ntcore/src/main/python/semiwrap/StructTopic.yml b/ntcore/src/main/python/semiwrap/StructTopic.yml index 694f0af8da..8ff5ad5a77 100644 --- a/ntcore/src/main/python/semiwrap/StructTopic.yml +++ b/ntcore/src/main/python/semiwrap/StructTopic.yml @@ -1,5 +1,5 @@ classes: - nt::StructSubscriber: + wpi::nt::StructSubscriber: template_params: - T - I @@ -23,18 +23,18 @@ classes: ReadQueue: GetTopic: inline_code: | - .def("close", [](nt::StructSubscriber *self) { + .def("close", [](wpi::nt::StructSubscriber *self) { py::gil_scoped_release release; - *self = nt::StructSubscriber(); + *self = wpi::nt::StructSubscriber(); }, py::doc("Destroys the subscriber")) - .def("__enter__", [](nt::StructSubscriber *self) { + .def("__enter__", [](wpi::nt::StructSubscriber *self) { return self; }) - .def("__exit__", [](nt::StructSubscriber *self, py::args args) { + .def("__exit__", [](wpi::nt::StructSubscriber *self, py::args args) { py::gil_scoped_release release; - *self = nt::StructSubscriber(); + *self = wpi::nt::StructSubscriber(); }) - nt::StructPublisher: + wpi::nt::StructPublisher: template_params: - T - I @@ -49,24 +49,24 @@ classes: SetDefault: GetTopic: inline_code: | - .def("close", [](nt::StructPublisher *self) { + .def("close", [](wpi::nt::StructPublisher *self) { py::gil_scoped_release release; - *self = nt::StructPublisher(); + *self = wpi::nt::StructPublisher(); }, py::doc("Destroys the publisher")) - .def("__enter__", [](nt::StructPublisher *self) { + .def("__enter__", [](wpi::nt::StructPublisher *self) { return self; }) - .def("__exit__", [](nt::StructPublisher *self, py::args args) { + .def("__exit__", [](wpi::nt::StructPublisher *self, py::args args) { py::gil_scoped_release release; - *self = nt::StructPublisher(); + *self = wpi::nt::StructPublisher(); }) - nt::StructEntry: + wpi::nt::StructEntry: template_params: - T - I base_qualnames: - StructSubscriber: nt::StructSubscriber - StructPublisher: nt::StructPublisher + StructSubscriber: wpi::nt::StructSubscriber + StructPublisher: wpi::nt::StructPublisher methods: StructEntry: overloads: @@ -79,18 +79,18 @@ classes: GetTopic: Unpublish: inline_code: | - .def("close", [](nt::StructEntry *self) { + .def("close", [](wpi::nt::StructEntry *self) { py::gil_scoped_release release; - *self = nt::StructEntry(); + *self = wpi::nt::StructEntry(); }, py::doc("Destroys the entry")) - .def("__enter__", [](nt::StructEntry *self) { + .def("__enter__", [](wpi::nt::StructEntry *self) { return self; }) - .def("__exit__", [](nt::StructEntry *self, py::args args) { + .def("__exit__", [](wpi::nt::StructEntry *self, py::args args) { py::gil_scoped_release release; - *self = nt::StructEntry(); + *self = wpi::nt::StructEntry(); }) - nt::StructTopic: + wpi::nt::StructTopic: template_params: - T - I @@ -108,42 +108,42 @@ classes: cpp_code: | [](Topic topic, const py::type &t) { WPyStructInfo info(t); - return nt::StructTopic(topic, info); + return wpi::nt::StructTopic(topic, info); } Subscribe: Publish: PublishEx: GetEntry: inline_code: | - .def("close", [](nt::StructTopic *self) { + .def("close", [](wpi::nt::StructTopic *self) { py::gil_scoped_release release; - *self = nt::StructTopic(); + *self = wpi::nt::StructTopic(); }, py::doc("Destroys the topic")) - .def("__enter__", [](nt::StructTopic *self) { + .def("__enter__", [](wpi::nt::StructTopic *self) { return self; }) - .def("__exit__", [](nt::StructTopic *self, py::args args) { + .def("__exit__", [](wpi::nt::StructTopic *self, py::args args) { py::gil_scoped_release release; - *self = nt::StructTopic(); + *self = wpi::nt::StructTopic(); }) templates: StructSubscriber: - qualname: nt::StructSubscriber + qualname: wpi::nt::StructSubscriber params: - WPyStruct - WPyStructInfo StructPublisher: - qualname: nt::StructPublisher + qualname: wpi::nt::StructPublisher params: - WPyStruct - WPyStructInfo StructEntry: - qualname: nt::StructEntry + qualname: wpi::nt::StructEntry params: - WPyStruct - WPyStructInfo StructTopic: - qualname: nt::StructTopic + qualname: wpi::nt::StructTopic params: - WPyStruct - WPyStructInfo diff --git a/ntcore/src/main/python/semiwrap/Topic.yml b/ntcore/src/main/python/semiwrap/Topic.yml index aca537746e..bb52df81e4 100644 --- a/ntcore/src/main/python/semiwrap/Topic.yml +++ b/ntcore/src/main/python/semiwrap/Topic.yml @@ -3,7 +3,7 @@ extra_includes: - wpi/nt/NetworkTableInstance.hpp classes: - nt::Topic: + wpi::nt::Topic: methods: Topic: overloads: @@ -47,7 +47,7 @@ classes: std::string name = self.cast().GetName(); return py::str("<{} {!r}>").format(type_name, name); }) - nt::Subscriber: + wpi::nt::Subscriber: attributes: m_subHandle: methods: @@ -68,7 +68,7 @@ classes: auto topic = self.cast().GetTopic(); return py::str("<{} {!r}>").format(type_name, topic.GetName()); }) - nt::Publisher: + wpi::nt::Publisher: attributes: m_pubHandle: methods: diff --git a/ntcore/src/main/python/semiwrap/ntcore_cpp.yml b/ntcore/src/main/python/semiwrap/ntcore_cpp.yml index 360e2c47af..6a7e938289 100644 --- a/ntcore/src/main/python/semiwrap/ntcore_cpp.yml +++ b/ntcore/src/main/python/semiwrap/ntcore_cpp.yml @@ -28,7 +28,7 @@ functions: DecodeClients: subpackage: meta classes: - nt::EventFlags: + wpi::nt::EventFlags: attributes: kNone: kImmediate: @@ -44,7 +44,7 @@ classes: kValueAll: kLogMessage: kTimeSync: - nt::TopicInfo: + wpi::nt::TopicInfo: attributes: name: type_str: @@ -57,16 +57,16 @@ classes: GetProperties: inline_code: | .def_property_readonly("topic", [](const TopicInfo &self) { - return std::make_shared(self.topic); + return std::make_shared(self.topic); }) .def_property_readonly("type", [](const TopicInfo &self) { - return nt::NetworkTableType(self.type); + return wpi::nt::NetworkTableType(self.type); }) .def("__repr__", [](const TopicInfo &self) -> py::str { return py::str("") .format(self.name, self.type_str); }) - nt::ConnectionInfo: + wpi::nt::ConnectionInfo: attributes: remote_id: remote_ip: @@ -79,7 +79,7 @@ classes: .format(self.remote_id, self.remote_ip, self.remote_port, self.last_update, self.protocol_version); }) - nt::ValueEventData: + wpi::nt::ValueEventData: attributes: topic: ignore: true @@ -95,14 +95,14 @@ classes: ignore: true inline_code: | .def_property_readonly("topic", [](const ValueEventData &self) { - return std::make_shared(self.topic); + return std::make_shared(self.topic); }) .def("__repr__", [](const ValueEventData &self) -> py::str { - auto topicInfo = nt::GetTopicInfo(self.topic); + auto topicInfo = wpi::nt::GetTopicInfo(self.topic); return py::str("") .format(topicInfo.name, topicInfo.type_str, self.value); }) - nt::LogMessage: + wpi::nt::LogMessage: attributes: level: filename: @@ -115,7 +115,7 @@ classes: ignore: true unsigned int, std::string_view, unsigned int, std::string_view: ignore: true - nt::TimeSyncEventData: + wpi::nt::TimeSyncEventData: attributes: serverTimeOffset: rtt2: @@ -126,7 +126,7 @@ classes: '': ignore: true int64_t, int64_t, bool: - nt::Event: + wpi::nt::Event: attributes: listener: flags: @@ -184,14 +184,14 @@ classes: '': ignore: true inline_code: | - .def_property_readonly("data", [](nt::Event *self){ + .def_property_readonly("data", [](wpi::nt::Event *self){ return self->data; }) - .def("__repr__", [](const nt::Event &self) -> py::str { + .def("__repr__", [](const wpi::nt::Event &self) -> py::str { return py::str("") .format(self.listener, self.flags, self.data); }) - nt::PubSubOptions: + wpi::nt::PubSubOptions: force_no_default_constructor: true attributes: kDefaultPeriodic: @@ -213,7 +213,7 @@ classes: .def(py::init([]( unsigned int pollStorage, double periodic, - std::optional> excludePublisher, + std::optional> excludePublisher, bool sendAll, bool topicsOnly, bool keepDuplicates, @@ -222,8 +222,8 @@ classes: bool disableLocal, bool excludeSelf, bool hidden - ) -> nt::PubSubOptions { - return nt::PubSubOptions{ + ) -> wpi::nt::PubSubOptions { + return wpi::nt::PubSubOptions{ .pollStorage = pollStorage, .periodic = periodic, .excludePublisher = excludePublisher.has_value() ? excludePublisher.value()->GetHandle() : 0, @@ -239,7 +239,7 @@ classes: }), py::kw_only(), py::arg("pollStorage") = 0, - py::arg("periodic") = nt::PubSubOptions::kDefaultPeriodic, + py::arg("periodic") = wpi::nt::PubSubOptions::kDefaultPeriodic, py::arg("excludePublisher") = std::nullopt, py::arg("sendAll") = false, py::arg("topicsOnly") = false, @@ -280,36 +280,36 @@ classes: will not appear in metatopics. )" ) - nt::meta::SubscriberOptions: + wpi::nt::meta::SubscriberOptions: subpackage: meta attributes: periodic: topicsOnly: sendAll: prefixMatch: - nt::meta::TopicPublisher: + wpi::nt::meta::TopicPublisher: subpackage: meta attributes: client: pubuid: - nt::meta::TopicSubscriber: + wpi::nt::meta::TopicSubscriber: subpackage: meta attributes: client: subuid: options: - nt::meta::ClientPublisher: + wpi::nt::meta::ClientPublisher: subpackage: meta attributes: uid: topic: - nt::meta::ClientSubscriber: + wpi::nt::meta::ClientSubscriber: subpackage: meta attributes: uid: topics: options: - nt::meta::Client: + wpi::nt::meta::Client: subpackage: meta attributes: id: diff --git a/ntcore/src/main/python/semiwrap/ntcore_cpp_types.yml b/ntcore/src/main/python/semiwrap/ntcore_cpp_types.yml index 0fddb11e91..aa31e612c7 100644 --- a/ntcore/src/main/python/semiwrap/ntcore_cpp_types.yml +++ b/ntcore/src/main/python/semiwrap/ntcore_cpp_types.yml @@ -6,7 +6,7 @@ defaults: report_ignored_missing: false classes: - nt::Timestamped: + wpi::nt::Timestamped: template_params: - T attributes: @@ -29,54 +29,54 @@ classes: templates: TimestampedBoolean: - qualname: nt::Timestamped + qualname: wpi::nt::Timestamped params: - bool TimestampedInteger: - qualname: nt::Timestamped + qualname: wpi::nt::Timestamped params: - int64_t TimestampedFloat: - qualname: nt::Timestamped + qualname: wpi::nt::Timestamped params: - float TimestampedDouble: - qualname: nt::Timestamped + qualname: wpi::nt::Timestamped params: - double TimestampedString: - qualname: nt::Timestamped + qualname: wpi::nt::Timestamped params: - std::string TimestampedRaw: - qualname: nt::Timestamped + qualname: wpi::nt::Timestamped params: - std::vector TimestampedBooleanArray: - qualname: nt::Timestamped + qualname: wpi::nt::Timestamped params: - std::vector TimestampedIntegerArray: - qualname: nt::Timestamped + qualname: wpi::nt::Timestamped params: - std::vector TimestampedFloatArray: - qualname: nt::Timestamped + qualname: wpi::nt::Timestamped params: - std::vector TimestampedDoubleArray: - qualname: nt::Timestamped + qualname: wpi::nt::Timestamped params: - std::vector TimestampedStringArray: - qualname: nt::Timestamped + qualname: wpi::nt::Timestamped params: - std::vector TimestampedStruct: - qualname: nt::Timestamped + qualname: wpi::nt::Timestamped params: - WPyStruct TimestampedStructArray: - qualname: nt::Timestamped + qualname: wpi::nt::Timestamped params: - std::vector diff --git a/ntcore/src/test/native/cpp/ConnectionListenerTest.cpp b/ntcore/src/test/native/cpp/ConnectionListenerTest.cpp index 186f61c0b8..209601f563 100644 --- a/ntcore/src/test/native/cpp/ConnectionListenerTest.cpp +++ b/ntcore/src/test/native/cpp/ConnectionListenerTest.cpp @@ -16,11 +16,11 @@ class ConnectionListenerTest : public ::testing::Test { public: ConnectionListenerTest() - : server_inst(nt::CreateInstance()), client_inst(nt::CreateInstance()) {} + : server_inst(wpi::nt::CreateInstance()), client_inst(wpi::nt::CreateInstance()) {} ~ConnectionListenerTest() override { - nt::DestroyInstance(server_inst); - nt::DestroyInstance(client_inst); + wpi::nt::DestroyInstance(server_inst); + wpi::nt::DestroyInstance(client_inst); } void Connect(const char* address, unsigned int port4); @@ -31,13 +31,13 @@ class ConnectionListenerTest : public ::testing::Test { }; void ConnectionListenerTest::Connect(const char* address, unsigned int port4) { - nt::StartServer(server_inst, "connectionlistenertest.ini", address, port4); - nt::StartClient(client_inst, "client"); - nt::SetServer(client_inst, address, port4); + wpi::nt::StartServer(server_inst, "connectionlistenertest.ini", address, port4); + wpi::nt::StartClient(client_inst, "client"); + wpi::nt::SetServer(client_inst, address, port4); // wait for client to report it's connected, then wait another 0.1 sec int count = 0; - while (!nt::IsConnected(client_inst)) { + while (!wpi::nt::IsConnected(client_inst)) { std::this_thread::sleep_for(std::chrono::milliseconds(100)); if (++count > 30) { FAIL() << "timed out waiting for client to start"; @@ -48,10 +48,10 @@ void ConnectionListenerTest::Connect(const char* address, unsigned int port4) { TEST_F(ConnectionListenerTest, Polled) { // set up the poller - NT_ListenerPoller poller = nt::CreateListenerPoller(server_inst); + NT_ListenerPoller poller = wpi::nt::CreateListenerPoller(server_inst); ASSERT_NE(poller, 0u); NT_Listener handle = - nt::AddPolledListener(poller, server_inst, nt::EventFlags::kConnection); + wpi::nt::AddPolledListener(poller, server_inst, wpi::nt::EventFlags::kConnection); ASSERT_NE(handle, 0u); // trigger a connect event @@ -59,27 +59,27 @@ TEST_F(ConnectionListenerTest, Polled) { // get the event bool timed_out = false; - ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timed_out)); + ASSERT_TRUE(wpi::util::WaitForObject(poller, 1.0, &timed_out)); ASSERT_FALSE(timed_out); - auto result = nt::ReadListenerQueue(poller); + auto result = wpi::nt::ReadListenerQueue(poller); ASSERT_EQ(result.size(), 1u); EXPECT_EQ(handle, result[0].listener); EXPECT_TRUE(result[0].GetConnectionInfo()); - EXPECT_EQ(result[0].flags, nt::EventFlags::kConnected); + EXPECT_EQ(result[0].flags, wpi::nt::EventFlags::kConnected); // trigger a disconnect event - nt::StopClient(client_inst); + wpi::nt::StopClient(client_inst); std::this_thread::sleep_for(std::chrono::milliseconds(100)); // get the event timed_out = false; - ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timed_out)); + ASSERT_TRUE(wpi::util::WaitForObject(poller, 1.0, &timed_out)); ASSERT_FALSE(timed_out); - result = nt::ReadListenerQueue(poller); + result = wpi::nt::ReadListenerQueue(poller); ASSERT_EQ(result.size(), 1u); EXPECT_EQ(handle, result[0].listener); EXPECT_TRUE(result[0].GetConnectionInfo()); - EXPECT_EQ(result[0].flags, nt::EventFlags::kDisconnected); + EXPECT_EQ(result[0].flags, wpi::nt::EventFlags::kDisconnected); } class ConnectionListenerVariantTest @@ -87,9 +87,9 @@ class ConnectionListenerVariantTest public ::testing::WithParamInterface> {}; TEST_P(ConnectionListenerVariantTest, Threaded) { - wpi::mutex m; - std::vector result; - auto handle = nt::AddListener(server_inst, nt::EventFlags::kConnection, + wpi::util::mutex m; + std::vector result; + auto handle = wpi::nt::AddListener(server_inst, wpi::nt::EventFlags::kConnection, [&](auto& event) { std::scoped_lock lock{m}; result.push_back(event); @@ -99,7 +99,7 @@ TEST_P(ConnectionListenerVariantTest, Threaded) { Connect(GetParam().first, 20001 + GetParam().second); bool timed_out = false; - ASSERT_TRUE(wpi::WaitForObject(handle, 1.0, &timed_out)); + ASSERT_TRUE(wpi::util::WaitForObject(handle, 1.0, &timed_out)); ASSERT_FALSE(timed_out); // get the event @@ -108,16 +108,16 @@ TEST_P(ConnectionListenerVariantTest, Threaded) { ASSERT_EQ(result.size(), 1u); EXPECT_EQ(handle, result[0].listener); EXPECT_TRUE(result[0].GetConnectionInfo()); - EXPECT_EQ(result[0].flags, nt::EventFlags::kConnected); + EXPECT_EQ(result[0].flags, wpi::nt::EventFlags::kConnected); result.clear(); } // trigger a disconnect event - nt::StopClient(client_inst); + wpi::nt::StopClient(client_inst); std::this_thread::sleep_for(std::chrono::milliseconds(100)); // wait for thread - nt::WaitForListenerQueue(server_inst, 1.0); + wpi::nt::WaitForListenerQueue(server_inst, 1.0); // get the event { @@ -125,7 +125,7 @@ TEST_P(ConnectionListenerVariantTest, Threaded) { ASSERT_EQ(result.size(), 1u); EXPECT_EQ(handle, result[0].listener); EXPECT_TRUE(result[0].GetConnectionInfo()); - EXPECT_EQ(result[0].flags, nt::EventFlags::kDisconnected); + EXPECT_EQ(result[0].flags, wpi::nt::EventFlags::kDisconnected); } } diff --git a/ntcore/src/test/native/cpp/LocalStorageTest.cpp b/ntcore/src/test/native/cpp/LocalStorageTest.cpp index 28f8ad015b..bae92b07f8 100644 --- a/ntcore/src/test/native/cpp/LocalStorageTest.cpp +++ b/ntcore/src/test/native/cpp/LocalStorageTest.cpp @@ -28,7 +28,7 @@ using ::testing::IsEmpty; using ::testing::Property; using ::testing::Return; -namespace nt { +namespace wpi::nt { ::testing::Matcher IsPubSubOptions( const PubSubOptionsImpl& good) { @@ -80,7 +80,7 @@ TEST_F(LocalStorageTest, GetEntryEmptyName) { } TEST_F(LocalStorageTest, GetEntryCached) { - EXPECT_CALL(network, ClientSubscribe(_, wpi::SpanEq({std::string{"tocache"}}), + EXPECT_CALL(network, ClientSubscribe(_, wpi::util::SpanEq({std::string{"tocache"}}), IsDefaultPubSubOptions())); auto entry1 = storage.GetEntry("tocache"); @@ -109,8 +109,8 @@ TEST_F(LocalStorageTest, DefaultProps) { EXPECT_CALL( network, ClientPublish(_, std::string_view{"foo"}, std::string_view{"boolean"}, - wpi::json::object(), IsDefaultPubSubOptions())); - storage.Publish(fooTopic, NT_BOOLEAN, "boolean", wpi::json::object(), {}); + wpi::util::json::object(), IsDefaultPubSubOptions())); + storage.Publish(fooTopic, NT_BOOLEAN, "boolean", wpi::util::json::object(), {}); EXPECT_FALSE(storage.GetTopicPersistent(fooTopic)); EXPECT_FALSE(storage.GetTopicRetained(fooTopic)); @@ -121,8 +121,8 @@ TEST_F(LocalStorageTest, PublishNewNoProps) { EXPECT_CALL( network, ClientPublish(_, std::string_view{"foo"}, std::string_view{"boolean"}, - wpi::json::object(), IsDefaultPubSubOptions())); - storage.Publish(fooTopic, NT_BOOLEAN, "boolean", wpi::json::object(), {}); + wpi::util::json::object(), IsDefaultPubSubOptions())); + storage.Publish(fooTopic, NT_BOOLEAN, "boolean", wpi::util::json::object(), {}); auto info = storage.GetTopicInfo(fooTopic); EXPECT_EQ(info.properties, "{}"); @@ -132,7 +132,7 @@ TEST_F(LocalStorageTest, PublishNewNoPropsNull) { EXPECT_CALL( network, ClientPublish(_, std::string_view{"foo"}, std::string_view{"boolean"}, - wpi::json::object(), IsDefaultPubSubOptions())); + wpi::util::json::object(), IsDefaultPubSubOptions())); storage.Publish(fooTopic, NT_BOOLEAN, "boolean", {}, {}); auto info = storage.GetTopicInfo(fooTopic); @@ -140,7 +140,7 @@ TEST_F(LocalStorageTest, PublishNewNoPropsNull) { } TEST_F(LocalStorageTest, PublishNew) { - wpi::json properties = {{"persistent", true}}; + wpi::util::json properties = {{"persistent", true}}; EXPECT_CALL(network, ClientPublish(_, std::string_view{"foo"}, std::string_view{"boolean"}, properties, IsDefaultPubSubOptions())); @@ -159,14 +159,14 @@ TEST_F(LocalStorageTest, PublishNew) { } TEST_F(LocalStorageTest, SubscribeNoTypeLocalPubPost) { - EXPECT_CALL(network, ClientSubscribe(_, wpi::SpanEq({std::string{"foo"}}), + EXPECT_CALL(network, ClientSubscribe(_, wpi::util::SpanEq({std::string{"foo"}}), IsDefaultPubSubOptions())); auto sub = storage.Subscribe(fooTopic, NT_UNASSIGNED, "", {}); EXPECT_CALL( network, ClientPublish(_, std::string_view{"foo"}, std::string_view{"boolean"}, - wpi::json::object(), IsDefaultPubSubOptions())); + wpi::util::json::object(), IsDefaultPubSubOptions())); auto pub = storage.Publish(fooTopic, NT_BOOLEAN, "boolean", {}, {}); auto val = Value::MakeBoolean(true, 5); @@ -199,14 +199,14 @@ TEST_F(LocalStorageTest, SubscribeNoTypeLocalPubPre) { EXPECT_CALL( network, ClientPublish(_, std::string_view{"foo"}, std::string_view{"boolean"}, - wpi::json::object(), IsDefaultPubSubOptions())); + wpi::util::json::object(), IsDefaultPubSubOptions())); auto pub = storage.Publish(fooTopic, NT_BOOLEAN, "boolean", {}, {}); auto val = Value::MakeBoolean(true, 5); EXPECT_CALL(network, ClientSetValue(Handle{pub}.GetIndex(), val)); storage.SetEntryValue(pub, val); - EXPECT_CALL(network, ClientSubscribe(_, wpi::SpanEq({std::string{"foo"}}), + EXPECT_CALL(network, ClientSubscribe(_, wpi::util::SpanEq({std::string{"foo"}}), IsDefaultPubSubOptions())); auto sub = storage.Subscribe(fooTopic, NT_UNASSIGNED, "", {}); @@ -221,7 +221,7 @@ TEST_F(LocalStorageTest, SubscribeNoTypeLocalPubPre) { } TEST_F(LocalStorageTest, EntryNoTypeLocalSet) { - EXPECT_CALL(network, ClientSubscribe(_, wpi::SpanEq({std::string{"foo"}}), + EXPECT_CALL(network, ClientSubscribe(_, wpi::util::SpanEq({std::string{"foo"}}), IsDefaultPubSubOptions())); auto entry = storage.GetEntry(fooTopic, NT_UNASSIGNED, "", {}); @@ -230,7 +230,7 @@ TEST_F(LocalStorageTest, EntryNoTypeLocalSet) { EXPECT_CALL( network, ClientPublish(_, std::string_view{"foo"}, std::string_view{"boolean"}, - wpi::json::object(), IsDefaultPubSubOptions())); + wpi::util::json::object(), IsDefaultPubSubOptions())); EXPECT_CALL(network, ClientSetValue(_, val)); EXPECT_TRUE(storage.SetEntryValue(entry, val)); @@ -268,14 +268,14 @@ TEST_F(LocalStorageTest, EntryNoTypeLocalSet) { } TEST_F(LocalStorageTest, PubUnpubPub) { - EXPECT_CALL(network, ClientSubscribe(_, wpi::SpanEq({std::string{"foo"}}), + EXPECT_CALL(network, ClientSubscribe(_, wpi::util::SpanEq({std::string{"foo"}}), IsDefaultPubSubOptions())); auto sub = storage.Subscribe(fooTopic, NT_INTEGER, "int", {}); EXPECT_CALL( network, ClientPublish(_, std::string_view{"foo"}, std::string_view{"boolean"}, - wpi::json::object(), IsDefaultPubSubOptions())); + wpi::util::json::object(), IsDefaultPubSubOptions())); EXPECT_CALL(logger, Call(NT_LOG_INFO, _, _, std::string_view{ @@ -302,7 +302,7 @@ TEST_F(LocalStorageTest, PubUnpubPub) { EXPECT_CALL(network, ClientPublish(_, std::string_view{"foo"}, std::string_view{"int"}, - wpi::json::object(), IsDefaultPubSubOptions())); + wpi::util::json::object(), IsDefaultPubSubOptions())); pub = storage.Publish(fooTopic, NT_INTEGER, "int", {}, {}); val = Value::MakeInteger(3, 5); @@ -320,7 +320,7 @@ TEST_F(LocalStorageTest, LocalPubConflict) { EXPECT_CALL( network, ClientPublish(_, std::string_view{"foo"}, std::string_view{"boolean"}, - wpi::json::object(), IsDefaultPubSubOptions())); + wpi::util::json::object(), IsDefaultPubSubOptions())); auto pub1 = storage.Publish(fooTopic, NT_BOOLEAN, "boolean", {}, {}); EXPECT_CALL( @@ -343,7 +343,7 @@ TEST_F(LocalStorageTest, LocalPubConflict) { EXPECT_CALL(network, ClientUnpublish(Handle{pub1}.GetIndex())); EXPECT_CALL(network, ClientPublish(_, std::string_view{"foo"}, std::string_view{"int"}, - wpi::json::object(), IsDefaultPubSubOptions())); + wpi::util::json::object(), IsDefaultPubSubOptions())); storage.Unpublish(pub1); EXPECT_EQ(storage.GetTopicType(fooTopic), NT_INTEGER); @@ -360,10 +360,10 @@ TEST_F(LocalStorageTest, LocalSubConflict) { EXPECT_CALL( network, ClientPublish(_, std::string_view{"foo"}, std::string_view{"boolean"}, - wpi::json::object(), IsDefaultPubSubOptions())); + wpi::util::json::object(), IsDefaultPubSubOptions())); storage.Publish(fooTopic, NT_BOOLEAN, "boolean", {}, {}); - EXPECT_CALL(network, ClientSubscribe(_, wpi::SpanEq({std::string{"foo"}}), + EXPECT_CALL(network, ClientSubscribe(_, wpi::util::SpanEq({std::string{"foo"}}), IsDefaultPubSubOptions())); EXPECT_CALL(logger, Call(NT_LOG_INFO, _, _, @@ -377,7 +377,7 @@ TEST_F(LocalStorageTest, RemotePubConflict) { EXPECT_CALL( network, ClientPublish(_, std::string_view{"foo"}, std::string_view{"boolean"}, - wpi::json::object(), IsDefaultPubSubOptions())); + wpi::util::json::object(), IsDefaultPubSubOptions())); storage.Publish(fooTopic, NT_BOOLEAN, "boolean", {}, {}); @@ -387,7 +387,7 @@ TEST_F(LocalStorageTest, RemotePubConflict) { "network announce of 'foo' overriding local publish " "(was 'boolean', now 'int')"})); - auto id = storage.ServerAnnounce("foo", 0, "int", wpi::json::object(), + auto id = storage.ServerAnnounce("foo", 0, "int", wpi::util::json::object(), std::nullopt); // network overrides local @@ -398,7 +398,7 @@ TEST_F(LocalStorageTest, RemotePubConflict) { EXPECT_CALL( network, ClientPublish(_, std::string_view{"foo"}, std::string_view{"boolean"}, - wpi::json::object(), IsDefaultPubSubOptions())); + wpi::util::json::object(), IsDefaultPubSubOptions())); storage.ServerUnannounce("foo", id); @@ -409,14 +409,14 @@ TEST_F(LocalStorageTest, RemotePubConflict) { TEST_F(LocalStorageTest, SubNonExist) { // makes sure no warning is emitted - EXPECT_CALL(network, ClientSubscribe(_, wpi::SpanEq({std::string{"foo"}}), + EXPECT_CALL(network, ClientSubscribe(_, wpi::util::SpanEq({std::string{"foo"}}), IsDefaultPubSubOptions())); storage.Subscribe(fooTopic, NT_BOOLEAN, "boolean", {}); } TEST_F(LocalStorageTest, SetDefaultSubscribe) { // no publish, no value on wire, this is just handled locally - EXPECT_CALL(network, ClientSubscribe(_, wpi::SpanEq({std::string{"foo"}}), + EXPECT_CALL(network, ClientSubscribe(_, wpi::util::SpanEq({std::string{"foo"}}), IsDefaultPubSubOptions())); auto sub = storage.Subscribe(fooTopic, NT_BOOLEAN, "boolean", {}); EXPECT_TRUE(storage.SetDefaultEntryValue(sub, Value::MakeBoolean(true))); @@ -430,7 +430,7 @@ TEST_F(LocalStorageTest, SetDefaultPublish) { EXPECT_CALL( network, ClientPublish(_, std::string_view{"foo"}, std::string_view{"boolean"}, - wpi::json::object(), IsDefaultPubSubOptions())); + wpi::util::json::object(), IsDefaultPubSubOptions())); auto pub = storage.Publish(fooTopic, NT_BOOLEAN, "boolean", {}, {}); // expect a value across the wire @@ -447,7 +447,7 @@ TEST_F(LocalStorageTest, SetDefaultPublish) { } TEST_F(LocalStorageTest, SetDefaultEntry) { - EXPECT_CALL(network, ClientSubscribe(_, wpi::SpanEq({std::string{"foo"}}), + EXPECT_CALL(network, ClientSubscribe(_, wpi::util::SpanEq({std::string{"foo"}}), IsDefaultPubSubOptions())); auto entry = storage.GetEntry(fooTopic, NT_BOOLEAN, "boolean", {}); @@ -455,7 +455,7 @@ TEST_F(LocalStorageTest, SetDefaultEntry) { EXPECT_CALL( network, ClientPublish(_, std::string_view{"foo"}, std::string_view{"boolean"}, - wpi::json::object(), IsDefaultPubSubOptions())); + wpi::util::json::object(), IsDefaultPubSubOptions())); auto expectVal = Value::MakeBoolean(true, 0); EXPECT_CALL(network, ClientSetValue(_, expectVal)); EXPECT_TRUE(storage.SetDefaultEntryValue(entry, Value::MakeBoolean(true))); @@ -467,7 +467,7 @@ TEST_F(LocalStorageTest, SetDefaultEntry) { } TEST_F(LocalStorageTest, SetDefaultEntryUnassigned) { - EXPECT_CALL(network, ClientSubscribe(_, wpi::SpanEq({std::string{"foo"}}), + EXPECT_CALL(network, ClientSubscribe(_, wpi::util::SpanEq({std::string{"foo"}}), IsDefaultPubSubOptions())); auto entry = storage.GetEntry(fooTopic, NT_UNASSIGNED, "", {}); @@ -475,7 +475,7 @@ TEST_F(LocalStorageTest, SetDefaultEntryUnassigned) { EXPECT_CALL( network, ClientPublish(_, std::string_view{"foo"}, std::string_view{"boolean"}, - wpi::json::object(), IsDefaultPubSubOptions())); + wpi::util::json::object(), IsDefaultPubSubOptions())); auto expectVal = Value::MakeBoolean(true, 0); EXPECT_CALL(network, ClientSetValue(_, expectVal)); EXPECT_TRUE(storage.SetDefaultEntryValue(entry, Value::MakeBoolean(true))); @@ -491,7 +491,7 @@ TEST_F(LocalStorageTest, SetDefaultEntryDiffType) { EXPECT_CALL( network, ClientPublish(_, std::string_view{"foo"}, std::string_view{"string"}, - wpi::json::object(), IsDefaultPubSubOptions())); + wpi::util::json::object(), IsDefaultPubSubOptions())); auto pub = storage.Publish(fooTopic, NT_STRING, "string", {}, {}); EXPECT_FALSE(storage.SetDefaultEntryValue(pub, Value::MakeBoolean(true))); @@ -502,14 +502,14 @@ TEST_F(LocalStorageTest, SetValueEmptyValue) { EXPECT_CALL( network, ClientPublish(_, std::string_view{"foo"}, std::string_view{"string"}, - wpi::json::object(), IsDefaultPubSubOptions())); + wpi::util::json::object(), IsDefaultPubSubOptions())); auto pub = storage.Publish(fooTopic, NT_STRING, "string", {}, {}); EXPECT_FALSE(storage.SetEntryValue(pub, {})); } TEST_F(LocalStorageTest, SetValueEmptyUntypedEntry) { - EXPECT_CALL(network, ClientSubscribe(_, wpi::SpanEq({std::string{"foo"}}), + EXPECT_CALL(network, ClientSubscribe(_, wpi::util::SpanEq({std::string{"foo"}}), IsDefaultPubSubOptions())); auto entry = storage.GetEntry(fooTopic, NT_UNASSIGNED, "", {}); EXPECT_FALSE(storage.SetEntryValue(entry, {})); @@ -546,14 +546,14 @@ void LocalStorageDuplicatesTest::SetupPubSub(bool keepPub, bool keepSub) { EXPECT_CALL( network, ClientPublish(_, std::string_view{"foo"}, std::string_view{"double"}, - wpi::json::object(), IsPubSubOptions(pubOptions))); + wpi::util::json::object(), IsPubSubOptions(pubOptions))); pub = storage.Publish(fooTopic, NT_DOUBLE, "double", {}, {.keepDuplicates = keepPub}); PubSubOptionsImpl subOptions; subOptions.pollStorage = 10; subOptions.keepDuplicates = keepSub; - EXPECT_CALL(network, ClientSubscribe(_, wpi::SpanEq({std::string{"foo"}}), + EXPECT_CALL(network, ClientSubscribe(_, wpi::util::SpanEq({std::string{"foo"}}), IsPubSubOptions(subOptions))); sub = storage.Subscribe(fooTopic, NT_DOUBLE, "double", {.pollStorage = 10, .keepDuplicates = keepSub}); @@ -836,7 +836,7 @@ TEST_F(LocalStorageNumberVariantsTest, GetAtomic) { template ::testing::Matcher TSSpanEq(std::span value, int64_t time) { return AllOf( - Field("value", &T::value, wpi::SpanEq(std::span(value))), + Field("value", &T::value, wpi::util::SpanEq(std::span(value))), Field("time", &T::time, time)); } @@ -927,15 +927,15 @@ TEST_F(LocalStorageTest, MultiSubSpecial) { EXPECT_CALL( listenerStorage, - Notify(wpi::SpanEq(std::span{{2}}), _, _, _, _)); + Notify(wpi::util::SpanEq(std::span{{2}}), _, _, _, _)); storage.SetEntryValue(pubspecial, Value::MakeDouble(1.0, 30)); EXPECT_CALL( listenerStorage, - Notify(wpi::SpanEq(std::span{{1}}), _, _, _, _)); + Notify(wpi::util::SpanEq(std::span{{1}}), _, _, _, _)); EXPECT_CALL( listenerStorage, - Notify(wpi::SpanEq(std::span{{2}}), _, _, _, _)); + Notify(wpi::util::SpanEq(std::span{{2}}), _, _, _, _)); storage.SetEntryValue(pubnormal, Value::MakeDouble(2.0, 40)); } @@ -943,7 +943,7 @@ TEST_F(LocalStorageTest, NetworkDuplicateDetect) { EXPECT_CALL(network, ClientPublish(_, _, _, _, _)); auto pub = storage.Publish(fooTopic, NT_DOUBLE, "double", {}, {}); auto remoteTopic = storage.ServerAnnounce("foo", 0, "double", - wpi::json::object(), std::nullopt); + wpi::util::json::object(), std::nullopt); // local set EXPECT_CALL(network, ClientSetValue(_, _)); @@ -969,7 +969,7 @@ TEST_F(LocalStorageTest, ReadQueueLocalRemote) { storage.Subscribe(fooTopic, NT_DOUBLE, "double", {.disableLocal = true}); auto pub = storage.Publish(fooTopic, NT_DOUBLE, "double", {}, {}); auto remoteTopic = storage.ServerAnnounce("foo", 0, "double", - wpi::json::object(), std::nullopt); + wpi::util::json::object(), std::nullopt); // local set EXPECT_CALL(network, ClientSetValue(_, _)); @@ -998,7 +998,7 @@ TEST_F(LocalStorageTest, SubExcludePub) { auto subExclude = storage.Subscribe(fooTopic, NT_DOUBLE, "double", {.excludePublisher = pub}); auto remoteTopic = storage.ServerAnnounce("foo", 0, "double", - wpi::json::object(), std::nullopt); + wpi::util::json::object(), std::nullopt); // local set EXPECT_CALL(network, ClientSetValue(_, _)); @@ -1021,7 +1021,7 @@ TEST_F(LocalStorageTest, EntryExcludeSelf) { auto entry = storage.GetEntry(fooTopic, NT_DOUBLE, "double", {.excludeSelf = true}); auto remoteTopic = storage.ServerAnnounce("foo", 0, "double", - wpi::json::object(), std::nullopt); + wpi::util::json::object(), std::nullopt); // local set EXPECT_CALL(network, ClientPublish(_, _, _, _, _)); @@ -1061,7 +1061,7 @@ TEST_F(LocalStorageTest, ReadQueueInitialRemote) { EXPECT_CALL(network, ClientSubscribe(_, _, _)).Times(3); auto remoteTopic = storage.ServerAnnounce("foo", 0, "double", - wpi::json::object(), std::nullopt); + wpi::util::json::object(), std::nullopt); storage.ServerSetValue(remoteTopic, Value::MakeDouble(2.0, 60)); auto subBoth = @@ -1079,4 +1079,4 @@ TEST_F(LocalStorageTest, ReadQueueInitialRemote) { EXPECT_THAT(storage.ReadQueue(subLocal), IsEmpty()); } -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/test/native/cpp/LoggerTest.cpp b/ntcore/src/test/native/cpp/LoggerTest.cpp index 488098022d..9a7fc19382 100644 --- a/ntcore/src/test/native/cpp/LoggerTest.cpp +++ b/ntcore/src/test/native/cpp/LoggerTest.cpp @@ -13,12 +13,12 @@ class LoggerTest : public ::testing::Test { public: - LoggerTest() : m_inst(nt::CreateInstance()) {} + LoggerTest() : m_inst(wpi::nt::CreateInstance()) {} - ~LoggerTest() override { nt::DestroyInstance(m_inst); } + ~LoggerTest() override { wpi::nt::DestroyInstance(m_inst); } void Generate(); - void Check(const std::vector& events, NT_Listener handle, + void Check(const std::vector& events, NT_Listener handle, bool infoMsg, bool errMsg); protected: @@ -27,21 +27,21 @@ class LoggerTest : public ::testing::Test { void LoggerTest::Generate() { // generate info message - nt::StartClient(m_inst, ""); + wpi::nt::StartClient(m_inst, ""); // generate error message - nt::Publish(nt::Handle(nt::Handle{m_inst}.GetInst(), 5, nt::Handle::kTopic), + wpi::nt::Publish(wpi::nt::Handle(wpi::nt::Handle{m_inst}.GetInst(), 5, wpi::nt::Handle::kTopic), NT_DOUBLE, ""); } -void LoggerTest::Check(const std::vector& events, NT_Listener handle, +void LoggerTest::Check(const std::vector& events, NT_Listener handle, bool infoMsg, bool errMsg) { size_t count = (infoMsg ? 1u : 0u) + (errMsg ? 1u : 0u); ASSERT_EQ(events.size(), count); for (size_t i = 0; i < count; ++i) { ASSERT_EQ(events[i].listener, handle); - ASSERT_EQ(events[i].flags & nt::EventFlags::kLogMessage, - nt::EventFlags::kLogMessage); + ASSERT_EQ(events[i].flags & wpi::nt::EventFlags::kLogMessage, + wpi::nt::EventFlags::kLogMessage); auto log = events[i].GetLogMessage(); ASSERT_TRUE(log); if (infoMsg) { @@ -58,41 +58,41 @@ void LoggerTest::Check(const std::vector& events, NT_Listener handle, } TEST_F(LoggerTest, DefaultLogRange) { - auto poller = nt::CreateListenerPoller(m_inst); + auto poller = wpi::nt::CreateListenerPoller(m_inst); auto handle = - nt::AddPolledListener(poller, m_inst, nt::EventFlags::kLogMessage); + wpi::nt::AddPolledListener(poller, m_inst, wpi::nt::EventFlags::kLogMessage); Generate(); bool timedOut = false; - ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut)); - auto events = nt::ReadListenerQueue(poller); + ASSERT_TRUE(wpi::util::WaitForObject(poller, 1.0, &timedOut)); + auto events = wpi::nt::ReadListenerQueue(poller); Check(events, handle, true, true); } TEST_F(LoggerTest, InfoOnly) { - auto poller = nt::CreateListenerPoller(m_inst); - auto handle = nt::AddPolledLogger(poller, NT_LOG_INFO, NT_LOG_INFO); + auto poller = wpi::nt::CreateListenerPoller(m_inst); + auto handle = wpi::nt::AddPolledLogger(poller, NT_LOG_INFO, NT_LOG_INFO); Generate(); bool timedOut = false; - ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut)); - auto events = nt::ReadListenerQueue(poller); + ASSERT_TRUE(wpi::util::WaitForObject(poller, 1.0, &timedOut)); + auto events = wpi::nt::ReadListenerQueue(poller); Check(events, handle, true, false); } TEST_F(LoggerTest, Error) { - auto poller = nt::CreateListenerPoller(m_inst); - auto handle = nt::AddPolledLogger(poller, NT_LOG_ERROR, 100); + auto poller = wpi::nt::CreateListenerPoller(m_inst); + auto handle = wpi::nt::AddPolledLogger(poller, NT_LOG_ERROR, 100); Generate(); bool timedOut = false; - ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut)); - auto events = nt::ReadListenerQueue(poller); + ASSERT_TRUE(wpi::util::WaitForObject(poller, 1.0, &timedOut)); + auto events = wpi::nt::ReadListenerQueue(poller); Check(events, handle, false, true); } diff --git a/ntcore/src/test/native/cpp/MockConnectionList.hpp b/ntcore/src/test/native/cpp/MockConnectionList.hpp index 97c5f6f109..837526208a 100644 --- a/ntcore/src/test/native/cpp/MockConnectionList.hpp +++ b/ntcore/src/test/native/cpp/MockConnectionList.hpp @@ -9,7 +9,7 @@ #include "IConnectionList.hpp" #include "gmock/gmock.h" -namespace nt { +namespace wpi::nt { class MockConnectionList : public IConnectionList { public: @@ -21,4 +21,4 @@ class MockConnectionList : public IConnectionList { MOCK_METHOD(bool, IsConnected, (), (const, override)); }; -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/test/native/cpp/MockListenerStorage.hpp b/ntcore/src/test/native/cpp/MockListenerStorage.hpp index 370923e9e0..8a5e081c98 100644 --- a/ntcore/src/test/native/cpp/MockListenerStorage.hpp +++ b/ntcore/src/test/native/cpp/MockListenerStorage.hpp @@ -11,7 +11,7 @@ #include "IListenerStorage.hpp" #include "gmock/gmock.h" -namespace nt { +namespace wpi::nt { class MockListenerStorage : public IListenerStorage { public: @@ -42,4 +42,4 @@ class MockListenerStorage : public IListenerStorage { (override)); }; -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/test/native/cpp/MockLogger.hpp b/ntcore/src/test/native/cpp/MockLogger.hpp index 616abb08d8..9aeeee31a9 100644 --- a/ntcore/src/test/native/cpp/MockLogger.hpp +++ b/ntcore/src/test/native/cpp/MockLogger.hpp @@ -9,7 +9,7 @@ namespace wpi { -class MockLogger : public Logger, +class MockLogger : public wpi::util::Logger, public ::testing::MockFunction { diff --git a/ntcore/src/test/native/cpp/NetworkTableTest.cpp b/ntcore/src/test/native/cpp/NetworkTableTest.cpp index 9ffab514d0..3b3fd0371d 100644 --- a/ntcore/src/test/native/cpp/NetworkTableTest.cpp +++ b/ntcore/src/test/native/cpp/NetworkTableTest.cpp @@ -14,94 +14,94 @@ class NetworkTableTest : public ::testing::Test {}; TEST_F(NetworkTableTest, BasenameKey) { - EXPECT_EQ("simple", nt::NetworkTable::BasenameKey("simple")); - EXPECT_EQ("simple", nt::NetworkTable::BasenameKey("one/two/many/simple")); + EXPECT_EQ("simple", wpi::nt::NetworkTable::BasenameKey("simple")); + EXPECT_EQ("simple", wpi::nt::NetworkTable::BasenameKey("one/two/many/simple")); EXPECT_EQ("simple", - nt::NetworkTable::BasenameKey("//////an/////awful/key////simple")); + wpi::nt::NetworkTable::BasenameKey("//////an/////awful/key////simple")); } TEST_F(NetworkTableTest, NormalizeKeySlash) { - EXPECT_EQ("/", nt::NetworkTable::NormalizeKey("///")); - EXPECT_EQ("/no/normal/req", nt::NetworkTable::NormalizeKey("/no/normal/req")); + EXPECT_EQ("/", wpi::nt::NetworkTable::NormalizeKey("///")); + EXPECT_EQ("/no/normal/req", wpi::nt::NetworkTable::NormalizeKey("/no/normal/req")); EXPECT_EQ("/no/leading/slash", - nt::NetworkTable::NormalizeKey("no/leading/slash")); - EXPECT_EQ("/what/an/awful/key/", nt::NetworkTable::NormalizeKey( + wpi::nt::NetworkTable::NormalizeKey("no/leading/slash")); + EXPECT_EQ("/what/an/awful/key/", wpi::nt::NetworkTable::NormalizeKey( "//////what////an/awful/////key///")); } TEST_F(NetworkTableTest, NormalizeKeyNoSlash) { - EXPECT_EQ("a", nt::NetworkTable::NormalizeKey("a", false)); - EXPECT_EQ("a", nt::NetworkTable::NormalizeKey("///a", false)); + EXPECT_EQ("a", wpi::nt::NetworkTable::NormalizeKey("a", false)); + EXPECT_EQ("a", wpi::nt::NetworkTable::NormalizeKey("///a", false)); EXPECT_EQ("leading/slash", - nt::NetworkTable::NormalizeKey("/leading/slash", false)); + wpi::nt::NetworkTable::NormalizeKey("/leading/slash", false)); EXPECT_EQ("no/leading/slash", - nt::NetworkTable::NormalizeKey("no/leading/slash", false)); + wpi::nt::NetworkTable::NormalizeKey("no/leading/slash", false)); EXPECT_EQ("what/an/awful/key/", - nt::NetworkTable::NormalizeKey("//////what////an/awful/////key///", + wpi::nt::NetworkTable::NormalizeKey("//////what////an/awful/////key///", false)); } TEST_F(NetworkTableTest, GetHierarchyEmpty) { std::vector expected{"/"}; - ASSERT_EQ(expected, nt::NetworkTable::GetHierarchy("")); + ASSERT_EQ(expected, wpi::nt::NetworkTable::GetHierarchy("")); } TEST_F(NetworkTableTest, GetHierarchyRoot) { std::vector expected{"/"}; - ASSERT_EQ(expected, nt::NetworkTable::GetHierarchy("/")); + ASSERT_EQ(expected, wpi::nt::NetworkTable::GetHierarchy("/")); } TEST_F(NetworkTableTest, GetHierarchyNormal) { std::vector expected{"/", "/foo", "/foo/bar", "/foo/bar/baz"}; - ASSERT_EQ(expected, nt::NetworkTable::GetHierarchy("/foo/bar/baz")); + ASSERT_EQ(expected, wpi::nt::NetworkTable::GetHierarchy("/foo/bar/baz")); } TEST_F(NetworkTableTest, GetHierarchyTrailingSlash) { std::vector expected{"/", "/foo", "/foo/bar", "/foo/bar/"}; - ASSERT_EQ(expected, nt::NetworkTable::GetHierarchy("/foo/bar/")); + ASSERT_EQ(expected, wpi::nt::NetworkTable::GetHierarchy("/foo/bar/")); } TEST_F(NetworkTableTest, ContainsKey) { - auto inst = nt::NetworkTableInstance::Create(); + auto inst = wpi::nt::NetworkTableInstance::Create(); auto nt = inst.GetTable("containskey"); ASSERT_FALSE(nt->ContainsKey("testkey")); nt->PutNumber("testkey", 5); ASSERT_TRUE(nt->ContainsKey("testkey")); ASSERT_TRUE(inst.GetEntry("/containskey/testkey").Exists()); ASSERT_FALSE(inst.GetEntry("containskey/testkey").Exists()); - nt::NetworkTableInstance::Destroy(inst); + wpi::nt::NetworkTableInstance::Destroy(inst); } TEST_F(NetworkTableTest, LeadingSlash) { - auto inst = nt::NetworkTableInstance::Create(); + auto inst = wpi::nt::NetworkTableInstance::Create(); auto nt = inst.GetTable("leadingslash"); auto nt2 = inst.GetTable("/leadingslash"); ASSERT_FALSE(nt->ContainsKey("testkey")); nt2->PutNumber("testkey", 5); ASSERT_TRUE(nt->ContainsKey("testkey")); ASSERT_TRUE(inst.GetEntry("/leadingslash/testkey").Exists()); - nt::NetworkTableInstance::Destroy(inst); + wpi::nt::NetworkTableInstance::Destroy(inst); } TEST_F(NetworkTableTest, EmptyOrNoSlash) { - auto inst = nt::NetworkTableInstance::Create(); + auto inst = wpi::nt::NetworkTableInstance::Create(); auto nt = inst.GetTable("/"); auto nt2 = inst.GetTable(""); ASSERT_FALSE(nt->ContainsKey("testkey")); nt2->PutNumber("testkey", 5); ASSERT_TRUE(nt->ContainsKey("testkey")); ASSERT_TRUE(inst.GetEntry("/testkey").Exists()); - nt::NetworkTableInstance::Destroy(inst); + wpi::nt::NetworkTableInstance::Destroy(inst); } TEST_F(NetworkTableTest, ResetInstance) { - auto inst = nt::NetworkTableInstance::Create(); + auto inst = wpi::nt::NetworkTableInstance::Create(); auto nt = inst.GetTable("containskey"); ASSERT_FALSE(nt->ContainsKey("testkey")); nt->PutNumber("testkey", 5); ASSERT_TRUE(nt->ContainsKey("testkey")); ASSERT_TRUE(inst.GetEntry("/containskey/testkey").Exists()); - nt::ResetInstance(inst.GetHandle()); + wpi::nt::ResetInstance(inst.GetHandle()); ASSERT_FALSE(nt->ContainsKey("testkey")); - nt::NetworkTableInstance::Destroy(inst); + wpi::nt::NetworkTableInstance::Destroy(inst); } diff --git a/ntcore/src/test/native/cpp/PubSubOptionsMatcher.cpp b/ntcore/src/test/native/cpp/PubSubOptionsMatcher.cpp index 6f7f5489d3..95670f3492 100644 --- a/ntcore/src/test/native/cpp/PubSubOptionsMatcher.cpp +++ b/ntcore/src/test/native/cpp/PubSubOptionsMatcher.cpp @@ -6,7 +6,7 @@ #include "TestPrinters.hpp" -namespace nt { +namespace wpi::nt { bool PubSubOptionsMatcher::MatchAndExplain( const PubSubOptionsImpl& val, @@ -40,4 +40,4 @@ void PubSubOptionsMatcher::DescribeNegationTo(::std::ostream* os) const { PrintTo(good, os); } -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/test/native/cpp/PubSubOptionsMatcher.hpp b/ntcore/src/test/native/cpp/PubSubOptionsMatcher.hpp index b43da2d7c9..c42ff995be 100644 --- a/ntcore/src/test/native/cpp/PubSubOptionsMatcher.hpp +++ b/ntcore/src/test/native/cpp/PubSubOptionsMatcher.hpp @@ -10,7 +10,7 @@ #include "PubSubOptions.hpp" #include "gmock/gmock.h" -namespace nt { +namespace wpi::nt { class PubSubOptionsMatcher : public ::testing::MatcherInterface { @@ -32,4 +32,4 @@ inline ::testing::Matcher PubSubOptionsEq( return ::testing::MakeMatcher(new PubSubOptionsMatcher(std::move(good))); } -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/test/native/cpp/StorageTest.hpp b/ntcore/src/test/native/cpp/StorageTest.hpp index c80fbf1891..cb662be149 100644 --- a/ntcore/src/test/native/cpp/StorageTest.hpp +++ b/ntcore/src/test/native/cpp/StorageTest.hpp @@ -12,7 +12,7 @@ #include "MockDispatcher.h" #include "Storage.h" -namespace nt { +namespace wpi::nt { class StorageTest { public: @@ -28,10 +28,10 @@ class StorageTest { void HookOutgoing(bool server) { storage.SetDispatcher(&dispatcher, server); } - wpi::Logger logger; + wpi::util::Logger logger; ::testing::StrictMock dispatcher; Storage storage; Storage::Entry tmp_entry; }; -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/test/native/cpp/StructTest.cpp b/ntcore/src/test/native/cpp/StructTest.cpp index b0c36b586e..b263c09fff 100644 --- a/ntcore/src/test/native/cpp/StructTest.cpp +++ b/ntcore/src/test/native/cpp/StructTest.cpp @@ -45,85 +45,85 @@ struct Info1 { } // namespace template <> -struct wpi::Struct { +struct wpi::util::Struct { static constexpr std::string_view GetTypeName() { return "Inner"; } static constexpr size_t GetSize() { return 8; } static constexpr std::string_view GetSchema() { return "int32 a; int32 b"; } static Inner Unpack(std::span data) { - return {wpi::UnpackStruct(data), - wpi::UnpackStruct(data)}; + return {wpi::util::UnpackStruct(data), + wpi::util::UnpackStruct(data)}; } static void Pack(std::span data, const Inner& value) { - wpi::PackStruct<0>(data, value.a); - wpi::PackStruct<4>(data, value.b); + wpi::util::PackStruct<0>(data, value.a); + wpi::util::PackStruct<4>(data, value.b); } }; template <> -struct wpi::Struct { +struct wpi::util::Struct { static constexpr std::string_view GetTypeName() { return "Outer"; } - static constexpr size_t GetSize() { return wpi::GetStructSize() + 4; } + static constexpr size_t GetSize() { return wpi::util::GetStructSize() + 4; } static constexpr std::string_view GetSchema() { return "Inner inner; int32 c"; } static Outer Unpack(std::span data) { - constexpr size_t innerSize = wpi::GetStructSize(); - return {wpi::UnpackStruct(data), - wpi::UnpackStruct(data)}; + constexpr size_t innerSize = wpi::util::GetStructSize(); + return {wpi::util::UnpackStruct(data), + wpi::util::UnpackStruct(data)}; } static void Pack(std::span data, const Outer& value) { - constexpr size_t innerSize = wpi::GetStructSize(); - wpi::PackStruct<0>(data, value.inner); - wpi::PackStruct(data, value.c); + constexpr size_t innerSize = wpi::util::GetStructSize(); + wpi::util::PackStruct<0>(data, value.inner); + wpi::util::PackStruct(data, value.c); } static void ForEachNested( std::invocable auto fn) { - wpi::ForEachStructSchema(fn); + wpi::util::ForEachStructSchema(fn); } }; template <> -struct wpi::Struct { +struct wpi::util::Struct { static std::string_view GetTypeName() { return "Inner2"; } static size_t GetSize() { return 8; } static std::string_view GetSchema() { return "int32 a; int32 b"; } static Inner2 Unpack(std::span data) { - return {wpi::UnpackStruct(data), - wpi::UnpackStruct(data)}; + return {wpi::util::UnpackStruct(data), + wpi::util::UnpackStruct(data)}; } static void Pack(std::span data, const Inner2& value) { - wpi::PackStruct<0>(data, value.a); - wpi::PackStruct<4>(data, value.b); + wpi::util::PackStruct<0>(data, value.a); + wpi::util::PackStruct<4>(data, value.b); } }; template <> -struct wpi::Struct { +struct wpi::util::Struct { static std::string_view GetTypeName() { return "Outer2"; } - static size_t GetSize() { return wpi::GetStructSize() + 4; } + static size_t GetSize() { return wpi::util::GetStructSize() + 4; } static std::string_view GetSchema() { return "Inner2 inner; int32 c"; } static Outer2 Unpack(std::span data) { - size_t innerSize = wpi::GetStructSize(); - return {wpi::UnpackStruct(data), - wpi::UnpackStruct(data.subspan(innerSize))}; + size_t innerSize = wpi::util::GetStructSize(); + return {wpi::util::UnpackStruct(data), + wpi::util::UnpackStruct(data.subspan(innerSize))}; } static void Pack(std::span data, const Outer2& value) { - size_t innerSize = wpi::GetStructSize(); - wpi::PackStruct<0>(data, value.inner); - wpi::PackStruct(data.subspan(innerSize), value.c); + size_t innerSize = wpi::util::GetStructSize(); + wpi::util::PackStruct<0>(data, value.inner); + wpi::util::PackStruct(data.subspan(innerSize), value.c); } static void ForEachNested( std::invocable auto fn) { - wpi::ForEachStructSchema(fn); + wpi::util::ForEachStructSchema(fn); } }; template <> -struct wpi::Struct { +struct wpi::util::Struct { static constexpr std::string_view GetTypeName() { return "ThingA"; } static constexpr size_t GetSize() { return 1; } static constexpr std::string_view GetSchema() { return "uint8 value"; } @@ -136,7 +136,7 @@ struct wpi::Struct { }; template <> -struct wpi::Struct { +struct wpi::util::Struct { static constexpr std::string_view GetTypeName(const Info1&) { return "ThingB"; } @@ -152,20 +152,20 @@ struct wpi::Struct { } }; -namespace nt { +namespace wpi::nt { class StructTest : public ::testing::Test { public: - StructTest() { inst = nt::NetworkTableInstance::Create(); } - ~StructTest() override { nt::NetworkTableInstance::Destroy(inst); } + StructTest() { inst = wpi::nt::NetworkTableInstance::Create(); } + ~StructTest() override { wpi::nt::NetworkTableInstance::Destroy(inst); } - nt::NetworkTableInstance inst; + wpi::nt::NetworkTableInstance inst; }; TEST_F(StructTest, InnerConstexpr) { - nt::StructTopic topic = inst.GetStructTopic("inner"); - nt::StructPublisher pub = topic.Publish(); - nt::StructSubscriber sub = topic.Subscribe({}); + wpi::nt::StructTopic topic = inst.GetStructTopic("inner"); + wpi::nt::StructPublisher pub = topic.Publish(); + wpi::nt::StructSubscriber sub = topic.Subscribe({}); ASSERT_EQ(topic.GetTypeString(), "struct:Inner"); @@ -191,9 +191,9 @@ TEST_F(StructTest, InnerConstexpr) { } TEST_F(StructTest, InnerNonconstexpr) { - nt::StructTopic topic = inst.GetStructTopic("inner2"); - nt::StructPublisher pub = topic.Publish(); - nt::StructSubscriber sub = topic.Subscribe({}); + wpi::nt::StructTopic topic = inst.GetStructTopic("inner2"); + wpi::nt::StructPublisher pub = topic.Publish(); + wpi::nt::StructSubscriber sub = topic.Subscribe({}); ASSERT_EQ(topic.GetTypeString(), "struct:Inner2"); @@ -219,9 +219,9 @@ TEST_F(StructTest, InnerNonconstexpr) { } TEST_F(StructTest, OuterConstexpr) { - nt::StructTopic topic = inst.GetStructTopic("outer"); - nt::StructPublisher pub = topic.Publish(); - nt::StructSubscriber sub = topic.Subscribe({}); + wpi::nt::StructTopic topic = inst.GetStructTopic("outer"); + wpi::nt::StructPublisher pub = topic.Publish(); + wpi::nt::StructSubscriber sub = topic.Subscribe({}); ASSERT_EQ(topic.GetTypeString(), "struct:Outer"); @@ -251,9 +251,9 @@ TEST_F(StructTest, OuterConstexpr) { } TEST_F(StructTest, OuterNonconstexpr) { - nt::StructTopic topic = inst.GetStructTopic("outer2"); - nt::StructPublisher pub = topic.Publish(); - nt::StructSubscriber sub = topic.Subscribe({}); + wpi::nt::StructTopic topic = inst.GetStructTopic("outer2"); + wpi::nt::StructPublisher pub = topic.Publish(); + wpi::nt::StructSubscriber sub = topic.Subscribe({}); ASSERT_EQ(topic.GetTypeString(), "struct:Outer2"); @@ -283,9 +283,9 @@ TEST_F(StructTest, OuterNonconstexpr) { } TEST_F(StructTest, InnerArrayConstexpr) { - nt::StructArrayTopic topic = inst.GetStructArrayTopic("innerA"); - nt::StructArrayPublisher pub = topic.Publish(); - nt::StructArraySubscriber sub = topic.Subscribe({}); + wpi::nt::StructArrayTopic topic = inst.GetStructArrayTopic("innerA"); + wpi::nt::StructArrayPublisher pub = topic.Publish(); + wpi::nt::StructArraySubscriber sub = topic.Subscribe({}); ASSERT_EQ(topic.GetTypeString(), "struct:Inner[]"); @@ -309,10 +309,10 @@ TEST_F(StructTest, InnerArrayConstexpr) { } TEST_F(StructTest, InnerArrayNonconstexpr) { - nt::StructArrayTopic topic = + wpi::nt::StructArrayTopic topic = inst.GetStructArrayTopic("innerA2"); - nt::StructArrayPublisher pub = topic.Publish(); - nt::StructArraySubscriber sub = topic.Subscribe({}); + wpi::nt::StructArrayPublisher pub = topic.Publish(); + wpi::nt::StructArraySubscriber sub = topic.Subscribe({}); ASSERT_EQ(topic.GetTypeString(), "struct:Inner2[]"); @@ -336,11 +336,11 @@ TEST_F(StructTest, InnerArrayNonconstexpr) { } TEST_F(StructTest, StructA) { - nt::StructTopic topic = inst.GetStructTopic("a"); - nt::StructPublisher pub = topic.Publish(); - nt::StructPublisher pub2 = topic.PublishEx({{}}); - nt::StructSubscriber sub = topic.Subscribe({}); - nt::StructEntry entry = topic.GetEntry({}); + wpi::nt::StructTopic topic = inst.GetStructTopic("a"); + wpi::nt::StructPublisher pub = topic.Publish(); + wpi::nt::StructPublisher pub2 = topic.PublishEx({{}}); + wpi::nt::StructSubscriber sub = topic.Subscribe({}); + wpi::nt::StructEntry entry = topic.GetEntry({}); pub.SetDefault({}); pub.Set({}, 5); sub.Get(); @@ -353,11 +353,11 @@ TEST_F(StructTest, StructA) { } TEST_F(StructTest, StructArrayA) { - nt::StructArrayTopic topic = inst.GetStructArrayTopic("a"); - nt::StructArrayPublisher pub = topic.Publish(); - nt::StructArrayPublisher pub2 = topic.PublishEx({{}}); - nt::StructArraySubscriber sub = topic.Subscribe({}); - nt::StructArrayEntry entry = topic.GetEntry({}); + wpi::nt::StructArrayTopic topic = inst.GetStructArrayTopic("a"); + wpi::nt::StructArrayPublisher pub = topic.Publish(); + wpi::nt::StructArrayPublisher pub2 = topic.PublishEx({{}}); + wpi::nt::StructArraySubscriber sub = topic.Subscribe({}); + wpi::nt::StructArrayEntry entry = topic.GetEntry({}); pub.SetDefault({{ThingA{}, ThingA{}}}); pub.Set({{ThingA{}, ThingA{}}}, 5); sub.Get(); @@ -370,12 +370,12 @@ TEST_F(StructTest, StructArrayA) { } TEST_F(StructTest, StructFixedArrayA) { - nt::StructTopic> topic = + wpi::nt::StructTopic> topic = inst.GetStructTopic>("a"); - nt::StructPublisher> pub = topic.Publish(); - nt::StructPublisher> pub2 = topic.PublishEx({{}}); - nt::StructSubscriber> sub = topic.Subscribe({}); - nt::StructEntry> entry = topic.GetEntry({}); + wpi::nt::StructPublisher> pub = topic.Publish(); + wpi::nt::StructPublisher> pub2 = topic.PublishEx({{}}); + wpi::nt::StructSubscriber> sub = topic.Subscribe({}); + wpi::nt::StructEntry> entry = topic.GetEntry({}); std::array arr; pub.SetDefault(arr); pub.Set(arr, 5); @@ -390,12 +390,12 @@ TEST_F(StructTest, StructFixedArrayA) { TEST_F(StructTest, StructB) { Info1 info; - nt::StructTopic topic = + wpi::nt::StructTopic topic = inst.GetStructTopic("b", info); - nt::StructPublisher pub = topic.Publish(); - nt::StructPublisher pub2 = topic.PublishEx({{}}); - nt::StructSubscriber sub = topic.Subscribe({}); - nt::StructEntry entry = topic.GetEntry({}); + wpi::nt::StructPublisher pub = topic.Publish(); + wpi::nt::StructPublisher pub2 = topic.PublishEx({{}}); + wpi::nt::StructSubscriber sub = topic.Subscribe({}); + wpi::nt::StructEntry entry = topic.GetEntry({}); pub.SetDefault({}); pub.Set({}, 5); sub.Get(); @@ -409,12 +409,12 @@ TEST_F(StructTest, StructB) { TEST_F(StructTest, StructArrayB) { Info1 info; - nt::StructArrayTopic topic = + wpi::nt::StructArrayTopic topic = inst.GetStructArrayTopic("b", info); - nt::StructArrayPublisher pub = topic.Publish(); - nt::StructArrayPublisher pub2 = topic.PublishEx({{}}); - nt::StructArraySubscriber sub = topic.Subscribe({}); - nt::StructArrayEntry entry = topic.GetEntry({}); + wpi::nt::StructArrayPublisher pub = topic.Publish(); + wpi::nt::StructArrayPublisher pub2 = topic.PublishEx({{}}); + wpi::nt::StructArraySubscriber sub = topic.Subscribe({}); + wpi::nt::StructArrayEntry entry = topic.GetEntry({}); pub.SetDefault({{ThingB{}, ThingB{}}}); pub.Set({{ThingB{}, ThingB{}}}, 5); sub.Get(); @@ -428,13 +428,13 @@ TEST_F(StructTest, StructArrayB) { TEST_F(StructTest, StructFixedArrayB) { Info1 info; - nt::StructTopic, Info1> topic = + wpi::nt::StructTopic, Info1> topic = inst.GetStructTopic, Info1>("b", info); - nt::StructPublisher, Info1> pub = topic.Publish(); - nt::StructPublisher, Info1> pub2 = + wpi::nt::StructPublisher, Info1> pub = topic.Publish(); + wpi::nt::StructPublisher, Info1> pub2 = topic.PublishEx({{}}); - nt::StructSubscriber, Info1> sub = topic.Subscribe({}); - nt::StructEntry, Info1> entry = topic.GetEntry({}); + wpi::nt::StructSubscriber, Info1> sub = topic.Subscribe({}); + wpi::nt::StructEntry, Info1> entry = topic.GetEntry({}); std::array arr; pub.SetDefault(arr); pub.Set(arr, 5); @@ -447,4 +447,4 @@ TEST_F(StructTest, StructFixedArrayB) { entry.Get(arr); } -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/test/native/cpp/TableListenerTest.cpp b/ntcore/src/test/native/cpp/TableListenerTest.cpp index 55586ee455..09f95baae3 100644 --- a/ntcore/src/test/native/cpp/TableListenerTest.cpp +++ b/ntcore/src/test/native/cpp/TableListenerTest.cpp @@ -15,24 +15,24 @@ using ::testing::_; using MockTableEventListener = testing::MockFunction; + wpi::nt::NetworkTable* table, std::string_view key, const wpi::nt::Event& event)>; using MockSubTableListener = - testing::MockFunction table)>; + testing::MockFunction table)>; class TableListenerTest : public ::testing::Test { public: - TableListenerTest() : m_inst(nt::NetworkTableInstance::Create()) {} + TableListenerTest() : m_inst(wpi::nt::NetworkTableInstance::Create()) {} - ~TableListenerTest() override { nt::NetworkTableInstance::Destroy(m_inst); } + ~TableListenerTest() override { wpi::nt::NetworkTableInstance::Destroy(m_inst); } void PublishTopics(); protected: - nt::NetworkTableInstance m_inst; - nt::DoublePublisher m_foovalue; - nt::DoublePublisher m_barvalue; - nt::DoublePublisher m_bazvalue; + wpi::nt::NetworkTableInstance m_inst; + wpi::nt::DoublePublisher m_foovalue; + wpi::nt::DoublePublisher m_barvalue; + wpi::nt::DoublePublisher m_bazvalue; }; void TableListenerTest::PublishTopics() { diff --git a/ntcore/src/test/native/cpp/TestPrinters.cpp b/ntcore/src/test/native/cpp/TestPrinters.cpp index 896d759ce6..4ee35168eb 100644 --- a/ntcore/src/test/native/cpp/TestPrinters.cpp +++ b/ntcore/src/test/native/cpp/TestPrinters.cpp @@ -10,7 +10,7 @@ #include "wpi/nt/NetworkTableValue.hpp" #include "wpi/nt/ntcore_cpp.hpp" -namespace nt { +namespace wpi::nt { void PrintTo(const Event& event, std::ostream* os) { *os << "Event{listener="; @@ -105,4 +105,4 @@ void PrintTo(const PubSubOptionsImpl& options, std::ostream* os) { << ", keepDuplicates=" << options.keepDuplicates << '}'; } -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/test/native/cpp/TestPrinters.hpp b/ntcore/src/test/native/cpp/TestPrinters.hpp index d51905c1f8..171ad77c48 100644 --- a/ntcore/src/test/native/cpp/TestPrinters.hpp +++ b/ntcore/src/test/native/cpp/TestPrinters.hpp @@ -13,7 +13,7 @@ #include "wpi/util/TestPrinters.hpp" -namespace nt { +namespace wpi::nt { namespace net3 { class Message3; @@ -37,4 +37,4 @@ void PrintTo(const net::ServerMessage& msg, std::ostream* os); void PrintTo(const Value& value, std::ostream* os); void PrintTo(const PubSubOptionsImpl& options, std::ostream* os); -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/test/native/cpp/TimeSyncTest.cpp b/ntcore/src/test/native/cpp/TimeSyncTest.cpp index 0f815b36ef..72d2b832b4 100644 --- a/ntcore/src/test/native/cpp/TimeSyncTest.cpp +++ b/ntcore/src/test/native/cpp/TimeSyncTest.cpp @@ -9,12 +9,12 @@ class TimeSyncTest : public ::testing::Test { public: - TimeSyncTest() : m_inst(nt::NetworkTableInstance::Create()) {} + TimeSyncTest() : m_inst(wpi::nt::NetworkTableInstance::Create()) {} - ~TimeSyncTest() override { nt::NetworkTableInstance::Destroy(m_inst); } + ~TimeSyncTest() override { wpi::nt::NetworkTableInstance::Destroy(m_inst); } protected: - nt::NetworkTableInstance m_inst; + wpi::nt::NetworkTableInstance m_inst; }; TEST_F(TimeSyncTest, TestLocal) { @@ -23,7 +23,7 @@ TEST_F(TimeSyncTest, TestLocal) { } TEST_F(TimeSyncTest, TestServer) { - nt::NetworkTableListenerPoller poller{m_inst}; + wpi::nt::NetworkTableListenerPoller poller{m_inst}; poller.AddTimeSyncListener(false); m_inst.StartServer("timesynctest.json", "127.0.0.1", 10030); diff --git a/ntcore/src/test/native/cpp/TopicListenerTest.cpp b/ntcore/src/test/native/cpp/TopicListenerTest.cpp index b7722ccd65..c512fb1f01 100644 --- a/ntcore/src/test/native/cpp/TopicListenerTest.cpp +++ b/ntcore/src/test/native/cpp/TopicListenerTest.cpp @@ -19,14 +19,14 @@ class TopicListenerTest : public ::testing::Test { public: TopicListenerTest() - : m_serverInst(nt::CreateInstance()), m_clientInst(nt::CreateInstance()) { + : m_serverInst(wpi::nt::CreateInstance()), m_clientInst(wpi::nt::CreateInstance()) { #if 0 - nt::AddLogger(m_serverInst, 0, UINT_MAX, [](auto& event) { + wpi::nt::AddLogger(m_serverInst, 0, UINT_MAX, [](auto& event) { if (auto msg = event.GetLogMessage()) { std::fprintf(stderr, "SERVER: %s\n", msg->message.c_str()); } }); - nt::AddLogger(m_clientInst, 0, UINT_MAX, [](auto& event) { + wpi::nt::AddLogger(m_clientInst, 0, UINT_MAX, [](auto& event) { if (auto msg = event.GetLogMessage()) { std::fprintf(stderr, "CLIENT: %s\n", msg.message.c_str()); } @@ -35,13 +35,13 @@ class TopicListenerTest : public ::testing::Test { } ~TopicListenerTest() override { - nt::DestroyInstance(m_serverInst); - nt::DestroyInstance(m_clientInst); + wpi::nt::DestroyInstance(m_serverInst); + wpi::nt::DestroyInstance(m_clientInst); } void Connect(unsigned int port); static void PublishTopics(NT_Inst inst); - void CheckEvents(const std::vector& events, NT_Listener handle, + void CheckEvents(const std::vector& events, NT_Listener handle, unsigned int flags, std::string_view topicName = "/foo/bar"); protected: @@ -50,26 +50,26 @@ class TopicListenerTest : public ::testing::Test { }; void TopicListenerTest::Connect(unsigned int port) { - nt::StartServer(m_serverInst, "topiclistenertest.json", "127.0.0.1", port); - nt::StartClient(m_clientInst, "client"); - nt::SetServer(m_clientInst, "127.0.0.1", port); + wpi::nt::StartServer(m_serverInst, "topiclistenertest.json", "127.0.0.1", port); + wpi::nt::StartClient(m_clientInst, "client"); + wpi::nt::SetServer(m_clientInst, "127.0.0.1", port); // Use connection listener to ensure we've connected - NT_ListenerPoller poller = nt::CreateListenerPoller(m_clientInst); - nt::AddPolledListener(poller, m_clientInst, nt::EventFlags::kConnected); + NT_ListenerPoller poller = wpi::nt::CreateListenerPoller(m_clientInst); + wpi::nt::AddPolledListener(poller, m_clientInst, wpi::nt::EventFlags::kConnected); bool timedOut = false; - if (!wpi::WaitForObject(poller, 1.0, &timedOut)) { + if (!wpi::util::WaitForObject(poller, 1.0, &timedOut)) { FAIL() << "client didn't connect to server"; } } void TopicListenerTest::PublishTopics(NT_Inst inst) { - nt::Publish(nt::GetTopic(inst, "/foo/bar"), NT_DOUBLE, "double"); - nt::Publish(nt::GetTopic(inst, "/foo"), NT_DOUBLE, "double"); - nt::Publish(nt::GetTopic(inst, "/baz"), NT_DOUBLE, "double"); + wpi::nt::Publish(wpi::nt::GetTopic(inst, "/foo/bar"), NT_DOUBLE, "double"); + wpi::nt::Publish(wpi::nt::GetTopic(inst, "/foo"), NT_DOUBLE, "double"); + wpi::nt::Publish(wpi::nt::GetTopic(inst, "/baz"), NT_DOUBLE, "double"); } -void TopicListenerTest::CheckEvents(const std::vector& events, +void TopicListenerTest::CheckEvents(const std::vector& events, NT_Listener handle, unsigned int flags, std::string_view topicName) { ASSERT_EQ(events.size(), 1u); @@ -77,21 +77,21 @@ void TopicListenerTest::CheckEvents(const std::vector& events, ASSERT_EQ(events[0].flags, flags); auto topicInfo = events[0].GetTopicInfo(); ASSERT_TRUE(topicInfo); - ASSERT_EQ(topicInfo->topic, nt::GetTopic(m_serverInst, topicName)); + ASSERT_EQ(topicInfo->topic, wpi::nt::GetTopic(m_serverInst, topicName)); ASSERT_EQ(topicInfo->name, topicName); } TEST_F(TopicListenerTest, TopicNewLocal) { - auto poller = nt::CreateListenerPoller(m_serverInst); - auto handle = nt::AddPolledListener( - poller, nt::GetTopic(m_serverInst, "/foo"), nt::EventFlags::kPublish); + auto poller = wpi::nt::CreateListenerPoller(m_serverInst); + auto handle = wpi::nt::AddPolledListener( + poller, wpi::nt::GetTopic(m_serverInst, "/foo"), wpi::nt::EventFlags::kPublish); PublishTopics(m_serverInst); bool timedOut = false; - ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut)); - auto events = nt::ReadListenerQueue(poller); - CheckEvents(events, handle, nt::EventFlags::kPublish, "/foo"); + ASSERT_TRUE(wpi::util::WaitForObject(poller, 1.0, &timedOut)); + auto events = wpi::nt::ReadListenerQueue(poller); + CheckEvents(events, handle, wpi::nt::EventFlags::kPublish, "/foo"); } TEST_F(TopicListenerTest, DISABLED_TopicNewRemote) { @@ -99,65 +99,65 @@ TEST_F(TopicListenerTest, DISABLED_TopicNewRemote) { if (HasFatalFailure()) { return; } - auto poller = nt::CreateListenerPoller(m_serverInst); - auto handle = nt::AddPolledListener( - poller, nt::GetTopic(m_serverInst, "/foo"), nt::EventFlags::kPublish); + auto poller = wpi::nt::CreateListenerPoller(m_serverInst); + auto handle = wpi::nt::AddPolledListener( + poller, wpi::nt::GetTopic(m_serverInst, "/foo"), wpi::nt::EventFlags::kPublish); PublishTopics(m_clientInst); - nt::Flush(m_clientInst); + wpi::nt::Flush(m_clientInst); std::this_thread::sleep_for(std::chrono::milliseconds(100)); bool timedOut = false; - ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut)); - auto events = nt::ReadListenerQueue(poller); - CheckEvents(events, handle, nt::EventFlags::kPublish, "/foo"); + ASSERT_TRUE(wpi::util::WaitForObject(poller, 1.0, &timedOut)); + auto events = wpi::nt::ReadListenerQueue(poller); + CheckEvents(events, handle, wpi::nt::EventFlags::kPublish, "/foo"); } TEST_F(TopicListenerTest, TopicPublishImm) { PublishTopics(m_serverInst); - auto poller = nt::CreateListenerPoller(m_serverInst); - auto handle = nt::AddPolledListener( - poller, nt::GetTopic(m_serverInst, "/foo"), - nt::EventFlags::kPublish | nt::EventFlags::kImmediate); + auto poller = wpi::nt::CreateListenerPoller(m_serverInst); + auto handle = wpi::nt::AddPolledListener( + poller, wpi::nt::GetTopic(m_serverInst, "/foo"), + wpi::nt::EventFlags::kPublish | wpi::nt::EventFlags::kImmediate); bool timedOut = false; - ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut)); - auto events = nt::ReadListenerQueue(poller); + ASSERT_TRUE(wpi::util::WaitForObject(poller, 1.0, &timedOut)); + auto events = wpi::nt::ReadListenerQueue(poller); CheckEvents(events, handle, - nt::EventFlags::kPublish | nt::EventFlags::kImmediate, "/foo"); + wpi::nt::EventFlags::kPublish | wpi::nt::EventFlags::kImmediate, "/foo"); } TEST_F(TopicListenerTest, TopicUnpublishPropsImm) { PublishTopics(m_serverInst); - auto poller = nt::CreateListenerPoller(m_serverInst); - nt::AddPolledListener(poller, nt::GetTopic(m_serverInst, "/foo"), - nt::EventFlags::kUnpublish | - nt::EventFlags::kProperties | - nt::EventFlags::kImmediate); + auto poller = wpi::nt::CreateListenerPoller(m_serverInst); + wpi::nt::AddPolledListener(poller, wpi::nt::GetTopic(m_serverInst, "/foo"), + wpi::nt::EventFlags::kUnpublish | + wpi::nt::EventFlags::kProperties | + wpi::nt::EventFlags::kImmediate); bool timedOut = false; - ASSERT_FALSE(wpi::WaitForObject(poller, 0.02, &timedOut)); - auto events = nt::ReadListenerQueue(poller); + ASSERT_FALSE(wpi::util::WaitForObject(poller, 0.02, &timedOut)); + auto events = wpi::nt::ReadListenerQueue(poller); ASSERT_TRUE(events.empty()); } TEST_F(TopicListenerTest, TopicUnpublishLocal) { - auto topic = nt::GetTopic(m_serverInst, "/foo"); + auto topic = wpi::nt::GetTopic(m_serverInst, "/foo"); - auto poller = nt::CreateListenerPoller(m_serverInst); + auto poller = wpi::nt::CreateListenerPoller(m_serverInst); auto handle = - nt::AddPolledListener(poller, topic, nt::EventFlags::kUnpublish); + wpi::nt::AddPolledListener(poller, topic, wpi::nt::EventFlags::kUnpublish); - auto pub = nt::Publish(topic, NT_DOUBLE, "double"); - nt::Unpublish(pub); + auto pub = wpi::nt::Publish(topic, NT_DOUBLE, "double"); + wpi::nt::Unpublish(pub); bool timedOut = false; - ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut)); - auto events = nt::ReadListenerQueue(poller); - CheckEvents(events, handle, nt::EventFlags::kUnpublish, "/foo"); + ASSERT_TRUE(wpi::util::WaitForObject(poller, 1.0, &timedOut)); + auto events = wpi::nt::ReadListenerQueue(poller); + CheckEvents(events, handle, wpi::nt::EventFlags::kUnpublish, "/foo"); } TEST_F(TopicListenerTest, DISABLED_TopicUnpublishRemote) { @@ -165,39 +165,39 @@ TEST_F(TopicListenerTest, DISABLED_TopicUnpublishRemote) { if (HasFatalFailure()) { return; } - auto poller = nt::CreateListenerPoller(m_serverInst); - auto handle = nt::AddPolledListener( - poller, nt::GetTopic(m_serverInst, "/foo"), nt::EventFlags::kUnpublish); + auto poller = wpi::nt::CreateListenerPoller(m_serverInst); + auto handle = wpi::nt::AddPolledListener( + poller, wpi::nt::GetTopic(m_serverInst, "/foo"), wpi::nt::EventFlags::kUnpublish); auto pub = - nt::Publish(nt::GetTopic(m_clientInst, "/foo"), NT_DOUBLE, "double"); - nt::Flush(m_clientInst); + wpi::nt::Publish(wpi::nt::GetTopic(m_clientInst, "/foo"), NT_DOUBLE, "double"); + wpi::nt::Flush(m_clientInst); std::this_thread::sleep_for(std::chrono::milliseconds(100)); - nt::Unpublish(pub); + wpi::nt::Unpublish(pub); - nt::Flush(m_clientInst); + wpi::nt::Flush(m_clientInst); std::this_thread::sleep_for(std::chrono::milliseconds(100)); bool timedOut = false; - ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut)); - auto events = nt::ReadListenerQueue(poller); - CheckEvents(events, handle, nt::EventFlags::kUnpublish, "/foo"); + ASSERT_TRUE(wpi::util::WaitForObject(poller, 1.0, &timedOut)); + auto events = wpi::nt::ReadListenerQueue(poller); + CheckEvents(events, handle, wpi::nt::EventFlags::kUnpublish, "/foo"); } TEST_F(TopicListenerTest, TopicPropertiesLocal) { - auto topic = nt::GetTopic(m_serverInst, "/foo"); + auto topic = wpi::nt::GetTopic(m_serverInst, "/foo"); - auto poller = nt::CreateListenerPoller(m_serverInst); + auto poller = wpi::nt::CreateListenerPoller(m_serverInst); auto handle = - nt::AddPolledListener(poller, topic, nt::EventFlags::kProperties); + wpi::nt::AddPolledListener(poller, topic, wpi::nt::EventFlags::kProperties); - nt::SetTopicProperty(topic, "foo", 5); + wpi::nt::SetTopicProperty(topic, "foo", 5); bool timedOut = false; - ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut)); - auto events = nt::ReadListenerQueue(poller); - CheckEvents(events, handle, nt::EventFlags::kProperties, "/foo"); + ASSERT_TRUE(wpi::util::WaitForObject(poller, 1.0, &timedOut)); + auto events = wpi::nt::ReadListenerQueue(poller); + CheckEvents(events, handle, wpi::nt::EventFlags::kProperties, "/foo"); } TEST_F(TopicListenerTest, DISABLED_TopicPropertiesRemote) { @@ -206,34 +206,34 @@ TEST_F(TopicListenerTest, DISABLED_TopicPropertiesRemote) { return; } // the topic needs to actually exist - nt::Publish(nt::GetTopic(m_serverInst, "/foo"), NT_BOOLEAN, "boolean"); + wpi::nt::Publish(wpi::nt::GetTopic(m_serverInst, "/foo"), NT_BOOLEAN, "boolean"); - auto poller = nt::CreateListenerPoller(m_serverInst); - auto handle = nt::AddPolledListener( - poller, nt::GetTopic(m_serverInst, "/foo"), nt::EventFlags::kProperties); - nt::FlushLocal(m_serverInst); + auto poller = wpi::nt::CreateListenerPoller(m_serverInst); + auto handle = wpi::nt::AddPolledListener( + poller, wpi::nt::GetTopic(m_serverInst, "/foo"), wpi::nt::EventFlags::kProperties); + wpi::nt::FlushLocal(m_serverInst); - nt::SetTopicProperty(nt::GetTopic(m_clientInst, "/foo"), "foo", 5); - nt::Flush(m_clientInst); + wpi::nt::SetTopicProperty(wpi::nt::GetTopic(m_clientInst, "/foo"), "foo", 5); + wpi::nt::Flush(m_clientInst); std::this_thread::sleep_for(std::chrono::milliseconds(100)); bool timedOut = false; - ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut)); - auto events = nt::ReadListenerQueue(poller); - CheckEvents(events, handle, nt::EventFlags::kProperties, "/foo"); + ASSERT_TRUE(wpi::util::WaitForObject(poller, 1.0, &timedOut)); + auto events = wpi::nt::ReadListenerQueue(poller); + CheckEvents(events, handle, wpi::nt::EventFlags::kProperties, "/foo"); } TEST_F(TopicListenerTest, PrefixPublishLocal) { - auto poller = nt::CreateListenerPoller(m_serverInst); + auto poller = wpi::nt::CreateListenerPoller(m_serverInst); auto handle = - nt::AddPolledListener(poller, {{"/foo/"}}, nt::EventFlags::kPublish); + wpi::nt::AddPolledListener(poller, {{"/foo/"}}, wpi::nt::EventFlags::kPublish); PublishTopics(m_serverInst); bool timedOut = false; - ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut)); - auto events = nt::ReadListenerQueue(poller); - CheckEvents(events, handle, nt::EventFlags::kPublish); + ASSERT_TRUE(wpi::util::WaitForObject(poller, 1.0, &timedOut)); + auto events = wpi::nt::ReadListenerQueue(poller); + CheckEvents(events, handle, wpi::nt::EventFlags::kPublish); } TEST_F(TopicListenerTest, DISABLED_PrefixPublishRemote) { @@ -241,47 +241,47 @@ TEST_F(TopicListenerTest, DISABLED_PrefixPublishRemote) { if (HasFatalFailure()) { return; } - auto poller = nt::CreateListenerPoller(m_serverInst); + auto poller = wpi::nt::CreateListenerPoller(m_serverInst); auto handle = - nt::AddPolledListener(poller, {{"/foo/"}}, nt::EventFlags::kPublish); + wpi::nt::AddPolledListener(poller, {{"/foo/"}}, wpi::nt::EventFlags::kPublish); PublishTopics(m_clientInst); - nt::Flush(m_clientInst); + wpi::nt::Flush(m_clientInst); std::this_thread::sleep_for(std::chrono::milliseconds(100)); bool timedOut = false; - ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut)); - auto events = nt::ReadListenerQueue(poller); - CheckEvents(events, handle, nt::EventFlags::kPublish); + ASSERT_TRUE(wpi::util::WaitForObject(poller, 1.0, &timedOut)); + auto events = wpi::nt::ReadListenerQueue(poller); + CheckEvents(events, handle, wpi::nt::EventFlags::kPublish); } TEST_F(TopicListenerTest, PrefixPublishImm) { PublishTopics(m_serverInst); - auto poller = nt::CreateListenerPoller(m_serverInst); - auto handle = nt::AddPolledListener( + auto poller = wpi::nt::CreateListenerPoller(m_serverInst); + auto handle = wpi::nt::AddPolledListener( poller, {{"/foo/"}}, - nt::EventFlags::kPublish | nt::EventFlags::kImmediate); + wpi::nt::EventFlags::kPublish | wpi::nt::EventFlags::kImmediate); bool timedOut = false; - ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut)); - auto events = nt::ReadListenerQueue(poller); + ASSERT_TRUE(wpi::util::WaitForObject(poller, 1.0, &timedOut)); + auto events = wpi::nt::ReadListenerQueue(poller); CheckEvents(events, handle, - nt::EventFlags::kPublish | nt::EventFlags::kImmediate); + wpi::nt::EventFlags::kPublish | wpi::nt::EventFlags::kImmediate); } TEST_F(TopicListenerTest, PrefixUnpublishPropsImm) { PublishTopics(m_serverInst); - auto poller = nt::CreateListenerPoller(m_serverInst); - nt::AddPolledListener(poller, {{"/foo/"}}, - nt::EventFlags::kUnpublish | - nt::EventFlags::kProperties | - nt::EventFlags::kImmediate); + auto poller = wpi::nt::CreateListenerPoller(m_serverInst); + wpi::nt::AddPolledListener(poller, {{"/foo/"}}, + wpi::nt::EventFlags::kUnpublish | + wpi::nt::EventFlags::kProperties | + wpi::nt::EventFlags::kImmediate); bool timedOut = false; - ASSERT_FALSE(wpi::WaitForObject(poller, 0.02, &timedOut)); - auto events = nt::ReadListenerQueue(poller); + ASSERT_FALSE(wpi::util::WaitForObject(poller, 0.02, &timedOut)); + auto events = wpi::nt::ReadListenerQueue(poller); ASSERT_TRUE(events.empty()); } diff --git a/ntcore/src/test/native/cpp/ValueListenerTest.cpp b/ntcore/src/test/native/cpp/ValueListenerTest.cpp index 86dc41f1aa..acf268e6bc 100644 --- a/ntcore/src/test/native/cpp/ValueListenerTest.cpp +++ b/ntcore/src/test/native/cpp/ValueListenerTest.cpp @@ -16,394 +16,394 @@ using ::testing::AnyNumber; using ::testing::IsNull; using ::testing::Return; -namespace nt { +namespace wpi::nt { // Test only local here; it's more reliable to mock the network class ValueListenerTest : public ::testing::Test { public: - ValueListenerTest() : m_inst{nt::CreateInstance()} {} + ValueListenerTest() : m_inst{wpi::nt::CreateInstance()} {} - ~ValueListenerTest() override { nt::DestroyInstance(m_inst); } + ~ValueListenerTest() override { wpi::nt::DestroyInstance(m_inst); } protected: NT_Inst m_inst; }; TEST_F(ValueListenerTest, MultiPollSub) { - auto topic = nt::GetTopic(m_inst, "foo"); - auto pub = nt::Publish(topic, NT_DOUBLE, "double"); - auto sub = nt::Subscribe(topic, NT_DOUBLE, "double"); + auto topic = wpi::nt::GetTopic(m_inst, "foo"); + auto pub = wpi::nt::Publish(topic, NT_DOUBLE, "double"); + auto sub = wpi::nt::Subscribe(topic, NT_DOUBLE, "double"); - auto poller1 = nt::CreateListenerPoller(m_inst); - auto poller2 = nt::CreateListenerPoller(m_inst); - auto poller3 = nt::CreateListenerPoller(m_inst); - auto h1 = nt::AddPolledListener(poller1, sub, nt::EventFlags::kValueLocal); - auto h2 = nt::AddPolledListener(poller2, sub, nt::EventFlags::kValueLocal); - auto h3 = nt::AddPolledListener(poller3, sub, nt::EventFlags::kValueLocal); + auto poller1 = wpi::nt::CreateListenerPoller(m_inst); + auto poller2 = wpi::nt::CreateListenerPoller(m_inst); + auto poller3 = wpi::nt::CreateListenerPoller(m_inst); + auto h1 = wpi::nt::AddPolledListener(poller1, sub, wpi::nt::EventFlags::kValueLocal); + auto h2 = wpi::nt::AddPolledListener(poller2, sub, wpi::nt::EventFlags::kValueLocal); + auto h3 = wpi::nt::AddPolledListener(poller3, sub, wpi::nt::EventFlags::kValueLocal); - nt::SetDouble(pub, 0); + wpi::nt::SetDouble(pub, 0); bool timedOut = false; - ASSERT_TRUE(wpi::WaitForObject(poller1, 1.0, &timedOut)); + ASSERT_TRUE(wpi::util::WaitForObject(poller1, 1.0, &timedOut)); ASSERT_FALSE(timedOut); - ASSERT_TRUE(wpi::WaitForObject(poller2, 1.0, &timedOut)); + ASSERT_TRUE(wpi::util::WaitForObject(poller2, 1.0, &timedOut)); ASSERT_FALSE(timedOut); - ASSERT_TRUE(wpi::WaitForObject(poller3, 1.0, &timedOut)); + ASSERT_TRUE(wpi::util::WaitForObject(poller3, 1.0, &timedOut)); ASSERT_FALSE(timedOut); - auto results1 = nt::ReadListenerQueue(poller1); - auto results2 = nt::ReadListenerQueue(poller2); - auto results3 = nt::ReadListenerQueue(poller3); + auto results1 = wpi::nt::ReadListenerQueue(poller1); + auto results2 = wpi::nt::ReadListenerQueue(poller2); + auto results3 = wpi::nt::ReadListenerQueue(poller3); ASSERT_EQ(results1.size(), 1u); - EXPECT_EQ(results1[0].flags, nt::EventFlags::kValueLocal); + EXPECT_EQ(results1[0].flags, wpi::nt::EventFlags::kValueLocal); EXPECT_EQ(results1[0].listener, h1); auto valueData = results1[0].GetValueEventData(); ASSERT_TRUE(valueData); EXPECT_EQ(valueData->subentry, sub); EXPECT_EQ(valueData->topic, topic); - EXPECT_EQ(valueData->value, nt::Value::MakeDouble(0.0)); + EXPECT_EQ(valueData->value, wpi::nt::Value::MakeDouble(0.0)); ASSERT_EQ(results2.size(), 1u); - EXPECT_EQ(results2[0].flags, nt::EventFlags::kValueLocal); + EXPECT_EQ(results2[0].flags, wpi::nt::EventFlags::kValueLocal); EXPECT_EQ(results2[0].listener, h2); valueData = results2[0].GetValueEventData(); ASSERT_TRUE(valueData); EXPECT_EQ(valueData->subentry, sub); EXPECT_EQ(valueData->topic, topic); - EXPECT_EQ(valueData->value, nt::Value::MakeDouble(0.0)); + EXPECT_EQ(valueData->value, wpi::nt::Value::MakeDouble(0.0)); ASSERT_EQ(results3.size(), 1u); - EXPECT_EQ(results3[0].flags, nt::EventFlags::kValueLocal); + EXPECT_EQ(results3[0].flags, wpi::nt::EventFlags::kValueLocal); EXPECT_EQ(results3[0].listener, h3); valueData = results3[0].GetValueEventData(); ASSERT_TRUE(valueData); EXPECT_EQ(valueData->subentry, sub); EXPECT_EQ(valueData->topic, topic); - EXPECT_EQ(valueData->value, nt::Value::MakeDouble(0.0)); + EXPECT_EQ(valueData->value, wpi::nt::Value::MakeDouble(0.0)); } TEST_F(ValueListenerTest, PollMultiSub) { - auto topic = nt::GetTopic(m_inst, "foo"); - auto pub = nt::Publish(topic, NT_DOUBLE, "double"); - auto sub1 = nt::Subscribe(topic, NT_DOUBLE, "double"); - auto sub2 = nt::Subscribe(topic, NT_DOUBLE, "double"); + auto topic = wpi::nt::GetTopic(m_inst, "foo"); + auto pub = wpi::nt::Publish(topic, NT_DOUBLE, "double"); + auto sub1 = wpi::nt::Subscribe(topic, NT_DOUBLE, "double"); + auto sub2 = wpi::nt::Subscribe(topic, NT_DOUBLE, "double"); - auto poller = nt::CreateListenerPoller(m_inst); - auto h1 = nt::AddPolledListener(poller, sub1, nt::EventFlags::kValueLocal); - auto h2 = nt::AddPolledListener(poller, sub2, nt::EventFlags::kValueLocal); + auto poller = wpi::nt::CreateListenerPoller(m_inst); + auto h1 = wpi::nt::AddPolledListener(poller, sub1, wpi::nt::EventFlags::kValueLocal); + auto h2 = wpi::nt::AddPolledListener(poller, sub2, wpi::nt::EventFlags::kValueLocal); - nt::SetDouble(pub, 0); + wpi::nt::SetDouble(pub, 0); bool timedOut = false; - ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut)); + ASSERT_TRUE(wpi::util::WaitForObject(poller, 1.0, &timedOut)); ASSERT_FALSE(timedOut); - auto results = nt::ReadListenerQueue(poller); + auto results = wpi::nt::ReadListenerQueue(poller); ASSERT_EQ(results.size(), 2u); - EXPECT_EQ(results[0].flags, nt::EventFlags::kValueLocal); + EXPECT_EQ(results[0].flags, wpi::nt::EventFlags::kValueLocal); EXPECT_EQ(results[0].listener, h1); auto valueData = results[0].GetValueEventData(); ASSERT_TRUE(valueData); EXPECT_EQ(valueData->subentry, sub1); EXPECT_EQ(valueData->topic, topic); - EXPECT_EQ(valueData->value, nt::Value::MakeDouble(0.0)); + EXPECT_EQ(valueData->value, wpi::nt::Value::MakeDouble(0.0)); - EXPECT_EQ(results[1].flags, nt::EventFlags::kValueLocal); + EXPECT_EQ(results[1].flags, wpi::nt::EventFlags::kValueLocal); EXPECT_EQ(results[1].listener, h2); valueData = results[1].GetValueEventData(); ASSERT_TRUE(valueData); EXPECT_EQ(valueData->subentry, sub2); EXPECT_EQ(valueData->topic, topic); - EXPECT_EQ(valueData->value, nt::Value::MakeDouble(0.0)); + EXPECT_EQ(valueData->value, wpi::nt::Value::MakeDouble(0.0)); } TEST_F(ValueListenerTest, PollMultiSubTopic) { - auto topic1 = nt::GetTopic(m_inst, "foo"); - auto topic2 = nt::GetTopic(m_inst, "bar"); - auto pub1 = nt::Publish(topic1, NT_DOUBLE, "double"); - auto pub2 = nt::Publish(topic2, NT_DOUBLE, "double"); - auto sub1 = nt::Subscribe(topic1, NT_DOUBLE, "double"); - auto sub2 = nt::Subscribe(topic2, NT_DOUBLE, "double"); + auto topic1 = wpi::nt::GetTopic(m_inst, "foo"); + auto topic2 = wpi::nt::GetTopic(m_inst, "bar"); + auto pub1 = wpi::nt::Publish(topic1, NT_DOUBLE, "double"); + auto pub2 = wpi::nt::Publish(topic2, NT_DOUBLE, "double"); + auto sub1 = wpi::nt::Subscribe(topic1, NT_DOUBLE, "double"); + auto sub2 = wpi::nt::Subscribe(topic2, NT_DOUBLE, "double"); - auto poller = nt::CreateListenerPoller(m_inst); - auto h1 = nt::AddPolledListener(poller, sub1, nt::EventFlags::kValueLocal); - auto h2 = nt::AddPolledListener(poller, sub2, nt::EventFlags::kValueLocal); + auto poller = wpi::nt::CreateListenerPoller(m_inst); + auto h1 = wpi::nt::AddPolledListener(poller, sub1, wpi::nt::EventFlags::kValueLocal); + auto h2 = wpi::nt::AddPolledListener(poller, sub2, wpi::nt::EventFlags::kValueLocal); - nt::SetDouble(pub1, 0); - nt::SetDouble(pub2, 1); + wpi::nt::SetDouble(pub1, 0); + wpi::nt::SetDouble(pub2, 1); bool timedOut = false; - ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut)); + ASSERT_TRUE(wpi::util::WaitForObject(poller, 1.0, &timedOut)); ASSERT_FALSE(timedOut); - auto results = nt::ReadListenerQueue(poller); + auto results = wpi::nt::ReadListenerQueue(poller); ASSERT_EQ(results.size(), 2u); - EXPECT_EQ(results[0].flags, nt::EventFlags::kValueLocal); + EXPECT_EQ(results[0].flags, wpi::nt::EventFlags::kValueLocal); EXPECT_EQ(results[0].listener, h1); auto valueData = results[0].GetValueEventData(); ASSERT_TRUE(valueData); EXPECT_EQ(valueData->subentry, sub1); EXPECT_EQ(valueData->topic, topic1); - EXPECT_EQ(valueData->value, nt::Value::MakeDouble(0.0)); + EXPECT_EQ(valueData->value, wpi::nt::Value::MakeDouble(0.0)); - EXPECT_EQ(results[1].flags, nt::EventFlags::kValueLocal); + EXPECT_EQ(results[1].flags, wpi::nt::EventFlags::kValueLocal); EXPECT_EQ(results[1].listener, h2); valueData = results[1].GetValueEventData(); ASSERT_TRUE(valueData); EXPECT_EQ(valueData->subentry, sub2); EXPECT_EQ(valueData->topic, topic2); - EXPECT_EQ(valueData->value, nt::Value::MakeDouble(1.0)); + EXPECT_EQ(valueData->value, wpi::nt::Value::MakeDouble(1.0)); } TEST_F(ValueListenerTest, PollSubMultiple) { - auto topic1 = nt::GetTopic(m_inst, "foo/1"); - auto topic2 = nt::GetTopic(m_inst, "foo/2"); - auto pub1 = nt::Publish(topic1, NT_DOUBLE, "double"); - auto pub2 = nt::Publish(topic2, NT_DOUBLE, "double"); - auto sub = nt::SubscribeMultiple(m_inst, {{"foo"}}); + auto topic1 = wpi::nt::GetTopic(m_inst, "foo/1"); + auto topic2 = wpi::nt::GetTopic(m_inst, "foo/2"); + auto pub1 = wpi::nt::Publish(topic1, NT_DOUBLE, "double"); + auto pub2 = wpi::nt::Publish(topic2, NT_DOUBLE, "double"); + auto sub = wpi::nt::SubscribeMultiple(m_inst, {{"foo"}}); - auto poller = nt::CreateListenerPoller(m_inst); - auto h = nt::AddPolledListener(poller, sub, nt::EventFlags::kValueLocal); + auto poller = wpi::nt::CreateListenerPoller(m_inst); + auto h = wpi::nt::AddPolledListener(poller, sub, wpi::nt::EventFlags::kValueLocal); - nt::SetDouble(pub1, 0); - nt::SetDouble(pub2, 1); + wpi::nt::SetDouble(pub1, 0); + wpi::nt::SetDouble(pub2, 1); bool timedOut = false; - ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut)); + ASSERT_TRUE(wpi::util::WaitForObject(poller, 1.0, &timedOut)); ASSERT_FALSE(timedOut); - auto results = nt::ReadListenerQueue(poller); + auto results = wpi::nt::ReadListenerQueue(poller); ASSERT_EQ(results.size(), 2u); - EXPECT_EQ(results[0].flags, nt::EventFlags::kValueLocal); + EXPECT_EQ(results[0].flags, wpi::nt::EventFlags::kValueLocal); EXPECT_EQ(results[0].listener, h); auto valueData = results[0].GetValueEventData(); ASSERT_TRUE(valueData); EXPECT_EQ(valueData->subentry, sub); EXPECT_EQ(valueData->topic, topic1); - EXPECT_EQ(valueData->value, nt::Value::MakeDouble(0.0)); + EXPECT_EQ(valueData->value, wpi::nt::Value::MakeDouble(0.0)); - EXPECT_EQ(results[1].flags, nt::EventFlags::kValueLocal); + EXPECT_EQ(results[1].flags, wpi::nt::EventFlags::kValueLocal); EXPECT_EQ(results[1].listener, h); valueData = results[1].GetValueEventData(); ASSERT_TRUE(valueData); EXPECT_EQ(valueData->subentry, sub); EXPECT_EQ(valueData->topic, topic2); - EXPECT_EQ(valueData->value, nt::Value::MakeDouble(1.0)); + EXPECT_EQ(valueData->value, wpi::nt::Value::MakeDouble(1.0)); } TEST_F(ValueListenerTest, PollSubPrefixCreated) { - auto poller = nt::CreateListenerPoller(m_inst); + auto poller = wpi::nt::CreateListenerPoller(m_inst); auto h = - nt::AddPolledListener(poller, {{"foo"}}, nt::EventFlags::kValueLocal); + wpi::nt::AddPolledListener(poller, {{"foo"}}, wpi::nt::EventFlags::kValueLocal); - auto topic1 = nt::GetTopic(m_inst, "foo/1"); - auto topic2 = nt::GetTopic(m_inst, "foo/2"); - auto topic3 = nt::GetTopic(m_inst, "bar/3"); - auto pub1 = nt::Publish(topic1, NT_DOUBLE, "double"); - auto pub2 = nt::Publish(topic2, NT_DOUBLE, "double"); - auto pub3 = nt::Publish(topic3, NT_DOUBLE, "double"); + auto topic1 = wpi::nt::GetTopic(m_inst, "foo/1"); + auto topic2 = wpi::nt::GetTopic(m_inst, "foo/2"); + auto topic3 = wpi::nt::GetTopic(m_inst, "bar/3"); + auto pub1 = wpi::nt::Publish(topic1, NT_DOUBLE, "double"); + auto pub2 = wpi::nt::Publish(topic2, NT_DOUBLE, "double"); + auto pub3 = wpi::nt::Publish(topic3, NT_DOUBLE, "double"); - nt::SetDouble(pub1, 0); - nt::SetDouble(pub2, 1); - nt::SetDouble(pub3, 1); + wpi::nt::SetDouble(pub1, 0); + wpi::nt::SetDouble(pub2, 1); + wpi::nt::SetDouble(pub3, 1); bool timedOut = false; - ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut)); + ASSERT_TRUE(wpi::util::WaitForObject(poller, 1.0, &timedOut)); ASSERT_FALSE(timedOut); - auto results = nt::ReadListenerQueue(poller); + auto results = wpi::nt::ReadListenerQueue(poller); ASSERT_EQ(results.size(), 2u); - EXPECT_EQ(results[0].flags, nt::EventFlags::kValueLocal); + EXPECT_EQ(results[0].flags, wpi::nt::EventFlags::kValueLocal); EXPECT_EQ(results[0].listener, h); auto valueData = results[0].GetValueEventData(); ASSERT_TRUE(valueData); EXPECT_EQ(valueData->topic, topic1); - EXPECT_EQ(valueData->value, nt::Value::MakeDouble(0.0)); + EXPECT_EQ(valueData->value, wpi::nt::Value::MakeDouble(0.0)); - EXPECT_EQ(results[1].flags, nt::EventFlags::kValueLocal); + EXPECT_EQ(results[1].flags, wpi::nt::EventFlags::kValueLocal); EXPECT_EQ(results[1].listener, h); valueData = results[1].GetValueEventData(); ASSERT_TRUE(valueData); EXPECT_EQ(valueData->topic, topic2); - EXPECT_EQ(valueData->value, nt::Value::MakeDouble(1.0)); + EXPECT_EQ(valueData->value, wpi::nt::Value::MakeDouble(1.0)); } TEST_F(ValueListenerTest, PollEntry) { - auto entry = nt::GetEntry(m_inst, "foo"); + auto entry = wpi::nt::GetEntry(m_inst, "foo"); - auto poller = nt::CreateListenerPoller(m_inst); - auto h = nt::AddPolledListener(poller, entry, nt::EventFlags::kValueLocal); + auto poller = wpi::nt::CreateListenerPoller(m_inst); + auto h = wpi::nt::AddPolledListener(poller, entry, wpi::nt::EventFlags::kValueLocal); - ASSERT_TRUE(nt::SetDouble(entry, 0)); + ASSERT_TRUE(wpi::nt::SetDouble(entry, 0)); bool timedOut = false; - ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut)); + ASSERT_TRUE(wpi::util::WaitForObject(poller, 1.0, &timedOut)); ASSERT_FALSE(timedOut); - auto results = nt::ReadListenerQueue(poller); + auto results = wpi::nt::ReadListenerQueue(poller); ASSERT_EQ(results.size(), 1u); - EXPECT_EQ(results[0].flags, nt::EventFlags::kValueLocal); + EXPECT_EQ(results[0].flags, wpi::nt::EventFlags::kValueLocal); EXPECT_EQ(results[0].listener, h); auto valueData = results[0].GetValueEventData(); ASSERT_TRUE(valueData); EXPECT_EQ(valueData->subentry, entry); - EXPECT_EQ(valueData->topic, nt::GetTopic(m_inst, "foo")); - EXPECT_EQ(valueData->value, nt::Value::MakeDouble(0.0)); + EXPECT_EQ(valueData->topic, wpi::nt::GetTopic(m_inst, "foo")); + EXPECT_EQ(valueData->value, wpi::nt::Value::MakeDouble(0.0)); } TEST_F(ValueListenerTest, PollImmediate) { - auto entry = nt::GetEntry(m_inst, "foo"); - ASSERT_TRUE(nt::SetDouble(entry, 0)); + auto entry = wpi::nt::GetEntry(m_inst, "foo"); + ASSERT_TRUE(wpi::nt::SetDouble(entry, 0)); - auto poller = nt::CreateListenerPoller(m_inst); - auto h = nt::AddPolledListener( - poller, entry, nt::EventFlags::kValueLocal | nt::EventFlags::kImmediate); + auto poller = wpi::nt::CreateListenerPoller(m_inst); + auto h = wpi::nt::AddPolledListener( + poller, entry, wpi::nt::EventFlags::kValueLocal | wpi::nt::EventFlags::kImmediate); bool timedOut = false; - ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut)); + ASSERT_TRUE(wpi::util::WaitForObject(poller, 1.0, &timedOut)); ASSERT_FALSE(timedOut); - auto results = nt::ReadListenerQueue(poller); + auto results = wpi::nt::ReadListenerQueue(poller); ASSERT_EQ(results.size(), 1u); EXPECT_EQ(results[0].flags & - (nt::EventFlags::kValueLocal | nt::EventFlags::kImmediate), - nt::EventFlags::kValueLocal | nt::EventFlags::kImmediate); + (wpi::nt::EventFlags::kValueLocal | wpi::nt::EventFlags::kImmediate), + wpi::nt::EventFlags::kValueLocal | wpi::nt::EventFlags::kImmediate); EXPECT_EQ(results[0].listener, h); auto valueData = results[0].GetValueEventData(); ASSERT_TRUE(valueData); EXPECT_EQ(valueData->subentry, entry); - EXPECT_EQ(valueData->topic, nt::GetTopic(m_inst, "foo")); - EXPECT_EQ(valueData->value, nt::Value::MakeDouble(0.0)); + EXPECT_EQ(valueData->topic, wpi::nt::GetTopic(m_inst, "foo")); + EXPECT_EQ(valueData->value, wpi::nt::Value::MakeDouble(0.0)); } TEST_F(ValueListenerTest, PollImmediateNoValue) { - auto entry = nt::GetEntry(m_inst, "foo"); + auto entry = wpi::nt::GetEntry(m_inst, "foo"); - auto poller = nt::CreateListenerPoller(m_inst); - auto h = nt::AddPolledListener( - poller, entry, nt::EventFlags::kValueLocal | nt::EventFlags::kImmediate); + auto poller = wpi::nt::CreateListenerPoller(m_inst); + auto h = wpi::nt::AddPolledListener( + poller, entry, wpi::nt::EventFlags::kValueLocal | wpi::nt::EventFlags::kImmediate); bool timedOut = false; - ASSERT_FALSE(wpi::WaitForObject(poller, 0.02, &timedOut)); + ASSERT_FALSE(wpi::util::WaitForObject(poller, 0.02, &timedOut)); ASSERT_TRUE(timedOut); - auto results = nt::ReadListenerQueue(poller); + auto results = wpi::nt::ReadListenerQueue(poller); ASSERT_TRUE(results.empty()); // now set a value - ASSERT_TRUE(nt::SetDouble(entry, 0)); + ASSERT_TRUE(wpi::nt::SetDouble(entry, 0)); - ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut)); - results = nt::ReadListenerQueue(poller); + ASSERT_TRUE(wpi::util::WaitForObject(poller, 1.0, &timedOut)); + results = wpi::nt::ReadListenerQueue(poller); ASSERT_FALSE(timedOut); ASSERT_EQ(results.size(), 1u); - EXPECT_EQ(results[0].flags, nt::EventFlags::kValueLocal); + EXPECT_EQ(results[0].flags, wpi::nt::EventFlags::kValueLocal); EXPECT_EQ(results[0].listener, h); auto valueData = results[0].GetValueEventData(); ASSERT_TRUE(valueData); EXPECT_EQ(valueData->subentry, entry); - EXPECT_EQ(valueData->topic, nt::GetTopic(m_inst, "foo")); - EXPECT_EQ(valueData->value, nt::Value::MakeDouble(0.0)); + EXPECT_EQ(valueData->topic, wpi::nt::GetTopic(m_inst, "foo")); + EXPECT_EQ(valueData->value, wpi::nt::Value::MakeDouble(0.0)); } TEST_F(ValueListenerTest, PollImmediateSubMultiple) { - auto topic1 = nt::GetTopic(m_inst, "foo/1"); - auto topic2 = nt::GetTopic(m_inst, "foo/2"); - auto pub1 = nt::Publish(topic1, NT_DOUBLE, "double"); - auto pub2 = nt::Publish(topic2, NT_DOUBLE, "double"); - auto sub = nt::SubscribeMultiple(m_inst, {{"foo"}}); - nt::SetDouble(pub1, 0); - nt::SetDouble(pub2, 1); + auto topic1 = wpi::nt::GetTopic(m_inst, "foo/1"); + auto topic2 = wpi::nt::GetTopic(m_inst, "foo/2"); + auto pub1 = wpi::nt::Publish(topic1, NT_DOUBLE, "double"); + auto pub2 = wpi::nt::Publish(topic2, NT_DOUBLE, "double"); + auto sub = wpi::nt::SubscribeMultiple(m_inst, {{"foo"}}); + wpi::nt::SetDouble(pub1, 0); + wpi::nt::SetDouble(pub2, 1); - auto poller = nt::CreateListenerPoller(m_inst); - auto h = nt::AddPolledListener( - poller, sub, nt::EventFlags::kValueLocal | nt::EventFlags::kImmediate); + auto poller = wpi::nt::CreateListenerPoller(m_inst); + auto h = wpi::nt::AddPolledListener( + poller, sub, wpi::nt::EventFlags::kValueLocal | wpi::nt::EventFlags::kImmediate); bool timedOut = false; - ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut)); + ASSERT_TRUE(wpi::util::WaitForObject(poller, 1.0, &timedOut)); ASSERT_FALSE(timedOut); - auto results = nt::ReadListenerQueue(poller); + auto results = wpi::nt::ReadListenerQueue(poller); ASSERT_EQ(results.size(), 2u); EXPECT_EQ(results[0].flags & - (nt::EventFlags::kValueLocal | nt::EventFlags::kImmediate), - nt::EventFlags::kValueLocal | nt::EventFlags::kImmediate); + (wpi::nt::EventFlags::kValueLocal | wpi::nt::EventFlags::kImmediate), + wpi::nt::EventFlags::kValueLocal | wpi::nt::EventFlags::kImmediate); EXPECT_EQ(results[0].listener, h); auto valueData = results[0].GetValueEventData(); ASSERT_TRUE(valueData); EXPECT_EQ(valueData->subentry, sub); EXPECT_EQ(valueData->topic, topic1); - EXPECT_EQ(valueData->value, nt::Value::MakeDouble(0.0)); + EXPECT_EQ(valueData->value, wpi::nt::Value::MakeDouble(0.0)); EXPECT_EQ(results[1].flags & - (nt::EventFlags::kValueLocal | nt::EventFlags::kImmediate), - nt::EventFlags::kValueLocal | nt::EventFlags::kImmediate); + (wpi::nt::EventFlags::kValueLocal | wpi::nt::EventFlags::kImmediate), + wpi::nt::EventFlags::kValueLocal | wpi::nt::EventFlags::kImmediate); EXPECT_EQ(results[1].listener, h); valueData = results[1].GetValueEventData(); ASSERT_TRUE(valueData); EXPECT_EQ(valueData->subentry, sub); EXPECT_EQ(valueData->topic, topic2); - EXPECT_EQ(valueData->value, nt::Value::MakeDouble(1.0)); + EXPECT_EQ(valueData->value, wpi::nt::Value::MakeDouble(1.0)); } TEST_F(ValueListenerTest, TwoSubOneListener) { - auto topic = nt::GetTopic(m_inst, "foo"); - auto pub = nt::Publish(topic, NT_DOUBLE, "double"); - auto sub1 = nt::Subscribe(topic, NT_DOUBLE, "double"); - auto sub2 = nt::Subscribe(topic, NT_DOUBLE, "double"); - auto sub3 = nt::SubscribeMultiple(m_inst, {{"foo"}}); + auto topic = wpi::nt::GetTopic(m_inst, "foo"); + auto pub = wpi::nt::Publish(topic, NT_DOUBLE, "double"); + auto sub1 = wpi::nt::Subscribe(topic, NT_DOUBLE, "double"); + auto sub2 = wpi::nt::Subscribe(topic, NT_DOUBLE, "double"); + auto sub3 = wpi::nt::SubscribeMultiple(m_inst, {{"foo"}}); - auto poller = nt::CreateListenerPoller(m_inst); - auto h = nt::AddPolledListener(poller, sub1, nt::EventFlags::kValueLocal); + auto poller = wpi::nt::CreateListenerPoller(m_inst); + auto h = wpi::nt::AddPolledListener(poller, sub1, wpi::nt::EventFlags::kValueLocal); (void)sub2; (void)sub3; - nt::SetDouble(pub, 0); + wpi::nt::SetDouble(pub, 0); bool timedOut = false; - ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut)); + ASSERT_TRUE(wpi::util::WaitForObject(poller, 1.0, &timedOut)); ASSERT_FALSE(timedOut); - auto results = nt::ReadListenerQueue(poller); + auto results = wpi::nt::ReadListenerQueue(poller); ASSERT_EQ(results.size(), 1u); - EXPECT_EQ(results[0].flags & nt::EventFlags::kValueLocal, - nt::EventFlags::kValueLocal); + EXPECT_EQ(results[0].flags & wpi::nt::EventFlags::kValueLocal, + wpi::nt::EventFlags::kValueLocal); EXPECT_EQ(results[0].listener, h); auto valueData = results[0].GetValueEventData(); ASSERT_TRUE(valueData); EXPECT_EQ(valueData->subentry, sub1); EXPECT_EQ(valueData->topic, topic); - EXPECT_EQ(valueData->value, nt::Value::MakeDouble(0.0)); + EXPECT_EQ(valueData->value, wpi::nt::Value::MakeDouble(0.0)); } TEST_F(ValueListenerTest, TwoSubOneMultiListener) { - auto topic = nt::GetTopic(m_inst, "foo"); - auto pub = nt::Publish(topic, NT_DOUBLE, "double"); - auto sub1 = nt::Subscribe(topic, NT_DOUBLE, "double"); - auto sub2 = nt::Subscribe(topic, NT_DOUBLE, "double"); - auto sub3 = nt::SubscribeMultiple(m_inst, {{"foo"}}); + auto topic = wpi::nt::GetTopic(m_inst, "foo"); + auto pub = wpi::nt::Publish(topic, NT_DOUBLE, "double"); + auto sub1 = wpi::nt::Subscribe(topic, NT_DOUBLE, "double"); + auto sub2 = wpi::nt::Subscribe(topic, NT_DOUBLE, "double"); + auto sub3 = wpi::nt::SubscribeMultiple(m_inst, {{"foo"}}); - auto poller = nt::CreateListenerPoller(m_inst); - auto h = nt::AddPolledListener(poller, sub3, nt::EventFlags::kValueLocal); + auto poller = wpi::nt::CreateListenerPoller(m_inst); + auto h = wpi::nt::AddPolledListener(poller, sub3, wpi::nt::EventFlags::kValueLocal); (void)sub1; (void)sub2; - nt::SetDouble(pub, 0); + wpi::nt::SetDouble(pub, 0); bool timedOut = false; - ASSERT_TRUE(wpi::WaitForObject(poller, 1.0, &timedOut)); + ASSERT_TRUE(wpi::util::WaitForObject(poller, 1.0, &timedOut)); ASSERT_FALSE(timedOut); - auto results = nt::ReadListenerQueue(poller); + auto results = wpi::nt::ReadListenerQueue(poller); ASSERT_EQ(results.size(), 1u); - EXPECT_EQ(results[0].flags & nt::EventFlags::kValueLocal, - nt::EventFlags::kValueLocal); + EXPECT_EQ(results[0].flags & wpi::nt::EventFlags::kValueLocal, + wpi::nt::EventFlags::kValueLocal); EXPECT_EQ(results[0].listener, h); auto valueData = results[0].GetValueEventData(); ASSERT_TRUE(valueData); EXPECT_EQ(valueData->subentry, sub3); EXPECT_EQ(valueData->topic, topic); - EXPECT_EQ(valueData->value, nt::Value::MakeDouble(0.0)); + EXPECT_EQ(valueData->value, wpi::nt::Value::MakeDouble(0.0)); } -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/test/native/cpp/ValueMatcher.cpp b/ntcore/src/test/native/cpp/ValueMatcher.cpp index 8a7106ff1b..c9b9a09a88 100644 --- a/ntcore/src/test/native/cpp/ValueMatcher.cpp +++ b/ntcore/src/test/native/cpp/ValueMatcher.cpp @@ -6,7 +6,7 @@ #include "TestPrinters.hpp" -namespace nt { +namespace wpi::nt { bool ValueMatcher::MatchAndExplain( Value val, ::testing::MatchResultListener* listener) const { @@ -26,4 +26,4 @@ void ValueMatcher::DescribeNegationTo(::std::ostream* os) const { PrintTo(goodval, os); } -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/test/native/cpp/ValueMatcher.hpp b/ntcore/src/test/native/cpp/ValueMatcher.hpp index d82ab055cc..0232e8f3fb 100644 --- a/ntcore/src/test/native/cpp/ValueMatcher.hpp +++ b/ntcore/src/test/native/cpp/ValueMatcher.hpp @@ -11,7 +11,7 @@ #include "gmock/gmock.h" #include "wpi/nt/NetworkTableValue.hpp" -namespace nt { +namespace wpi::nt { class ValueMatcher : public ::testing::MatcherInterface { public: @@ -30,4 +30,4 @@ inline ::testing::Matcher ValueEq(const Value& goodval) { return ::testing::MakeMatcher(new ValueMatcher(goodval)); } -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/test/native/cpp/ValueTest.cpp b/ntcore/src/test/native/cpp/ValueTest.cpp index 4e5f13867a..480356c236 100644 --- a/ntcore/src/test/native/cpp/ValueTest.cpp +++ b/ntcore/src/test/native/cpp/ValueTest.cpp @@ -26,7 +26,7 @@ inline bool operator==(std::span lhs, std::span rhs) { } } // namespace std -namespace nt { +namespace wpi::nt { class ValueTest : public ::testing::Test {}; @@ -87,7 +87,7 @@ TEST_F(ValueTest, String) { NT_InitValue(&cv); ConvertToC(v, &cv); ASSERT_EQ(NT_STRING, cv.type); - ASSERT_EQ("hello"sv, wpi::to_string_view(&cv.data.v_string)); + ASSERT_EQ("hello"sv, wpi::util::to_string_view(&cv.data.v_string)); ASSERT_EQ(5u, cv.data.v_string.len); v = Value::MakeString("goodbye"); @@ -96,7 +96,7 @@ TEST_F(ValueTest, String) { NT_DisposeValue(&cv); ConvertToC(v, &cv); ASSERT_EQ(NT_STRING, cv.type); - ASSERT_EQ("goodbye"sv, wpi::to_string_view(&cv.data.v_string)); + ASSERT_EQ("goodbye"sv, wpi::util::to_string_view(&cv.data.v_string)); ASSERT_EQ(7u, cv.data.v_string.len); NT_DisposeValue(&cv); @@ -229,9 +229,9 @@ TEST_F(ValueTest, StringArray) { ConvertToC(v, &cv); ASSERT_EQ(NT_STRING_ARRAY, cv.type); ASSERT_EQ(3u, cv.data.arr_string.size); - ASSERT_EQ("hello"sv, wpi::to_string_view(&cv.data.arr_string.arr[0])); - ASSERT_EQ("goodbye"sv, wpi::to_string_view(&cv.data.arr_string.arr[1])); - ASSERT_EQ("string"sv, wpi::to_string_view(&cv.data.arr_string.arr[2])); + ASSERT_EQ("hello"sv, wpi::util::to_string_view(&cv.data.arr_string.arr[0])); + ASSERT_EQ("goodbye"sv, wpi::util::to_string_view(&cv.data.arr_string.arr[1])); + ASSERT_EQ("string"sv, wpi::util::to_string_view(&cv.data.arr_string.arr[2])); // assign with same size vec.clear(); @@ -248,9 +248,9 @@ TEST_F(ValueTest, StringArray) { ConvertToC(v, &cv); ASSERT_EQ(NT_STRING_ARRAY, cv.type); ASSERT_EQ(3u, cv.data.arr_string.size); - ASSERT_EQ("s1"sv, wpi::to_string_view(&cv.data.arr_string.arr[0])); - ASSERT_EQ("str2"sv, wpi::to_string_view(&cv.data.arr_string.arr[1])); - ASSERT_EQ("string3"sv, wpi::to_string_view(&cv.data.arr_string.arr[2])); + ASSERT_EQ("s1"sv, wpi::util::to_string_view(&cv.data.arr_string.arr[0])); + ASSERT_EQ("str2"sv, wpi::util::to_string_view(&cv.data.arr_string.arr[1])); + ASSERT_EQ("string3"sv, wpi::util::to_string_view(&cv.data.arr_string.arr[2])); // assign with different size vec.clear(); @@ -265,8 +265,8 @@ TEST_F(ValueTest, StringArray) { ConvertToC(v, &cv); ASSERT_EQ(NT_STRING_ARRAY, cv.type); ASSERT_EQ(2u, cv.data.arr_string.size); - ASSERT_EQ("short"sv, wpi::to_string_view(&cv.data.arr_string.arr[0])); - ASSERT_EQ("er"sv, wpi::to_string_view(&cv.data.arr_string.arr[1])); + ASSERT_EQ("short"sv, wpi::util::to_string_view(&cv.data.arr_string.arr[0])); + ASSERT_EQ("er"sv, wpi::util::to_string_view(&cv.data.arr_string.arr[1])); NT_DisposeValue(&cv); } @@ -463,4 +463,4 @@ TEST_F(ValueTest, StringArrayComparison) { ASSERT_EQ(v1, v2); } -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/test/native/cpp/main.cpp b/ntcore/src/test/native/cpp/main.cpp index 6332a300a4..01d1bec3ab 100644 --- a/ntcore/src/test/native/cpp/main.cpp +++ b/ntcore/src/test/native/cpp/main.cpp @@ -10,7 +10,7 @@ #include "wpi/util/timestamp.h" int main(int argc, char** argv) { - nt::AddLogger(nt::GetDefaultInstance(), 0, UINT_MAX, [](auto& event) { + wpi::nt::AddLogger(wpi::nt::GetDefaultInstance(), 0, UINT_MAX, [](auto& event) { if (auto msg = event.GetLogMessage()) { std::fputs(msg->message.c_str(), stderr); std::fputc('\n', stderr); diff --git a/ntcore/src/test/native/cpp/net/MockClientMessageQueue.hpp b/ntcore/src/test/native/cpp/net/MockClientMessageQueue.hpp index c290810de0..486a8916ec 100644 --- a/ntcore/src/test/native/cpp/net/MockClientMessageQueue.hpp +++ b/ntcore/src/test/native/cpp/net/MockClientMessageQueue.hpp @@ -11,7 +11,7 @@ #include "net/ClientMessageQueue.hpp" #include "net/Message.hpp" -namespace nt::net { +namespace wpi::nt::net { class MockClientMessageQueue : public net::ClientMessageQueue { public: @@ -30,4 +30,4 @@ class MockClientMessageQueue : public net::ClientMessageQueue { std::vector msgs; }; -} // namespace nt::net +} // namespace wpi::nt::net diff --git a/ntcore/src/test/native/cpp/net/MockMessageHandler.hpp b/ntcore/src/test/native/cpp/net/MockMessageHandler.hpp index cb4d3d67e7..8b47a37bcc 100644 --- a/ntcore/src/test/native/cpp/net/MockMessageHandler.hpp +++ b/ntcore/src/test/native/cpp/net/MockMessageHandler.hpp @@ -11,17 +11,17 @@ #include "net/MessageHandler.hpp" #include "wpi/util/json.hpp" -namespace nt::net { +namespace wpi::nt::net { class MockClientMessageHandler : public net::ClientMessageHandler { public: MOCK_METHOD(void, ClientPublish, (int pubuid, std::string_view name, std::string_view typeStr, - const wpi::json& properties, const PubSubOptionsImpl& options), + const wpi::util::json& properties, const PubSubOptionsImpl& options), (override)); MOCK_METHOD(void, ClientUnpublish, (int pubuid), (override)); MOCK_METHOD(void, ClientSetProperties, - (std::string_view name, const wpi::json& update), (override)); + (std::string_view name, const wpi::util::json& update), (override)); MOCK_METHOD(void, ClientSubscribe, (int subuid, std::span prefixes, const PubSubOptionsImpl& options), @@ -35,15 +35,15 @@ class MockServerMessageHandler : public net::ServerMessageHandler { public: MOCK_METHOD(int, ServerAnnounce, (std::string_view name, int id, std::string_view typeStr, - const wpi::json& properties, std::optional pubuid), + const wpi::util::json& properties, std::optional pubuid), (override)); MOCK_METHOD(void, ServerUnannounce, (std::string_view name, int id), (override)); MOCK_METHOD(void, ServerPropertiesUpdate, - (std::string_view name, const wpi::json& update, bool ack), + (std::string_view name, const wpi::util::json& update, bool ack), (override)); MOCK_METHOD(void, ServerSetValue, (int topicuid, const Value& value), (override)); }; -} // namespace nt::net +} // namespace wpi::nt::net diff --git a/ntcore/src/test/native/cpp/net/MockNetworkInterface.hpp b/ntcore/src/test/native/cpp/net/MockNetworkInterface.hpp index ff50a19c1c..8453a4765f 100644 --- a/ntcore/src/test/native/cpp/net/MockNetworkInterface.hpp +++ b/ntcore/src/test/native/cpp/net/MockNetworkInterface.hpp @@ -8,18 +8,18 @@ #include "net/NetworkInterface.hpp" #include "wpi/util/json.hpp" -namespace nt::net { +namespace wpi::nt::net { class MockLocalStorage : public ILocalStorage { public: MOCK_METHOD(int, ServerAnnounce, (std::string_view name, int id, std::string_view typeStr, - const wpi::json& properties, std::optional pubuid), + const wpi::util::json& properties, std::optional pubuid), (override)); MOCK_METHOD(void, ServerUnannounce, (std::string_view name, int id), (override)); MOCK_METHOD(void, ServerPropertiesUpdate, - (std::string_view name, const wpi::json& update, bool ack), + (std::string_view name, const wpi::util::json& update, bool ack), (override)); MOCK_METHOD(void, ServerSetValue, (int topicId, const Value& value), (override)); @@ -27,4 +27,4 @@ class MockLocalStorage : public ILocalStorage { MOCK_METHOD(void, ClearNetwork, (), (override)); }; -} // namespace nt::net +} // namespace wpi::nt::net diff --git a/ntcore/src/test/native/cpp/net/MockWireConnection.hpp b/ntcore/src/test/native/cpp/net/MockWireConnection.hpp index 8072823f62..ebb937c264 100644 --- a/ntcore/src/test/native/cpp/net/MockWireConnection.hpp +++ b/ntcore/src/test/native/cpp/net/MockWireConnection.hpp @@ -15,7 +15,7 @@ #include "net/WireConnection.hpp" #include "wpi/util/raw_ostream.hpp" -namespace nt::net { +namespace wpi::nt::net { class MockWireConnection : public WireConnection { public: @@ -25,30 +25,30 @@ class MockWireConnection : public WireConnection { MOCK_METHOD(bool, Ready, (), (const, override)); - int WriteText(wpi::function_ref writer) override { + int WriteText(wpi::util::function_ref writer) override { std::string text; - wpi::raw_string_ostream os{text}; + wpi::util::raw_string_ostream os{text}; writer(os); return DoWriteText(text); } int WriteBinary( - wpi::function_ref writer) override { + wpi::util::function_ref writer) override { std::vector binary; - wpi::raw_uvector_ostream os{binary}; + wpi::util::raw_uvector_ostream os{binary}; writer(os); return DoWriteBinary(binary); } - void SendText(wpi::function_ref writer) override { + void SendText(wpi::util::function_ref writer) override { std::string text; - wpi::raw_string_ostream os{text}; + wpi::util::raw_string_ostream os{text}; writer(os); DoSendText(text); } void SendBinary( - wpi::function_ref writer) override { + wpi::util::function_ref writer) override { std::vector binary; - wpi::raw_uvector_ostream os{binary}; + wpi::util::raw_uvector_ostream os{binary}; writer(os); DoSendBinary(binary); } @@ -70,4 +70,4 @@ class MockWireConnection : public WireConnection { MOCK_METHOD(void, Disconnect, (std::string_view reason), (override)); }; -} // namespace nt::net +} // namespace wpi::nt::net diff --git a/ntcore/src/test/native/cpp/net/WireDecoderTest.cpp b/ntcore/src/test/native/cpp/net/WireDecoderTest.cpp index 379fcde909..95de5b6cb1 100644 --- a/ntcore/src/test/native/cpp/net/WireDecoderTest.cpp +++ b/ntcore/src/test/native/cpp/net/WireDecoderTest.cpp @@ -23,7 +23,7 @@ using testing::_; using testing::MockFunction; using testing::StrictMock; -namespace nt { +namespace wpi::nt { class WireDecodeTextClientTest : public ::testing::Test { public: @@ -110,7 +110,7 @@ TEST_F(WireDecodeTextClientTest, ErrorUnknownMethod) { TEST_F(WireDecodeTextClientTest, PublishPropsEmpty) { EXPECT_CALL(handler, ClientPublish(5, std::string_view{"test"}, std::string_view{"double"}, - wpi::json::object(), PubSubOptionsEq({}))); + wpi::util::json::object(), PubSubOptionsEq({}))); net::WireDecodeText( "[{\"method\":\"publish\",\"params\":{" "\"name\":\"test\",\"properties\":{},\"pubuid\":5,\"type\":\"double\"}}]", @@ -118,7 +118,7 @@ TEST_F(WireDecodeTextClientTest, PublishPropsEmpty) { EXPECT_CALL(handler, ClientPublish(5, std::string_view{"test"}, std::string_view{"double"}, - wpi::json::object(), PubSubOptionsEq({}))); + wpi::util::json::object(), PubSubOptionsEq({}))); net::WireDecodeText( "[{\"method\":\"publish\",\"params\":{" "\"name\":\"test\",\"pubuid\":5,\"type\":\"double\"}}]", @@ -126,7 +126,7 @@ TEST_F(WireDecodeTextClientTest, PublishPropsEmpty) { } TEST_F(WireDecodeTextClientTest, PublishProps) { - wpi::json props = {{"k", 6}}; + wpi::util::json props = {{"k", 6}}; EXPECT_CALL(handler, ClientPublish(5, std::string_view{"test"}, std::string_view{"double"}, props, PubSubOptionsEq({}))); @@ -192,4 +192,4 @@ TEST_F(WireDecodeTextClientTest, UnpublishError) { logger); } -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/test/native/cpp/net/WireEncoderTest.cpp b/ntcore/src/test/native/cpp/net/WireEncoderTest.cpp index 4a8378cd9c..ab49ff5981 100644 --- a/ntcore/src/test/native/cpp/net/WireEncoderTest.cpp +++ b/ntcore/src/test/native/cpp/net/WireEncoderTest.cpp @@ -22,23 +22,23 @@ using namespace std::string_view_literals; -namespace nt { +namespace wpi::nt { class WireEncoderTextTest : public ::testing::Test { protected: std::string out; - wpi::raw_string_ostream os{out}; - wpi::json GetJson() { return wpi::json::parse(os.str()); } + wpi::util::raw_string_ostream os{out}; + wpi::util::json GetJson() { return wpi::util::json::parse(os.str()); } }; class WireEncoderBinaryTest : public ::testing::Test { protected: std::vector out; - wpi::raw_uvector_ostream os{out}; + wpi::util::raw_uvector_ostream os{out}; }; TEST_F(WireEncoderTextTest, PublishPropsEmpty) { - net::WireEncodePublish(os, 5, "test", "double", wpi::json::object()); + net::WireEncodePublish(os, 5, "test", "double", wpi::util::json::object()); ASSERT_EQ( os.str(), "{\"method\":\"publish\",\"params\":{" @@ -113,7 +113,7 @@ TEST_F(WireEncoderTextTest, Unsubscribe) { } TEST_F(WireEncoderTextTest, Announce) { - net::WireEncodeAnnounce(os, "test", 5, "double", wpi::json::object(), + net::WireEncodeAnnounce(os, "test", 5, "double", wpi::util::json::object(), std::nullopt); ASSERT_EQ(os.str(), "{\"method\":\"announce\",\"params\":{\"id\":5,\"name\":\"test\"," @@ -128,7 +128,7 @@ TEST_F(WireEncoderTextTest, AnnounceProperties) { } TEST_F(WireEncoderTextTest, AnnouncePubuid) { - net::WireEncodeAnnounce(os, "test", 5, "double", wpi::json::object(), 6); + net::WireEncodeAnnounce(os, "test", 5, "double", wpi::util::json::object(), 6); ASSERT_EQ(os.str(), "{\"method\":\"announce\",\"params\":{\"id\":5,\"name\":\"test\"," "\"properties\":{},\"pubuid\":6,\"type\":\"double\"}}"); @@ -180,7 +180,7 @@ TEST_F(WireEncoderTextTest, MessageUnsubscribe) { TEST_F(WireEncoderTextTest, MessageAnnounce) { net::ServerMessage msg{ - net::AnnounceMsg{"test", 5, "double", std::nullopt, wpi::json::object()}}; + net::AnnounceMsg{"test", 5, "double", std::nullopt, wpi::util::json::object()}}; ASSERT_TRUE(net::WireEncodeText(os, msg)); ASSERT_EQ(os.str(), "{\"method\":\"announce\",\"params\":{\"id\":5,\"name\":\"test\"," @@ -198,7 +198,7 @@ TEST_F(WireEncoderTextTest, MessageAnnounceProperties) { TEST_F(WireEncoderTextTest, MessageAnnouncePubuid) { net::ServerMessage msg{ - net::AnnounceMsg{"test", 5, "double", 6, wpi::json::object()}}; + net::AnnounceMsg{"test", 5, "double", 6, wpi::util::json::object()}}; ASSERT_TRUE(net::WireEncodeText(os, msg)); ASSERT_EQ(os.str(), "{\"method\":\"announce\",\"params\":{\"id\":5,\"name\":\"test\"," @@ -224,49 +224,49 @@ TEST_F(WireEncoderTextTest, ServerMessageValue) { TEST_F(WireEncoderBinaryTest, Boolean) { net::WireEncodeBinary(os, 5, 6, Value::MakeBoolean(true)); - ASSERT_THAT(out, wpi::SpanEq("\x94\x05\x06\x00\xc3"_us)); + ASSERT_THAT(out, wpi::util::SpanEq("\x94\x05\x06\x00\xc3"_us)); } TEST_F(WireEncoderBinaryTest, Integer) { net::WireEncodeBinary(os, 5, 6, Value::MakeInteger(7)); - ASSERT_THAT(out, wpi::SpanEq("\x94\x05\x06\x02\x07"_us)); + ASSERT_THAT(out, wpi::util::SpanEq("\x94\x05\x06\x02\x07"_us)); } TEST_F(WireEncoderBinaryTest, Float) { net::WireEncodeBinary(os, 5, 6, Value::MakeFloat(2.5)); - ASSERT_THAT(out, wpi::SpanEq("\x94\x05\x06\x03\xca\x40\x20\x00\x00"_us)); + ASSERT_THAT(out, wpi::util::SpanEq("\x94\x05\x06\x03\xca\x40\x20\x00\x00"_us)); } TEST_F(WireEncoderBinaryTest, Double) { net::WireEncodeBinary(os, 5, 6, Value::MakeDouble(2.5)); ASSERT_THAT( out, - wpi::SpanEq("\x94\x05\x06\x01\xcb\x40\x04\x00\x00\x00\x00\x00\x00"_us)); + wpi::util::SpanEq("\x94\x05\x06\x01\xcb\x40\x04\x00\x00\x00\x00\x00\x00"_us)); } TEST_F(WireEncoderBinaryTest, String) { net::WireEncodeBinary(os, 5, 6, Value::MakeString("hello")); - ASSERT_THAT(out, wpi::SpanEq("\x94\x05\x06\x04\xa5hello"_us)); + ASSERT_THAT(out, wpi::util::SpanEq("\x94\x05\x06\x04\xa5hello"_us)); } TEST_F(WireEncoderBinaryTest, Raw) { net::WireEncodeBinary(os, 5, 6, Value::MakeRaw("hello"_us)); - ASSERT_THAT(out, wpi::SpanEq("\x94\x05\x06\x05\xc4\x05hello"_us)); + ASSERT_THAT(out, wpi::util::SpanEq("\x94\x05\x06\x05\xc4\x05hello"_us)); } TEST_F(WireEncoderBinaryTest, BooleanArray) { net::WireEncodeBinary(os, 5, 6, Value::MakeBooleanArray({true, false, true})); - ASSERT_THAT(out, wpi::SpanEq("\x94\x05\x06\x10\x93\xc3\xc2\xc3"_us)); + ASSERT_THAT(out, wpi::util::SpanEq("\x94\x05\x06\x10\x93\xc3\xc2\xc3"_us)); } TEST_F(WireEncoderBinaryTest, IntegerArray) { net::WireEncodeBinary(os, 5, 6, Value::MakeIntegerArray({1, 2, 4})); - ASSERT_THAT(out, wpi::SpanEq("\x94\x05\x06\x12\x93\x01\x02\x04"_us)); + ASSERT_THAT(out, wpi::util::SpanEq("\x94\x05\x06\x12\x93\x01\x02\x04"_us)); } TEST_F(WireEncoderBinaryTest, FloatArray) { net::WireEncodeBinary(os, 5, 6, Value::MakeFloatArray({1, 2, 3})); - ASSERT_THAT(out, wpi::SpanEq("\x94\x05\x06\x13\x93" + ASSERT_THAT(out, wpi::util::SpanEq("\x94\x05\x06\x13\x93" "\xca\x3f\x80\x00\x00" "\xca\x40\x00\x00\x00" "\xca\x40\x40\x00\x00"_us)); @@ -274,7 +274,7 @@ TEST_F(WireEncoderBinaryTest, FloatArray) { TEST_F(WireEncoderBinaryTest, DoubleArray) { net::WireEncodeBinary(os, 5, 6, Value::MakeDoubleArray({1, 2, 3})); - ASSERT_THAT(out, wpi::SpanEq("\x94\x05\x06\x11\x93" + ASSERT_THAT(out, wpi::util::SpanEq("\x94\x05\x06\x11\x93" "\xcb\x3f\xf0\x00\x00\x00\x00\x00\x00" "\xcb\x40\x00\x00\x00\x00\x00\x00\x00" "\xcb\x40\x08\x00\x00\x00\x00\x00\x00"_us)); @@ -282,8 +282,8 @@ TEST_F(WireEncoderBinaryTest, DoubleArray) { TEST_F(WireEncoderBinaryTest, StringArray) { net::WireEncodeBinary(os, 5, 6, Value::MakeStringArray({"hello", "bye"})); - ASSERT_THAT(out, wpi::SpanEq("\x94\x05\x06\x14\x92\xa5hello\xa3" + ASSERT_THAT(out, wpi::util::SpanEq("\x94\x05\x06\x14\x92\xa5hello\xa3" "bye"_us)); } -} // namespace nt +} // namespace wpi::nt diff --git a/ntcore/src/test/native/cpp/server/ServerImplTest.cpp b/ntcore/src/test/native/cpp/server/ServerImplTest.cpp index 207d182445..401414699c 100644 --- a/ntcore/src/test/native/cpp/server/ServerImplTest.cpp +++ b/ntcore/src/test/native/cpp/server/ServerImplTest.cpp @@ -41,7 +41,7 @@ using MockSetPeriodicFunc = ::testing::MockFunction; using MockConnected3Func = ::testing::MockFunction; -namespace nt { +namespace wpi::nt { class ServerImplTest : public ::testing::Test { public: @@ -85,7 +85,7 @@ TEST_F(ServerImplTest, AddClient3) {} template static std::string EncodeText1(const T& msg) { std::string data; - wpi::raw_string_ostream os{data}; + wpi::util::raw_string_ostream os{data}; net::WireEncodeText(os, msg); return data; } @@ -93,7 +93,7 @@ static std::string EncodeText1(const T& msg) { template static std::string EncodeText(const T& msgs) { std::string data; - wpi::raw_string_ostream os{data}; + wpi::util::raw_string_ostream os{data}; bool first = true; for (auto&& msg : msgs) { if (first) { @@ -111,7 +111,7 @@ static std::string EncodeText(const T& msgs) { template static std::vector EncodeServerBinary1(const T& msg) { std::vector data; - wpi::raw_uvector_ostream os{data}; + wpi::util::raw_uvector_ostream os{data}; if constexpr (std::same_as) { if (auto m = std::get_if(&msg.contents)) { net::WireEncodeBinary(os, m->topic, m->value.time(), m->value); @@ -128,7 +128,7 @@ static std::vector EncodeServerBinary1(const T& msg) { template static std::vector EncodeServerBinary(const T& msgs) { std::vector data; - wpi::raw_uvector_ostream os{data}; + wpi::util::raw_uvector_ostream os{data}; for (auto&& msg : msgs) { if constexpr (std::same_as) { if (auto m = std::get_if(&msg.contents)) { @@ -155,20 +155,20 @@ TEST_F(ServerImplTest, PublishLocal) { EXPECT_CALL( local, ServerAnnounce(std::string_view{"test"}, 0, std::string_view{"double"}, - wpi::json::object(), std::optional{pubuid})); + wpi::util::json::object(), std::optional{pubuid})); EXPECT_CALL( local, ServerAnnounce(std::string_view{"test2"}, 0, std::string_view{"double"}, - wpi::json::object(), std::optional{pubuid2})); + wpi::util::json::object(), std::optional{pubuid2})); EXPECT_CALL( local, ServerAnnounce(std::string_view{"test3"}, 0, std::string_view{"double"}, - wpi::json::object(), std::optional{pubuid3})); + wpi::util::json::object(), std::optional{pubuid3})); } { queue.msgs.emplace_back(net::ClientMessage{ - net::PublishMsg{pubuid, "test", "double", wpi::json::object(), {}}}); + net::PublishMsg{pubuid, "test", "double", wpi::util::json::object(), {}}}); EXPECT_FALSE(server.ProcessLocalMessages(UINT_MAX)); } @@ -187,17 +187,17 @@ TEST_F(ServerImplTest, PublishLocal) { EXPECT_CALL(wire, Ready()).WillOnce(Return(true)); // SendControl() EXPECT_CALL( wire, DoWriteText(StrEq(EncodeText1(net::ServerMessage{net::AnnounceMsg{ - "test", 3, "double", std::nullopt, wpi::json::object()}})))) + "test", 3, "double", std::nullopt, wpi::util::json::object()}})))) .WillOnce(Return(0)); EXPECT_CALL( wire, DoWriteText(StrEq(EncodeText1(net::ServerMessage{net::AnnounceMsg{ - "test2", 8, "double", std::nullopt, wpi::json::object()}})))) + "test2", 8, "double", std::nullopt, wpi::util::json::object()}})))) .WillOnce(Return(0)); EXPECT_CALL(wire, Flush()).WillOnce(Return(0)); // SendControl() EXPECT_CALL(wire, Ready()).WillOnce(Return(true)); // SendControl() EXPECT_CALL( wire, DoWriteText(StrEq(EncodeText1(net::ServerMessage{net::AnnounceMsg{ - "test3", 11, "double", std::nullopt, wpi::json::object()}})))) + "test3", 11, "double", std::nullopt, wpi::util::json::object()}})))) .WillOnce(Return(0)); EXPECT_CALL(wire, Flush()).WillOnce(Return(0)); // SendControl() } @@ -215,7 +215,7 @@ TEST_F(ServerImplTest, PublishLocal) { // publish before send control { queue.msgs.emplace_back(net::ClientMessage{ - net::PublishMsg{pubuid2, "test2", "double", wpi::json::object(), {}}}); + net::PublishMsg{pubuid2, "test2", "double", wpi::util::json::object(), {}}}); EXPECT_FALSE(server.ProcessLocalMessages(UINT_MAX)); } @@ -224,7 +224,7 @@ TEST_F(ServerImplTest, PublishLocal) { // publish after send control { queue.msgs.emplace_back(net::ClientMessage{ - net::PublishMsg{pubuid3, "test3", "double", wpi::json::object(), {}}}); + net::PublishMsg{pubuid3, "test3", "double", wpi::util::json::object(), {}}}); EXPECT_FALSE(server.ProcessLocalMessages(UINT_MAX)); } @@ -238,11 +238,11 @@ TEST_F(ServerImplTest, ClientSubTopicOnlyThenValue) { EXPECT_CALL( local, ServerAnnounce(std::string_view{"test"}, 0, std::string_view{"double"}, - wpi::json::object(), std::optional{pubuid})); + wpi::util::json::object(), std::optional{pubuid})); { queue.msgs.emplace_back(net::ClientMessage{ - net::PublishMsg{pubuid, "test", "double", wpi::json::object(), {}}}); + net::PublishMsg{pubuid, "test", "double", wpi::util::json::object(), {}}}); queue.msgs.emplace_back(net::ClientMessage{ net::ClientValueMsg{pubuid, Value::MakeDouble(1.0, 10)}}); EXPECT_FALSE(server.ProcessLocalMessages(UINT_MAX)); @@ -261,14 +261,14 @@ TEST_F(ServerImplTest, ClientSubTopicOnlyThenValue) { EXPECT_CALL(wire, Ready()).WillOnce(Return(true)); // SendValues() EXPECT_CALL( wire, DoWriteText(StrEq(EncodeText1(net::ServerMessage{net::AnnounceMsg{ - "test", 3, "double", std::nullopt, wpi::json::object()}})))) + "test", 3, "double", std::nullopt, wpi::util::json::object()}})))) .WillOnce(Return(0)); EXPECT_CALL(wire, Flush()).WillOnce(Return(0)); // SendValues() EXPECT_CALL(setPeriodic, Call(100)); // ClientSubscribe() // EXPECT_CALL(wire, Flush()).WillOnce(Return(0)); // ClientSubscribe() EXPECT_CALL(wire, Ready()).WillOnce(Return(true)); // SendValues() EXPECT_CALL( - wire, DoWriteBinary(wpi::SpanEq(EncodeServerBinary1(net::ServerMessage{ + wire, DoWriteBinary(wpi::util::SpanEq(EncodeServerBinary1(net::ServerMessage{ net::ServerValueMsg{3, Value::MakeDouble(1.0, 10)}})))) .WillOnce(Return(0)); EXPECT_CALL(wire, Flush()); // SendValues() @@ -312,17 +312,17 @@ TEST_F(ServerImplTest, ClientDisconnectUnpublish) { EXPECT_CALL( local, ServerAnnounce(std::string_view{"test2"}, 0, std::string_view{"double"}, - wpi::json::object(), std::optional{pubuidLocal})); + wpi::util::json::object(), std::optional{pubuidLocal})); EXPECT_CALL( local, ServerAnnounce(std::string_view{"test"}, 0, std::string_view{"double"}, - wpi::json::object(), std::optional{})); + wpi::util::json::object(), std::optional{})); EXPECT_CALL(local, ServerUnannounce(std::string_view{"test"}, 0)); } { queue.msgs.emplace_back(net::ClientMessage{net::PublishMsg{ - pubuidLocal, "test2", "double", wpi::json::object(), {}}}); + pubuidLocal, "test2", "double", wpi::util::json::object(), {}}}); queue.msgs.emplace_back(net::ClientMessage{ net::ClientValueMsg{pubuidLocal, Value::MakeDouble(1.0, 10)}}); EXPECT_FALSE(server.ProcessLocalMessages(UINT_MAX)); @@ -344,7 +344,7 @@ TEST_F(ServerImplTest, ClientDisconnectUnpublish) { EXPECT_CALL(wire, Ready()).WillOnce(Return(true)); // SendValues() EXPECT_CALL( wire, DoWriteText(StrEq(EncodeText1(net::ServerMessage{net::AnnounceMsg{ - "test", 8, "double", 1, wpi::json::object()}})))) + "test", 8, "double", 1, wpi::util::json::object()}})))) .WillOnce(Return(0)); EXPECT_CALL(wire, Flush()); // SendValues() } @@ -358,7 +358,7 @@ TEST_F(ServerImplTest, ClientDisconnectUnpublish) { constexpr int pubuid = 1; std::vector msgs; msgs.emplace_back(net::ClientMessage{ - net::PublishMsg{pubuid, "test", "double", wpi::json::object(), {}}}); + net::PublishMsg{pubuid, "test", "double", wpi::util::json::object(), {}}}); server.ProcessIncomingText(id, EncodeText(msgs)); } @@ -372,7 +372,7 @@ TEST_F(ServerImplTest, ZeroTimestampNegativeTime) { // publish before client connect server.SetLocal(&local, &queue); constexpr int pubuid = 1; - NT_Topic topicHandle = nt::Handle{0, 1, nt::Handle::kTopic}; + NT_Topic topicHandle = wpi::nt::Handle{0, 1, wpi::nt::Handle::kTopic}; constexpr int subuid = 1; Value defaultValue = Value::MakeDouble(1.0, 10); defaultValue.SetTime(0); @@ -383,7 +383,7 @@ TEST_F(ServerImplTest, ZeroTimestampNegativeTime) { EXPECT_CALL( local, ServerAnnounce(std::string_view{"test"}, 0, std::string_view{"double"}, - wpi::json::object(), std::optional{pubuid})) + wpi::util::json::object(), std::optional{pubuid})) .WillOnce(Return(topicHandle)); EXPECT_CALL(local, ServerSetValue(topicHandle, defaultValue)); EXPECT_CALL(local, ServerSetValue(topicHandle, value)); @@ -391,7 +391,7 @@ TEST_F(ServerImplTest, ZeroTimestampNegativeTime) { { queue.msgs.emplace_back(net::ClientMessage{ - net::PublishMsg{pubuid, "test", "double", wpi::json::object(), {}}}); + net::PublishMsg{pubuid, "test", "double", wpi::util::json::object(), {}}}); queue.msgs.emplace_back( net::ClientMessage{net::ClientValueMsg{pubuid, defaultValue}}); queue.msgs.emplace_back( @@ -415,7 +415,7 @@ TEST_F(ServerImplTest, ZeroTimestampNegativeTime) { constexpr int pubuid2 = 2; std::vector msgs; msgs.emplace_back(net::ClientMessage{ - net::PublishMsg{pubuid2, "test", "double", wpi::json::object(), {}}}); + net::PublishMsg{pubuid2, "test", "double", wpi::util::json::object(), {}}}); server.ProcessIncomingText(id, EncodeText(msgs)); msgs.clear(); msgs.emplace_back(net::ClientMessage{net::ClientValueMsg{pubuid2, value}}); @@ -439,4 +439,4 @@ TEST_F(ServerImplTest, InvalidPubUid) { "\"myvalue\",\"pubuid\":2147483647,\"properties\":{}}}]"); } -} // namespace nt +} // namespace wpi::nt diff --git a/ntcoreffi/src/main/native/cpp/DataLogManager.cpp b/ntcoreffi/src/main/native/cpp/DataLogManager.cpp index 737e55f048..6f5498a74b 100644 --- a/ntcoreffi/src/main/native/cpp/DataLogManager.cpp +++ b/ntcoreffi/src/main/native/cpp/DataLogManager.cpp @@ -185,7 +185,7 @@ inline void RemoveRefreshedDataEventHandle(WPI_EventHandle event) {} // } // namespace RobotBase // #endif -struct Thread final : public wpi::SafeThread { +struct Thread final : public wpi::util::SafeThread { Thread(std::string_view dir, std::string_view filename, double period); ~Thread() override; @@ -209,7 +209,7 @@ struct Thread final : public wpi::SafeThread { struct Instance { Instance(std::string_view dir, std::string_view filename, double period); - wpi::SafeThreadOwner owner; + wpi::util::SafeThreadOwner owner; }; } // namespace @@ -287,9 +287,9 @@ void Thread::Main() { std::vector entries; for (auto&& entry : fs::directory_iterator{m_logDir, ec}) { auto stem = entry.path().stem().string(); - if (wpi::starts_with(stem, "FRC_") && + if (wpi::util::starts_with(stem, "FRC_") && entry.path().extension() == ".wpilog" && - !wpi::starts_with(stem, "FRC_TBD_")) { + !wpi::util::starts_with(stem, "FRC_TBD_")) { entries.emplace_back(entry); } } @@ -313,7 +313,7 @@ void Thread::Main() { break; } } else { - wpi::print(stderr, "DataLogManager: could not delete {}\n", + wpi::util::print(stderr, "DataLogManager: could not delete {}\n", entry.path().string()); } } @@ -338,13 +338,13 @@ void Thread::Main() { m_log, "systemTime", "{\"source\":\"DataLogManager\",\"format\":\"time_t_us\"}"}; - wpi::Event newDataEvent; + wpi::util::Event newDataEvent; DriverStation::ProvideRefreshedDataEventHandle(newDataEvent.GetHandle()); for (;;) { bool timedOut = false; bool newData = - wpi::WaitForObject(newDataEvent.GetHandle(), 0.25, &timedOut); + wpi::util::WaitForObject(newDataEvent.GetHandle(), 0.25, &timedOut); if (!m_active) { break; } @@ -429,7 +429,7 @@ void Thread::Main() { if (sysTimeCount >= 250) { sysTimeCount = 0; if (RobotController::IsSystemTimeValid()) { - sysTimeEntry.Append(wpi::GetSystemTime(), wpi::Now()); + sysTimeEntry.Append(wpi::util::GetSystemTime(), wpi::util::Now()); } } } @@ -475,10 +475,10 @@ Instance::Instance(std::string_view dir, std::string_view filename, auto logDir = MakeLogDir(dir); std::error_code ec; for (auto&& entry : fs::directory_iterator{logDir, ec}) { - if (wpi::starts_with(entry.path().stem().string(), "FRC_TBD_") && + if (wpi::util::starts_with(entry.path().stem().string(), "FRC_TBD_") && entry.path().extension() == ".wpilog") { if (!fs::remove(entry, ec)) { - wpi::print(stderr, "DataLogManager: could not delete {}\n", + wpi::util::print(stderr, "DataLogManager: could not delete {}\n", entry.path().string()); } } @@ -510,7 +510,7 @@ void DataLogManager::Stop() { void DataLogManager::Log(std::string_view message) { GetInstance().owner.GetThread()->m_messageLog.Append(message); - wpi::print("{}\n", message); + wpi::util::print("{}\n", message); } wpi::log::DataLog& DataLogManager::GetLog() { @@ -542,14 +542,14 @@ void DataLogManager::LogConsoleOutput(bool enabled) { } void DataLogManager::SignalNewDSDataOccur() { - wpi::SetSignalObject(DriverStation::gNewDataEvent); + wpi::util::SetSignalObject(DriverStation::gNewDataEvent); } extern "C" { void DLM_Start(const struct WPI_String* dir, const struct WPI_String* filename, double period) { - DataLogManager::Start(wpi::to_string_view(dir), wpi::to_string_view(filename), + DataLogManager::Start(wpi::util::to_string_view(dir), wpi::util::to_string_view(filename), period); } @@ -558,7 +558,7 @@ void DLM_Stop(void) { } void DLM_Log(const struct WPI_String* message) { - DataLogManager::Log(wpi::to_string_view(message)); + DataLogManager::Log(wpi::util::to_string_view(message)); } WPI_DataLog* DLM_GetLog(void) { diff --git a/romiVendordep/src/main/native/cpp/romi/OnBoardIO.cpp b/romiVendordep/src/main/native/cpp/romi/OnBoardIO.cpp index 47db61f7bd..6bc7e67d5d 100644 --- a/romiVendordep/src/main/native/cpp/romi/OnBoardIO.cpp +++ b/romiVendordep/src/main/native/cpp/romi/OnBoardIO.cpp @@ -11,18 +11,18 @@ #include "wpi/system/Errors.hpp" #include "wpi/system/Timer.hpp" -using namespace frc; +using namespace wpi::romi; OnBoardIO::OnBoardIO(OnBoardIO::ChannelMode dio1, OnBoardIO::ChannelMode dio2) { if (dio1 == ChannelMode::INPUT) { - m_buttonB = std::make_unique(1); + m_buttonB = std::make_unique(1); } else { - m_greenLed = std::make_unique(1); + m_greenLed = std::make_unique(1); } if (dio2 == ChannelMode::INPUT) { - m_buttonC = std::make_unique(2); + m_buttonC = std::make_unique(2); } else { - m_redLed = std::make_unique(2); + m_redLed = std::make_unique(2); } } @@ -35,9 +35,9 @@ bool OnBoardIO::GetButtonBPressed() { return m_buttonB->Get(); } - auto currentTime = frc::Timer::GetTimestamp(); + auto currentTime = wpi::Timer::GetTimestamp(); if (currentTime > m_nextMessageTime) { - FRC_ReportError(frc::err::Error, "{}", "Button B was not configured"); + FRC_ReportError(wpi::err::Error, "{}", "Button B was not configured"); m_nextMessageTime = currentTime + kMessageInterval; } return false; @@ -48,9 +48,9 @@ bool OnBoardIO::GetButtonCPressed() { return m_buttonC->Get(); } - auto currentTime = frc::Timer::GetTimestamp(); + auto currentTime = wpi::Timer::GetTimestamp(); if (currentTime > m_nextMessageTime) { - FRC_ReportError(frc::err::Error, "{}", "Button C was not configured"); + FRC_ReportError(wpi::err::Error, "{}", "Button C was not configured"); m_nextMessageTime = currentTime + kMessageInterval; } return false; @@ -60,9 +60,9 @@ void OnBoardIO::SetGreenLed(bool value) { if (m_greenLed) { m_greenLed->Set(value); } else { - auto currentTime = frc::Timer::GetTimestamp(); + auto currentTime = wpi::Timer::GetTimestamp(); if (currentTime > m_nextMessageTime) { - FRC_ReportError(frc::err::Error, "{}", "Green LED was not configured"); + FRC_ReportError(wpi::err::Error, "{}", "Green LED was not configured"); m_nextMessageTime = currentTime + kMessageInterval; } } @@ -72,9 +72,9 @@ void OnBoardIO::SetRedLed(bool value) { if (m_redLed) { m_redLed->Set(value); } else { - auto currentTime = frc::Timer::GetTimestamp(); + auto currentTime = wpi::Timer::GetTimestamp(); if (currentTime > m_nextMessageTime) { - FRC_ReportError(frc::err::Error, "{}", "Red LED was not configured"); + FRC_ReportError(wpi::err::Error, "{}", "Red LED was not configured"); m_nextMessageTime = currentTime + kMessageInterval; } } diff --git a/romiVendordep/src/main/native/cpp/romi/RomiGyro.cpp b/romiVendordep/src/main/native/cpp/romi/RomiGyro.cpp index 0db60092ce..2ef94c0157 100644 --- a/romiVendordep/src/main/native/cpp/romi/RomiGyro.cpp +++ b/romiVendordep/src/main/native/cpp/romi/RomiGyro.cpp @@ -4,7 +4,7 @@ #include "wpi/romi/RomiGyro.hpp" -using namespace frc; +using namespace wpi::romi; RomiGyro::RomiGyro() : m_simDevice("Gyro:RomiGyro") { if (m_simDevice) { @@ -24,57 +24,57 @@ RomiGyro::RomiGyro() : m_simDevice("Gyro:RomiGyro") { } } -units::radian_t RomiGyro::GetAngle() const { +wpi::units::radian_t RomiGyro::GetAngle() const { return GetAngleZ(); } -units::radians_per_second_t RomiGyro::GetRate() const { +wpi::units::radians_per_second_t RomiGyro::GetRate() const { return GetRateZ(); } -units::radians_per_second_t RomiGyro::GetRateX() const { +wpi::units::radians_per_second_t RomiGyro::GetRateX() const { if (m_simRateX) { - return units::degrees_per_second_t{m_simRateX.Get()}; + return wpi::units::degrees_per_second_t{m_simRateX.Get()}; } return 0.0_rad_per_s; } -units::radians_per_second_t RomiGyro::GetRateY() const { +wpi::units::radians_per_second_t RomiGyro::GetRateY() const { if (m_simRateY) { - return units::degrees_per_second_t{m_simRateY.Get()}; + return wpi::units::degrees_per_second_t{m_simRateY.Get()}; } return 0.0_rad_per_s; } -units::radians_per_second_t RomiGyro::GetRateZ() const { +wpi::units::radians_per_second_t RomiGyro::GetRateZ() const { if (m_simRateZ) { - return units::degrees_per_second_t{m_simRateZ.Get()}; + return wpi::units::degrees_per_second_t{m_simRateZ.Get()}; } return 0.0_rad_per_s; } -units::radian_t RomiGyro::GetAngleX() const { +wpi::units::radian_t RomiGyro::GetAngleX() const { if (m_simAngleX) { - return units::degree_t{m_simAngleX.Get() - m_angleXOffset}; + return wpi::units::degree_t{m_simAngleX.Get() - m_angleXOffset}; } return 0.0_rad; } -units::radian_t RomiGyro::GetAngleY() const { +wpi::units::radian_t RomiGyro::GetAngleY() const { if (m_simAngleY) { - return units::degree_t{m_simAngleY.Get() - m_angleYOffset}; + return wpi::units::degree_t{m_simAngleY.Get() - m_angleYOffset}; } return 0.0_rad; } -units::radian_t RomiGyro::GetAngleZ() const { +wpi::units::radian_t RomiGyro::GetAngleZ() const { if (m_simAngleZ) { - return units::degree_t{m_simAngleZ.Get() - m_angleZOffset}; + return wpi::units::degree_t{m_simAngleZ.Get() - m_angleZOffset}; } return 0.0_rad; diff --git a/romiVendordep/src/main/native/cpp/romi/RomiMotor.cpp b/romiVendordep/src/main/native/cpp/romi/RomiMotor.cpp index 071e820043..b31ab0bfd9 100644 --- a/romiVendordep/src/main/native/cpp/romi/RomiMotor.cpp +++ b/romiVendordep/src/main/native/cpp/romi/RomiMotor.cpp @@ -4,7 +4,7 @@ #include "wpi/romi/RomiMotor.hpp" -using namespace frc; +using namespace wpi::romi; RomiMotor::RomiMotor(int channel) : PWMMotorController("Romi Motor", channel) { m_pwm.SetOutputPeriod(PWM::kOutputPeriod_5Ms); diff --git a/romiVendordep/src/main/native/include/wpi/romi/OnBoardIO.hpp b/romiVendordep/src/main/native/include/wpi/romi/OnBoardIO.hpp index 72530cd32c..4451575710 100644 --- a/romiVendordep/src/main/native/include/wpi/romi/OnBoardIO.hpp +++ b/romiVendordep/src/main/native/include/wpi/romi/OnBoardIO.hpp @@ -10,7 +10,7 @@ #include "wpi/hardware/discrete/DigitalOutput.hpp" #include "wpi/units/time.hpp" -namespace frc { +namespace wpi::romi { /** * @ingroup romi_api @@ -34,7 +34,7 @@ class OnBoardIO { OnBoardIO(OnBoardIO::ChannelMode dio1, OnBoardIO::ChannelMode dio2); static constexpr auto kMessageInterval = 1_s; - units::second_t m_nextMessageTime = 0_s; + wpi::units::second_t m_nextMessageTime = 0_s; /** * Gets if the A button is pressed. @@ -67,18 +67,18 @@ class OnBoardIO { void SetYellowLed(bool value); private: - frc::DigitalInput m_buttonA{0}; - frc::DigitalOutput m_yellowLed{3}; + wpi::DigitalInput m_buttonA{0}; + wpi::DigitalOutput m_yellowLed{3}; // DIO 1 - std::unique_ptr m_buttonB; - std::unique_ptr m_greenLed; + std::unique_ptr m_buttonB; + std::unique_ptr m_greenLed; // DIO 2 - std::unique_ptr m_buttonC; - std::unique_ptr m_redLed; + std::unique_ptr m_buttonC; + std::unique_ptr m_redLed; }; /** @} */ -} // namespace frc +} // namespace wpi::romi diff --git a/romiVendordep/src/main/native/include/wpi/romi/RomiGyro.hpp b/romiVendordep/src/main/native/include/wpi/romi/RomiGyro.hpp index cc468a6bdd..3179b784a9 100644 --- a/romiVendordep/src/main/native/include/wpi/romi/RomiGyro.hpp +++ b/romiVendordep/src/main/native/include/wpi/romi/RomiGyro.hpp @@ -8,7 +8,7 @@ #include "wpi/units/angle.hpp" #include "wpi/units/angular_velocity.hpp" -namespace frc { +namespace wpi::romi { /** * @ingroup romi_api @@ -35,7 +35,7 @@ class RomiGyro { * * @return The current heading of the robot. */ - units::radian_t GetAngle() const; + wpi::units::radian_t GetAngle() const; /** * Return the rate of rotation of the gyro @@ -44,49 +44,49 @@ class RomiGyro { * * @return The current rate. */ - units::radians_per_second_t GetRate() const; + wpi::units::radians_per_second_t GetRate() const; /** * Get the rate of turn in around the X-axis. * * @return Rate of turn. */ - units::radians_per_second_t GetRateX() const; + wpi::units::radians_per_second_t GetRateX() const; /** * Get the rate of turn in around the Y-axis. * * @return Rate of turn. */ - units::radians_per_second_t GetRateY() const; + wpi::units::radians_per_second_t GetRateY() const; /** * Get the rate of turn around the Z-axis. * * @return Rate of turn. */ - units::radians_per_second_t GetRateZ() const; + wpi::units::radians_per_second_t GetRateZ() const; /** * Get the currently reported angle around the X-axis. * * @return Current angle around X-axis. */ - units::radian_t GetAngleX() const; + wpi::units::radian_t GetAngleX() const; /** * Get the currently reported angle around the Y-axis. * * @return Current angle around Y-axis. */ - units::radian_t GetAngleY() const; + wpi::units::radian_t GetAngleY() const; /** * Get the currently reported angle around the Z-axis. * * @return Current angle around Z-axis. */ - units::radian_t GetAngleZ() const; + wpi::units::radian_t GetAngleZ() const; /** * Resets the gyro @@ -109,4 +109,4 @@ class RomiGyro { /** @} */ -} // namespace frc +} // namespace wpi::romi diff --git a/romiVendordep/src/main/native/include/wpi/romi/RomiMotor.hpp b/romiVendordep/src/main/native/include/wpi/romi/RomiMotor.hpp index 7542c7a72d..505735718f 100644 --- a/romiVendordep/src/main/native/include/wpi/romi/RomiMotor.hpp +++ b/romiVendordep/src/main/native/include/wpi/romi/RomiMotor.hpp @@ -6,7 +6,7 @@ #include "wpi/hardware/motor/PWMMotorController.hpp" -namespace frc { +namespace wpi::romi { /** * @defgroup romi_api Romi Hardware API @@ -34,4 +34,4 @@ class RomiMotor : public PWMMotorController { /** @} */ -} // namespace frc +} // namespace wpi::romi diff --git a/romiVendordep/src/main/python/semiwrap/OnBoardIO.yml b/romiVendordep/src/main/python/semiwrap/OnBoardIO.yml index 53fea27ab8..3f94510d8e 100644 --- a/romiVendordep/src/main/python/semiwrap/OnBoardIO.yml +++ b/romiVendordep/src/main/python/semiwrap/OnBoardIO.yml @@ -1,5 +1,5 @@ classes: - frc::OnBoardIO: + wpi::OnBoardIO: attributes: kMessageInterval: m_nextMessageTime: diff --git a/romiVendordep/src/main/python/semiwrap/RomiGyro.yml b/romiVendordep/src/main/python/semiwrap/RomiGyro.yml index 4544bd5fd0..246fba0e22 100644 --- a/romiVendordep/src/main/python/semiwrap/RomiGyro.yml +++ b/romiVendordep/src/main/python/semiwrap/RomiGyro.yml @@ -1,5 +1,5 @@ classes: - frc::RomiGyro: + wpi::RomiGyro: methods: RomiGyro: GetAngle: diff --git a/romiVendordep/src/main/python/semiwrap/RomiMotor.yml b/romiVendordep/src/main/python/semiwrap/RomiMotor.yml index b75fa2c5ad..34dbf5ee48 100644 --- a/romiVendordep/src/main/python/semiwrap/RomiMotor.yml +++ b/romiVendordep/src/main/python/semiwrap/RomiMotor.yml @@ -1,4 +1,4 @@ classes: - frc::RomiMotor: + wpi::RomiMotor: methods: RomiMotor: diff --git a/simulation/halsim_ds_socket/src/main/native/cpp/DSCommPacket.cpp b/simulation/halsim_ds_socket/src/main/native/cpp/DSCommPacket.cpp index 9cb84afdc5..6f94dc16fd 100644 --- a/simulation/halsim_ds_socket/src/main/native/cpp/DSCommPacket.cpp +++ b/simulation/halsim_ds_socket/src/main/native/cpp/DSCommPacket.cpp @@ -281,12 +281,12 @@ void DSCommPacket::SendJoysticks(void) { } } -void DSCommPacket::SetupSendBuffer(wpi::raw_uv_ostream& buf) { +void DSCommPacket::SetupSendBuffer(wpi::net::raw_uv_ostream& buf) { SetupSendHeader(buf); SetupJoystickTag(buf); } -void DSCommPacket::SetupSendHeader(wpi::raw_uv_ostream& buf) { +void DSCommPacket::SetupSendHeader(wpi::net::raw_uv_ostream& buf) { static constexpr uint8_t kCommVersion = 0x01; // High low packet index, comm version @@ -303,7 +303,7 @@ void DSCommPacket::SetupSendHeader(wpi::raw_uv_ostream& buf) { buf << static_cast(0); } -void DSCommPacket::SetupJoystickTag(wpi::raw_uv_ostream& buf) { +void DSCommPacket::SetupJoystickTag(wpi::net::raw_uv_ostream& buf) { static constexpr uint8_t kHIDTag = 0x01; // HID tags are sent 1 per device diff --git a/simulation/halsim_ds_socket/src/main/native/cpp/main.cpp b/simulation/halsim_ds_socket/src/main/native/cpp/main.cpp index 4fc36af0d8..9934110cbd 100644 --- a/simulation/halsim_ds_socket/src/main/native/cpp/main.cpp +++ b/simulation/halsim_ds_socket/src/main/native/cpp/main.cpp @@ -34,14 +34,14 @@ #pragma comment(lib, "Ws2_32.lib") #endif -using namespace wpi::uv; +using namespace wpi::net::uv; static std::unique_ptr singleByte; static std::atomic gDSConnected = false; namespace { struct DataStore { - wpi::SmallVector m_frame; + wpi::util::SmallVector m_frame; size_t m_frameSize = (std::numeric_limits::max)(); halsim::DSCommPacket* dsPacket; }; @@ -83,7 +83,7 @@ static void HandleTcpDataStream(Buffer& buf, size_t size, DataStore& store) { } } -static void SetupTcp(wpi::uv::Loop& loop) { +static void SetupTcp(wpi::net::uv::Loop& loop) { auto tcp = Tcp::Create(loop); auto tcpWaitTimer = Timer::Create(loop); @@ -109,8 +109,8 @@ static void SetupTcp(wpi::uv::Loop& loop) { }); } -static void SetupUdp(wpi::uv::Loop& loop) { - auto udp = wpi::uv::Udp::Create(loop); +static void SetupUdp(wpi::net::uv::Loop& loop) { + auto udp = wpi::net::uv::Udp::Create(loop); udp->Bind("0.0.0.0", 1110); // Simulation mode packet @@ -120,7 +120,7 @@ static void SetupUdp(wpi::uv::Loop& loop) { simLoopTimer->timeout.connect([udpLocal = udp.get(), simAddr] { udpLocal->Send(simAddr, {singleByte.get(), 1}, [](auto buf, Error err) { if (err) { - wpi::print(stderr, "{}\n", err.str()); + wpi::util::print(stderr, "{}\n", err.str()); std::fflush(stderr); } }); @@ -132,7 +132,7 @@ static void SetupUdp(wpi::uv::Loop& loop) { try { timeoutMs = std::stoi(envTimeout); } catch (const std::exception& e) { - wpi::print(stderr, "Error parsing DS_TIMEOUT_MS: {}\n", e.what()); + wpi::util::print(stderr, "Error parsing DS_TIMEOUT_MS: {}\n", e.what()); } } auto autoDisableTimer = Timer::Create(loop); @@ -151,15 +151,15 @@ static void SetupUdp(wpi::uv::Loop& loop) { outAddr.sin_family = PF_INET; outAddr.sin_port = htons(1150); - wpi::SmallVector sendBufs; - wpi::raw_uv_ostream stream{sendBufs, + wpi::util::SmallVector sendBufs; + wpi::net::raw_uv_ostream stream{sendBufs, [] { return GetBufferPool().Allocate(); }}; ds->SetupSendBuffer(stream); udpLocal->Send(outAddr, sendBufs, [](auto bufs, Error err) { GetBufferPool().Release(bufs); if (err) { - wpi::print(stderr, "{}\n", err.str()); + wpi::util::print(stderr, "{}\n", err.str()); std::fflush(stderr); } }); @@ -169,14 +169,14 @@ static void SetupUdp(wpi::uv::Loop& loop) { udp->StartRecv(); } -static void SetupEventLoop(wpi::uv::Loop& loop) { +static void SetupEventLoop(wpi::net::uv::Loop& loop) { auto loopData = std::make_shared(); loop.SetData(loopData); SetupUdp(loop); SetupTcp(loop); } -static std::unique_ptr eventLoopRunner; +static std::unique_ptr eventLoopRunner; /*---------------------------------------------------------------------------- ** Main entry point. We will start listen threads going, processing @@ -201,7 +201,7 @@ int HALSIM_InitExtension(void) { singleByte = std::make_unique("0"); - eventLoopRunner = std::make_unique(); + eventLoopRunner = std::make_unique(); eventLoopRunner->ExecAsync(SetupEventLoop); diff --git a/simulation/halsim_ds_socket/src/main/native/include/wpi/halsim/ds_socket/DSCommPacket.hpp b/simulation/halsim_ds_socket/src/main/native/include/wpi/halsim/ds_socket/DSCommPacket.hpp index 327adcd25f..0a55c01ffa 100644 --- a/simulation/halsim_ds_socket/src/main/native/include/wpi/halsim/ds_socket/DSCommPacket.hpp +++ b/simulation/halsim_ds_socket/src/main/native/include/wpi/halsim/ds_socket/DSCommPacket.hpp @@ -23,7 +23,7 @@ class DSCommPacket { void DecodeTCP(std::span packet); void DecodeUDP(std::span packet); void SendUDPToHALSim(void); - void SetupSendBuffer(wpi::raw_uv_ostream& buf); + void SetupSendBuffer(wpi::net::raw_uv_ostream& buf); /* TCP Tags */ static const uint8_t kGameDataTag = 0x0e; @@ -51,8 +51,8 @@ class DSCommPacket { void SendJoysticks(void); void SetControl(uint8_t control, uint8_t request); void SetAlliance(uint8_t station_code); - void SetupSendHeader(wpi::raw_uv_ostream& buf); - void SetupJoystickTag(wpi::raw_uv_ostream& buf); + void SetupSendHeader(wpi::net::raw_uv_ostream& buf); + void SetupJoystickTag(wpi::net::raw_uv_ostream& buf); void ReadMatchtimeTag(std::span tagData); void ReadJoystickTag(std::span data, int index); void ReadNewMatchInfoTag(std::span data); diff --git a/simulation/halsim_gui/src/main/native/cpp/AddressableLEDGui.cpp b/simulation/halsim_gui/src/main/native/cpp/AddressableLEDGui.cpp index 15f0a592fb..9ee2cade12 100644 --- a/simulation/halsim_gui/src/main/native/cpp/AddressableLEDGui.cpp +++ b/simulation/halsim_gui/src/main/native/cpp/AddressableLEDGui.cpp @@ -17,7 +17,7 @@ using namespace halsimgui; namespace { -class AddressableLEDModel : public glass::LEDDisplayModel { +class AddressableLEDModel : public wpi::glass::LEDDisplayModel { public: explicit AddressableLEDModel(int32_t channel) : m_channel{channel} {} @@ -26,7 +26,7 @@ class AddressableLEDModel : public glass::LEDDisplayModel { return HALSIM_GetAddressableLEDInitialized(m_channel); } - std::span GetData(wpi::SmallVectorImpl&) override { + std::span GetData(wpi::util::SmallVectorImpl&) override { size_t length = HALSIM_GetAddressableLEDData( HALSIM_GetAddressableLEDStart(m_channel), HALSIM_GetAddressableLEDLength(m_channel), m_data); @@ -39,7 +39,7 @@ class AddressableLEDModel : public glass::LEDDisplayModel { HAL_AddressableLEDData m_data[HAL_kAddressableLEDMaxLength]; }; -class AddressableLEDsModel : public glass::LEDDisplaysModel { +class AddressableLEDsModel : public wpi::glass::LEDDisplaysModel { public: AddressableLEDsModel() : m_models(HAL_GetNumAddressableLEDs()) {} @@ -49,7 +49,7 @@ class AddressableLEDsModel : public glass::LEDDisplaysModel { size_t GetNumLEDDisplays() override { return m_models.size(); } void ForEachLEDDisplay( - wpi::function_ref func) + wpi::util::function_ref func) override; private: @@ -83,7 +83,7 @@ bool AddressableLEDsModel::Exists() { } void AddressableLEDsModel::ForEachLEDDisplay( - wpi::function_ref func) { + wpi::util::function_ref func) { for (int i = 0; i < static_cast(m_models.size()); ++i) { if (m_models[i]) { func(*m_models[i], i); @@ -105,11 +105,11 @@ void AddressableLEDGui::Initialize() { HALSimGui::halProvider->Register( "Addressable LEDs", [] { return AddressableLEDsExists(); }, [] { return std::make_unique(); }, - [](glass::Window* win, glass::Model* model) { + [](wpi::glass::Window* win, wpi::glass::Model* model) { win->SetFlags(ImGuiWindowFlags_AlwaysAutoResize); win->SetDefaultPos(290, 100); - return glass::MakeFunctionView([=] { - glass::DisplayLEDDisplays(static_cast(model)); + return wpi::glass::MakeFunctionView([=] { + wpi::glass::DisplayLEDDisplays(static_cast(model)); }); }); } diff --git a/simulation/halsim_gui/src/main/native/cpp/AnalogInputSimGui.cpp b/simulation/halsim_gui/src/main/native/cpp/AnalogInputSimGui.cpp index 3faa56a9bd..992064a485 100644 --- a/simulation/halsim_gui/src/main/native/cpp/AnalogInputSimGui.cpp +++ b/simulation/halsim_gui/src/main/native/cpp/AnalogInputSimGui.cpp @@ -20,7 +20,7 @@ using namespace halsimgui; namespace { HALSIMGUI_DATASOURCE_DOUBLE_INDEXED(AnalogInVoltage, "AIn"); -class AnalogInputSimModel : public glass::AnalogInputModel { +class AnalogInputSimModel : public wpi::glass::AnalogInputModel { public: explicit AnalogInputSimModel(int32_t index) : m_index{index}, m_voltageData{m_index} {} @@ -37,7 +37,7 @@ class AnalogInputSimModel : public glass::AnalogInputModel { } } - glass::DoubleSource* GetVoltageData() override { return &m_voltageData; } + wpi::glass::DoubleSource* GetVoltageData() override { return &m_voltageData; } void SetVoltage(double val) override { HALSIM_SetAnalogInVoltage(m_index, val); @@ -48,7 +48,7 @@ class AnalogInputSimModel : public glass::AnalogInputModel { AnalogInVoltageSource m_voltageData; }; -class AnalogInputsSimModel : public glass::AnalogInputsModel { +class AnalogInputsSimModel : public wpi::glass::AnalogInputsModel { public: AnalogInputsSimModel() : m_models(HAL_GetNumAnalogInputs()) {} @@ -57,7 +57,7 @@ class AnalogInputsSimModel : public glass::AnalogInputsModel { bool Exists() override { return true; } void ForEachAnalogInput( - wpi::function_ref func) + wpi::util::function_ref func) override; private: @@ -81,7 +81,7 @@ void AnalogInputsSimModel::Update() { } void AnalogInputsSimModel::ForEachAnalogInput( - wpi::function_ref func) { + wpi::util::function_ref func) { for (int32_t i = 0, iend = static_cast(m_models.size()); i < iend; ++i) { if (auto model = m_models[i].get()) { @@ -104,11 +104,11 @@ void AnalogInputSimGui::Initialize() { HALSimGui::halProvider->Register( "Analog Inputs", AnalogInputsAnyInitialized, [] { return std::make_unique(); }, - [](glass::Window* win, glass::Model* model) { + [](wpi::glass::Window* win, wpi::glass::Model* model) { win->SetFlags(ImGuiWindowFlags_AlwaysAutoResize); win->SetDefaultPos(640, 20); - return glass::MakeFunctionView([=] { - glass::DisplayAnalogInputs(static_cast(model)); + return wpi::glass::MakeFunctionView([=] { + wpi::glass::DisplayAnalogInputs(static_cast(model)); }); }); } diff --git a/simulation/halsim_gui/src/main/native/cpp/DIOSimGui.cpp b/simulation/halsim_gui/src/main/native/cpp/DIOSimGui.cpp index 73dc70cc28..45620ccc50 100644 --- a/simulation/halsim_gui/src/main/native/cpp/DIOSimGui.cpp +++ b/simulation/halsim_gui/src/main/native/cpp/DIOSimGui.cpp @@ -26,7 +26,7 @@ HALSIMGUI_DATASOURCE_BOOLEAN_INDEXED(DIOValue, "DIO"); HALSIMGUI_DATASOURCE_DOUBLE_INDEXED(DigitalPWMDutyCycle, "DPWM"); HALSIMGUI_DATASOURCE_DOUBLE_INDEXED(DutyCycleOutput, "DutyCycle"); -class DPWMSimModel : public glass::DPWMModel { +class DPWMSimModel : public wpi::glass::DPWMModel { public: DPWMSimModel(int32_t index, int32_t dioChannel) : m_dioChannel{dioChannel}, m_index{index}, m_valueData{index} {} @@ -43,7 +43,7 @@ class DPWMSimModel : public glass::DPWMModel { } } - glass::DoubleSource* GetValueData() override { return &m_valueData; } + wpi::glass::DoubleSource* GetValueData() override { return &m_valueData; } void SetValue(double val) override { HALSIM_SetDigitalPWMDutyCycle(m_index, val); @@ -55,7 +55,7 @@ class DPWMSimModel : public glass::DPWMModel { DigitalPWMDutyCycleSource m_valueData; }; -class DutyCycleSimModel : public glass::DutyCycleModel { +class DutyCycleSimModel : public wpi::glass::DutyCycleModel { public: explicit DutyCycleSimModel(int32_t index) : m_index{index}, m_valueData{index} {} @@ -72,7 +72,7 @@ class DutyCycleSimModel : public glass::DutyCycleModel { } } - glass::DoubleSource* GetValueData() override { return &m_valueData; } + wpi::glass::DoubleSource* GetValueData() override { return &m_valueData; } void SetValue(double val) override { HALSIM_SetDutyCycleOutput(m_index, val); @@ -83,7 +83,7 @@ class DutyCycleSimModel : public glass::DutyCycleModel { DutyCycleOutputSource m_valueData; }; -class DIOSimModel : public glass::DIOModel { +class DIOSimModel : public wpi::glass::DIOModel { public: explicit DIOSimModel(int32_t channel) : m_channel{channel}, m_valueData{channel} {} @@ -106,15 +106,15 @@ class DIOSimModel : public glass::DIOModel { DPWMSimModel* GetDPWM() override { return m_dpwmSource; } DutyCycleSimModel* GetDutyCycle() override { return m_dutyCycleSource; } - glass::EncoderModel* GetEncoder() override { return m_encoderSource; } + wpi::glass::EncoderModel* GetEncoder() override { return m_encoderSource; } void SetDPWM(DPWMSimModel* model) { m_dpwmSource = model; } void SetDutyCycle(DutyCycleSimModel* model) { m_dutyCycleSource = model; } - void SetEncoder(glass::EncoderModel* model) { m_encoderSource = model; } + void SetEncoder(wpi::glass::EncoderModel* model) { m_encoderSource = model; } bool IsInput() const override { return HALSIM_GetDIOIsInput(m_channel); } - glass::BooleanSource* GetValueData() override { return &m_valueData; } + wpi::glass::BooleanSource* GetValueData() override { return &m_valueData; } void SetValue(bool val) override { HALSIM_SetDIOValue(m_channel, val); } @@ -123,10 +123,10 @@ class DIOSimModel : public glass::DIOModel { DIOValueSource m_valueData; DPWMSimModel* m_dpwmSource = nullptr; DutyCycleSimModel* m_dutyCycleSource = nullptr; - glass::EncoderModel* m_encoderSource = nullptr; + wpi::glass::EncoderModel* m_encoderSource = nullptr; }; -class DIOsSimModel : public glass::DIOsModel { +class DIOsSimModel : public wpi::glass::DIOsModel { public: DIOsSimModel() : m_dioModels(HAL_GetNumDigitalChannels()), @@ -138,7 +138,7 @@ class DIOsSimModel : public glass::DIOsModel { bool Exists() override { return true; } void ForEachDIO( - wpi::function_ref func) override; + wpi::util::function_ref func) override; private: // indexed by channel @@ -210,7 +210,7 @@ void DIOsSimModel::Update() { } void DIOsSimModel::ForEachDIO( - wpi::function_ref func) { + wpi::util::function_ref func) { const int32_t numDIO = m_dioModels.size(); for (int32_t i = 0; i < numDIO; ++i) { if (auto model = m_dioModels[i].get()) { @@ -232,11 +232,11 @@ static bool DIOAnyInitialized() { void DIOSimGui::Initialize() { HALSimGui::halProvider->Register( "DIO", DIOAnyInitialized, [] { return std::make_unique(); }, - [](glass::Window* win, glass::Model* model) { + [](wpi::glass::Window* win, wpi::glass::Model* model) { win->SetFlags(ImGuiWindowFlags_AlwaysAutoResize); win->SetDefaultPos(470, 20); - return glass::MakeFunctionView([=] { - glass::DisplayDIOs(static_cast(model), + return wpi::glass::MakeFunctionView([=] { + wpi::glass::DisplayDIOs(static_cast(model), HALSimGui::halProvider->AreOutputsEnabled()); }); }); diff --git a/simulation/halsim_gui/src/main/native/cpp/DriverStationGui.cpp b/simulation/halsim_gui/src/main/native/cpp/DriverStationGui.cpp index b6be9790e7..25aaab7325 100644 --- a/simulation/halsim_gui/src/main/native/cpp/DriverStationGui.cpp +++ b/simulation/halsim_gui/src/main/native/cpp/DriverStationGui.cpp @@ -94,7 +94,7 @@ class GlfwSystemJoystick : public SystemJoystick { class KeyboardJoystick : public SystemJoystick { public: - KeyboardJoystick(glass::Storage& storage, int index); + KeyboardJoystick(wpi::glass::Storage& storage, int index); void SettingsDisplay() override; void Update() override; @@ -124,7 +124,7 @@ class KeyboardJoystick : public SystemJoystick { int& m_povCount; struct AxisConfig { - explicit AxisConfig(glass::Storage& storage); + explicit AxisConfig(wpi::glass::Storage& storage); int& incKey; int& decKey; @@ -133,14 +133,14 @@ class KeyboardJoystick : public SystemJoystick { float& maxAbsValue; }; - std::vector>& m_axisStorage; + std::vector>& m_axisStorage; std::vector m_axisConfig; static constexpr int kMaxButtonCount = 32; std::vector& m_buttonKey; struct PovConfig { - explicit PovConfig(glass::Storage& storage); + explicit PovConfig(wpi::glass::Storage& storage); int& keyUp; int& keyUpRight; @@ -152,21 +152,21 @@ class KeyboardJoystick : public SystemJoystick { int& keyUpLeft; }; - std::vector>& m_povStorage; + std::vector>& m_povStorage; std::vector m_povConfig; }; class GlfwKeyboardJoystick : public KeyboardJoystick { public: - GlfwKeyboardJoystick(glass::Storage& storage, int index); + GlfwKeyboardJoystick(wpi::glass::Storage& storage, int index); const char* GetKeyName(int key) const override; }; struct RobotJoystick { - explicit RobotJoystick(glass::Storage& storage); + explicit RobotJoystick(wpi::glass::Storage& storage); - glass::NameSetting name; + wpi::glass::NameSetting name; std::string& guid; const SystemJoystick* sys = nullptr; bool& useGamepad; // = false; @@ -197,11 +197,11 @@ class JoystickModel { int axisCount; int buttonCount; int povCount; - std::unique_ptr axes[HAL_kMaxJoystickAxes]; + std::unique_ptr axes[HAL_kMaxJoystickAxes]; // use pointer instead of unique_ptr to allow it to be passed directly // to DrawLEDSources() - glass::BooleanSource* buttons[32]; - std::unique_ptr povs[HAL_kMaxJoystickPOVs]; + wpi::glass::BooleanSource* buttons[32]; + std::unique_ptr povs[HAL_kMaxJoystickPOVs]; private: static void CallbackFunc(const char*, void* param, const HAL_Value*); @@ -210,21 +210,21 @@ class JoystickModel { int32_t m_callback; }; -class FMSSimModel : public glass::FMSModel { +class FMSSimModel : public wpi::glass::FMSModel { public: FMSSimModel(); - glass::BooleanSource* GetFmsAttachedData() override { return &m_fmsAttached; } - glass::BooleanSource* GetDsAttachedData() override { return &m_dsAttached; } - glass::IntegerSource* GetAllianceStationIdData() override { + wpi::glass::BooleanSource* GetFmsAttachedData() override { return &m_fmsAttached; } + wpi::glass::BooleanSource* GetDsAttachedData() override { return &m_dsAttached; } + wpi::glass::IntegerSource* GetAllianceStationIdData() override { return &m_allianceStationId; } - glass::DoubleSource* GetMatchTimeData() override { return &m_matchTime; } - glass::BooleanSource* GetEStopData() override { return &m_estop; } - glass::BooleanSource* GetEnabledData() override { return &m_enabled; } - glass::BooleanSource* GetTestData() override { return &m_test; } - glass::BooleanSource* GetAutonomousData() override { return &m_autonomous; } - glass::StringSource* GetGameSpecificMessageData() override { + wpi::glass::DoubleSource* GetMatchTimeData() override { return &m_matchTime; } + wpi::glass::BooleanSource* GetEStopData() override { return &m_estop; } + wpi::glass::BooleanSource* GetEnabledData() override { return &m_enabled; } + wpi::glass::BooleanSource* GetTestData() override { return &m_test; } + wpi::glass::BooleanSource* GetAutonomousData() override { return &m_autonomous; } + wpi::glass::StringSource* GetGameSpecificMessageData() override { return &m_gameMessage; } @@ -251,16 +251,16 @@ class FMSSimModel : public glass::FMSModel { bool IsReadOnly() override; private: - glass::BooleanSource m_fmsAttached{"FMS:FMSAttached"}; - glass::BooleanSource m_dsAttached{"FMS:DSAttached"}; - glass::IntegerSource m_allianceStationId{"FMS:AllianceStationID"}; - glass::DoubleSource m_matchTime{"FMS:MatchTime"}; - glass::BooleanSource m_estop{"FMS:EStop"}; - glass::BooleanSource m_enabled{"FMS:RobotEnabled"}; - glass::BooleanSource m_test{"FMS:TestMode"}; - glass::BooleanSource m_autonomous{"FMS:AutonomousMode"}; + wpi::glass::BooleanSource m_fmsAttached{"FMS:FMSAttached"}; + wpi::glass::BooleanSource m_dsAttached{"FMS:DSAttached"}; + wpi::glass::IntegerSource m_allianceStationId{"FMS:AllianceStationID"}; + wpi::glass::DoubleSource m_matchTime{"FMS:MatchTime"}; + wpi::glass::BooleanSource m_estop{"FMS:EStop"}; + wpi::glass::BooleanSource m_enabled{"FMS:RobotEnabled"}; + wpi::glass::BooleanSource m_test{"FMS:TestMode"}; + wpi::glass::BooleanSource m_autonomous{"FMS:AutonomousMode"}; double m_startMatchTime = -1.0; - glass::StringSource m_gameMessage{"FMS:GameSpecificMessage"}; + wpi::glass::StringSource m_gameMessage{"FMS:GameSpecificMessage"}; }; } // namespace @@ -296,7 +296,7 @@ JoystickModel::JoystickModel(int index) : m_index{index} { HALSIM_GetJoystickAxes(index, &halAxes); axisCount = static_cast(16 - std::countl_zero(halAxes.available)); for (int i = 0; i < axisCount; ++i) { - axes[i] = std::make_unique( + axes[i] = std::make_unique( fmt::format("Joystick[{}] Axis[{}]", index, i)); } @@ -305,7 +305,7 @@ JoystickModel::JoystickModel(int index) : m_index{index} { buttonCount = static_cast(64 - std::countl_zero(halButtons.available)); for (int i = 0; i < buttonCount; ++i) { - buttons[i] = new glass::BooleanSource( + buttons[i] = new wpi::glass::BooleanSource( fmt::format("Joystick[{}] Button[{}]", index, i + 1)); } for (int i = buttonCount; i < 64; ++i) { @@ -316,7 +316,7 @@ JoystickModel::JoystickModel(int index) : m_index{index} { HALSIM_GetJoystickPOVs(index, &halPOVs); povCount = static_cast(8 - std::countl_zero(halPOVs.available)); for (int i = 0; i < povCount; ++i) { - povs[i] = std::make_unique( + povs[i] = std::make_unique( fmt::format("Joystick[{}] POV [{}]", index, i)); } @@ -468,7 +468,7 @@ void GlfwSystemJoystick::GetData(HALJoystickData* data, bool mapGamepad) const { } } -KeyboardJoystick::AxisConfig::AxisConfig(glass::Storage& storage) +KeyboardJoystick::AxisConfig::AxisConfig(wpi::glass::Storage& storage) : incKey{storage.GetInt("incKey", -1)}, decKey{storage.GetInt("decKey", -1)}, keyRate{storage.GetFloat("keyRate", 0.05f)}, @@ -483,7 +483,7 @@ KeyboardJoystick::AxisConfig::AxisConfig(glass::Storage& storage) } } -KeyboardJoystick::PovConfig::PovConfig(glass::Storage& storage) +KeyboardJoystick::PovConfig::PovConfig(wpi::glass::Storage& storage) : keyUp{storage.GetInt("keyUp", -1)}, keyUpRight{storage.GetInt("keyUpRight", -1)}, keyRight{storage.GetInt("keyRight", -1)}, @@ -519,7 +519,7 @@ KeyboardJoystick::PovConfig::PovConfig(glass::Storage& storage) } } -KeyboardJoystick::KeyboardJoystick(glass::Storage& storage, int index) +KeyboardJoystick::KeyboardJoystick(wpi::glass::Storage& storage, int index) : m_index{index}, m_axisCount{storage.GetInt("axisCount", -1)}, m_buttonCount{storage.GetInt("buttonCount", -1)}, @@ -527,8 +527,8 @@ KeyboardJoystick::KeyboardJoystick(glass::Storage& storage, int index) m_axisStorage{storage.GetChildArray("axisConfig")}, m_buttonKey{storage.GetIntArray("buttonKeys")}, m_povStorage{storage.GetChildArray("povConfig")} { - wpi::format_to_n_c_str(m_name, sizeof(m_name), "Keyboard {}", index); - wpi::format_to_n_c_str(m_guid, sizeof(m_guid), "Keyboard{}", index); + wpi::util::format_to_n_c_str(m_name, sizeof(m_name), "Keyboard {}", index); + wpi::util::format_to_n_c_str(m_guid, sizeof(m_guid), "Keyboard{}", index); // init axes for (auto&& axisConfig : m_axisStorage) { @@ -562,9 +562,9 @@ void KeyboardJoystick::EditKey(const char* label, int* key) { char editLabel[32]; if (s_keyEdit == key) { - wpi::format_to_n_c_str(editLabel, sizeof(editLabel), "(press key)###edit"); + wpi::util::format_to_n_c_str(editLabel, sizeof(editLabel), "(press key)###edit"); } else { - wpi::format_to_n_c_str(editLabel, sizeof(editLabel), "{}###edit", + wpi::util::format_to_n_c_str(editLabel, sizeof(editLabel), "{}###edit", GetKeyName(*key)); } @@ -608,11 +608,11 @@ void KeyboardJoystick::SettingsDisplay() { } } while (m_axisCount > static_cast(m_axisConfig.size())) { - m_axisStorage.emplace_back(std::make_unique()); + m_axisStorage.emplace_back(std::make_unique()); m_axisConfig.emplace_back(*m_axisStorage.back()); } for (int i = 0; i < m_axisCount; ++i) { - wpi::format_to_n_c_str(label, sizeof(label), "Axis {}", i); + wpi::util::format_to_n_c_str(label, sizeof(label), "Axis {}", i); if (ImGui::TreeNodeEx(label, ImGuiTreeNodeFlags_DefaultOpen)) { EditKey("Increase", &m_axisConfig[i].incKey); @@ -646,7 +646,7 @@ void KeyboardJoystick::SettingsDisplay() { m_buttonKey.emplace_back(-1); } for (int i = 0; i < m_buttonCount; ++i) { - wpi::format_to_n_c_str(label, sizeof(label), "Button {}", i + 1); + wpi::util::format_to_n_c_str(label, sizeof(label), "Button {}", i + 1); EditKey(label, &m_buttonKey[i]); } @@ -665,11 +665,11 @@ void KeyboardJoystick::SettingsDisplay() { } } while (m_povCount > static_cast(m_povConfig.size())) { - m_povStorage.emplace_back(std::make_unique()); + m_povStorage.emplace_back(std::make_unique()); m_povConfig.emplace_back(*m_povStorage.back()); } for (int i = 0; i < m_povCount; ++i) { - wpi::format_to_n_c_str(label, sizeof(label), "POV {}", i); + wpi::util::format_to_n_c_str(label, sizeof(label), "POV {}", i); if (ImGui::TreeNodeEx(label, ImGuiTreeNodeFlags_DefaultOpen)) { EditKey(" Up", &m_povConfig[i].keyUp); @@ -842,14 +842,14 @@ void KeyboardJoystick::ClearKey(int key) { } } -GlfwKeyboardJoystick::GlfwKeyboardJoystick(glass::Storage& storage, int index) +GlfwKeyboardJoystick::GlfwKeyboardJoystick(wpi::glass::Storage& storage, int index) : KeyboardJoystick{storage, index} { // set up a default keyboard config for 0, 1, and 2 if (index == 0) { if (m_axisCount == -1 && m_axisStorage.empty()) { m_axisCount = 3; for (int i = 0; i < 3; ++i) { - m_axisStorage.emplace_back(std::make_unique()); + m_axisStorage.emplace_back(std::make_unique()); m_axisConfig.emplace_back(*m_axisStorage.back()); } m_axisConfig[0].incKey = GLFW_KEY_D; @@ -871,7 +871,7 @@ GlfwKeyboardJoystick::GlfwKeyboardJoystick(glass::Storage& storage, int index) } if (m_povCount == -1 && m_povStorage.empty()) { m_povCount = 1; - m_povStorage.emplace_back(std::make_unique()); + m_povStorage.emplace_back(std::make_unique()); m_povConfig.emplace_back(*m_povStorage.back()); m_povConfig[0].keyUp = GLFW_KEY_KP_8; m_povConfig[0].keyUpRight = GLFW_KEY_KP_9; @@ -886,7 +886,7 @@ GlfwKeyboardJoystick::GlfwKeyboardJoystick(glass::Storage& storage, int index) if (m_axisCount == -1 && m_axisStorage.empty()) { m_axisCount = 2; for (int i = 0; i < 2; ++i) { - m_axisStorage.emplace_back(std::make_unique()); + m_axisStorage.emplace_back(std::make_unique()); m_axisConfig.emplace_back(*m_axisStorage.back()); } m_axisConfig[0].incKey = GLFW_KEY_L; @@ -906,7 +906,7 @@ GlfwKeyboardJoystick::GlfwKeyboardJoystick(glass::Storage& storage, int index) if (m_axisCount == -1 && m_axisStorage.empty()) { m_axisCount = 2; for (int i = 0; i < 2; ++i) { - m_axisStorage.emplace_back(std::make_unique()); + m_axisStorage.emplace_back(std::make_unique()); m_axisConfig.emplace_back(*m_axisStorage.back()); } m_axisConfig[0].incKey = GLFW_KEY_RIGHT; @@ -961,7 +961,7 @@ const char* GlfwKeyboardJoystick::GetKeyName(int key) const { return "(Unknown)"; } -RobotJoystick::RobotJoystick(glass::Storage& storage) +RobotJoystick::RobotJoystick(wpi::glass::Storage& storage) : name{storage.GetString("name")}, guid{storage.GetString("guid")}, useGamepad{storage.GetBool("useGamepad")} {} @@ -1040,11 +1040,11 @@ static void DriverStationExecute() { bool disableDS = IsDSDisabled(); if (disableDS && !prevDisableDS) { if (auto win = DriverStationGui::dsManager->GetWindow("System Joysticks")) { - win->SetVisibility(glass::Window::kDisabled); + win->SetVisibility(wpi::glass::Window::kDisabled); } } else if (!disableDS && prevDisableDS) { if (auto win = DriverStationGui::dsManager->GetWindow("System Joysticks")) { - win->SetVisibility(glass::Window::kShow); + win->SetVisibility(wpi::glass::Window::kShow); } } prevDisableDS = disableDS; @@ -1166,7 +1166,7 @@ void FMSSimModel::UpdateHAL() { HALSIM_SetDriverStationTest(m_test.GetValue()); HALSIM_SetDriverStationAutonomous(m_autonomous.GetValue()); HALSIM_SetDriverStationMatchTime(m_matchTime.GetValue()); - auto str = wpi::make_string(m_gameMessage.GetValue()); + auto str = wpi::util::make_string(m_gameMessage.GetValue()); HALSIM_SetGameSpecificMessage(&str); HALSIM_SetDriverStationDsAttached(m_dsAttached.GetValue()); } @@ -1216,7 +1216,7 @@ bool FMSSimModel::IsReadOnly() { static void DisplaySystemJoystick(SystemJoystick& joy, int i) { char label[64]; - wpi::format_to_n_c_str(label, sizeof(label), "{}: {}", i, joy.GetName()); + wpi::util::format_to_n_c_str(label, sizeof(label), "{}: {}", i, joy.GetName()); // highlight if any buttons pressed bool anyButtonPressed = joy.IsAnyButtonPressed(); @@ -1250,7 +1250,7 @@ static void DisplaySystemJoysticks() { DisplaySystemJoystick(*joy, i + GLFW_JOYSTICK_LAST + 1); if (ImGui::BeginPopupContextItem()) { char buf[64]; - wpi::format_to_n_c_str(buf, sizeof(buf), "{} Settings", joy->GetName()); + wpi::util::format_to_n_c_str(buf, sizeof(buf), "{} Settings", joy->GetName()); if (ImGui::MenuItem(buf)) { if (auto win = DriverStationGui::dsManager->GetWindow(buf)) { @@ -1301,7 +1301,7 @@ static void DisplayJoysticks() { joy.guid = payload_sys->GetGUID(); std::string_view name{payload_sys->GetName()}; joy.useGamepad = - wpi::starts_with(name, "Xbox") || wpi::contains(name, "pad"); + wpi::util::starts_with(name, "Xbox") || wpi::util::contains(name, "pad"); } ImGui::EndDragDropTarget(); } @@ -1339,7 +1339,7 @@ static void DisplayJoysticks() { for (int j = 0; j < axesCount; ++j) { if (source && source->axes[j]) { char label[64]; - wpi::format_to_n_c_str(label, sizeof(label), "Axis[{}]", j); + wpi::util::format_to_n_c_str(label, sizeof(label), "Axis[{}]", j); ImGui::Selectable(label); source->axes[j]->EmitDrag(); @@ -1356,7 +1356,7 @@ static void DisplayJoysticks() { for (int j = 0; j < povCount; ++j) { if (source && source->povs[j]) { char label[64]; - wpi::format_to_n_c_str(label, sizeof(label), "POVs[{}]", j); + wpi::util::format_to_n_c_str(label, sizeof(label), "POVs[{}]", j); ImGui::Selectable(label); source->povs[j]->EmitDrag(); @@ -1372,7 +1372,7 @@ static void DisplayJoysticks() { // show buttons as multiple lines of LED indicators, 8 per line static const ImU32 color = IM_COL32(255, 255, 102, 255); - wpi::SmallVector buttons; + wpi::util::SmallVector buttons; buttons.resize(buttonCount); for (int j = 0; j < buttonCount; ++j) { buttons[j] = joy.IsButtonPressed(j) ? 1 : -1; @@ -1415,7 +1415,7 @@ void DSManager::DisplayMenu() { } void DriverStationGui::GlobalInit() { - auto& storageRoot = glass::GetStorageRoot("ds"); + auto& storageRoot = wpi::glass::GetStorageRoot("ds"); dsManager = std::make_unique(storageRoot); // set up system joysticks (both GLFW and keyboard) @@ -1441,7 +1441,7 @@ void DriverStationGui::GlobalInit() { keyboardStorage.resize(4); for (int i = 0; i < 4; ++i) { if (!keyboardStorage[i]) { - keyboardStorage[i] = std::make_unique(); + keyboardStorage[i] = std::make_unique(); } gKeyboardJoysticks.emplace_back( std::make_unique(*keyboardStorage[i], i)); @@ -1451,7 +1451,7 @@ void DriverStationGui::GlobalInit() { robotJoystickStorage.resize(HAL_kMaxJoysticks); for (int i = 0; i < HAL_kMaxJoysticks; ++i) { if (!robotJoystickStorage[i]) { - robotJoystickStorage[i] = std::make_unique(); + robotJoystickStorage[i] = std::make_unique(); } gRobotJoysticks.emplace_back(*robotJoystickStorage[i]); } @@ -1459,12 +1459,12 @@ void DriverStationGui::GlobalInit() { int i = 0; for (auto&& joy : gKeyboardJoysticks) { char label[64]; - wpi::format_to_n_c_str(label, sizeof(label), "{} Settings", + wpi::util::format_to_n_c_str(label, sizeof(label), "{} Settings", joy->GetName()); if (auto win = dsManager->AddWindow( label, [j = joy.get()] { j->SettingsDisplay(); }, - glass::Window::kHide)) { + wpi::glass::Window::kHide)) { win->DisableRenamePopup(); win->SetDefaultPos(10 + 310 * i++, 50); if (i > 3) { diff --git a/simulation/halsim_gui/src/main/native/cpp/DriverStationGui.hpp b/simulation/halsim_gui/src/main/native/cpp/DriverStationGui.hpp index a544d192f4..a839c79052 100644 --- a/simulation/halsim_gui/src/main/native/cpp/DriverStationGui.hpp +++ b/simulation/halsim_gui/src/main/native/cpp/DriverStationGui.hpp @@ -11,9 +11,9 @@ namespace halsimgui { -class DSManager : public glass::WindowManager { +class DSManager : public wpi::glass::WindowManager { public: - explicit DSManager(glass::Storage& storage) : WindowManager{storage} {} + explicit DSManager(wpi::glass::Storage& storage) : WindowManager{storage} {} void DisplayMenu() override; }; diff --git a/simulation/halsim_gui/src/main/native/cpp/EncoderSimGui.cpp b/simulation/halsim_gui/src/main/native/cpp/EncoderSimGui.cpp index f1e6838d12..3313a38706 100644 --- a/simulation/halsim_gui/src/main/native/cpp/EncoderSimGui.cpp +++ b/simulation/halsim_gui/src/main/native/cpp/EncoderSimGui.cpp @@ -24,7 +24,7 @@ using namespace halsimgui; namespace { -class EncoderSimModel : public glass::EncoderModel { +class EncoderSimModel : public wpi::glass::EncoderModel { public: EncoderSimModel(std::string_view id, int32_t index, int channelA, int channelB) @@ -88,14 +88,14 @@ class EncoderSimModel : public glass::EncoderModel { int GetChannelA() const override { return m_channelA; } int GetChannelB() const override { return m_channelB; } - glass::DoubleSource* GetDistancePerPulseData() override { + wpi::glass::DoubleSource* GetDistancePerPulseData() override { return &m_distancePerPulse; } - glass::IntegerSource* GetCountData() override { return &m_count; } - glass::DoubleSource* GetPeriodData() override { return &m_period; } - glass::BooleanSource* GetDirectionData() override { return &m_direction; } - glass::DoubleSource* GetDistanceData() override { return &m_distance; } - glass::DoubleSource* GetRateData() override { return &m_rate; } + wpi::glass::IntegerSource* GetCountData() override { return &m_count; } + wpi::glass::DoubleSource* GetPeriodData() override { return &m_period; } + wpi::glass::BooleanSource* GetDirectionData() override { return &m_direction; } + wpi::glass::DoubleSource* GetDistanceData() override { return &m_distance; } + wpi::glass::DoubleSource* GetRateData() override { return &m_rate; } double GetMaxPeriod() override { return HALSIM_GetEncoderMaxPeriod(m_index); } bool GetReverseDirection() override { @@ -176,12 +176,12 @@ class EncoderSimModel : public glass::EncoderModel { } } - glass::DoubleSource m_distancePerPulse; - glass::IntegerSource m_count; - glass::DoubleSource m_period; - glass::BooleanSource m_direction; - glass::DoubleSource m_distance; - glass::DoubleSource m_rate; + wpi::glass::DoubleSource m_distancePerPulse; + wpi::glass::IntegerSource m_count; + wpi::glass::DoubleSource m_period; + wpi::glass::BooleanSource m_direction; + wpi::glass::DoubleSource m_distance; + wpi::glass::DoubleSource m_rate; int32_t m_index; int m_channelA; @@ -192,7 +192,7 @@ class EncoderSimModel : public glass::EncoderModel { int32_t m_directionCallback; }; -class EncodersSimModel : public glass::EncodersModel { +class EncodersSimModel : public wpi::glass::EncodersModel { public: EncodersSimModel() : m_models(HAL_GetNumEncoders()) {} @@ -201,7 +201,7 @@ class EncodersSimModel : public glass::EncodersModel { bool Exists() override { return true; } void ForEachEncoder( - wpi::function_ref func) + wpi::util::function_ref func) override; private: @@ -224,7 +224,7 @@ void EncodersSimModel::Update() { } void EncodersSimModel::ForEachEncoder( - wpi::function_ref func) { + wpi::util::function_ref func) { for (int32_t i = 0, iend = static_cast(m_models.size()); i < iend; ++i) { if (auto model = m_models[i].get()) { @@ -247,16 +247,16 @@ void EncoderSimGui::Initialize() { HALSimGui::halProvider->Register( "Encoders", EncodersAnyInitialized, [] { return std::make_unique(); }, - [](glass::Window* win, glass::Model* model) { + [](wpi::glass::Window* win, wpi::glass::Model* model) { win->SetFlags(ImGuiWindowFlags_AlwaysAutoResize); win->SetDefaultPos(5, 250); - return glass::MakeFunctionView( + return wpi::glass::MakeFunctionView( [=] { DisplayEncoders(static_cast(model)); }); }); } -glass::EncodersModel& EncoderSimGui::GetEncodersModel() { +wpi::glass::EncodersModel& EncoderSimGui::GetEncodersModel() { static auto model = HALSimGui::halProvider->GetModel("Encoders"); assert(model); - return *static_cast(model); + return *static_cast(model); } diff --git a/simulation/halsim_gui/src/main/native/cpp/EncoderSimGui.hpp b/simulation/halsim_gui/src/main/native/cpp/EncoderSimGui.hpp index f27d1801d6..410e4d40d3 100644 --- a/simulation/halsim_gui/src/main/native/cpp/EncoderSimGui.hpp +++ b/simulation/halsim_gui/src/main/native/cpp/EncoderSimGui.hpp @@ -4,7 +4,7 @@ #pragma once -namespace glass { +namespace wpi::glass { class EncodersModel; } // namespace glass @@ -13,7 +13,7 @@ namespace halsimgui { class EncoderSimGui { public: static void Initialize(); - static glass::EncodersModel& GetEncodersModel(); + static wpi::glass::EncodersModel& GetEncodersModel(); }; } // namespace halsimgui diff --git a/simulation/halsim_gui/src/main/native/cpp/HALProvider.cpp b/simulation/halsim_gui/src/main/native/cpp/HALProvider.cpp index 4bc821c241..7e727e0a5d 100644 --- a/simulation/halsim_gui/src/main/native/cpp/HALProvider.cpp +++ b/simulation/halsim_gui/src/main/native/cpp/HALProvider.cpp @@ -15,7 +15,7 @@ using namespace halsimgui; static bool gDisableOutputsOnDSDisable = true; -HALProvider::HALProvider(glass::Storage& storage) : Provider{storage} { +HALProvider::HALProvider(wpi::glass::Storage& storage) : Provider{storage} { storage.SetCustomApply([this] { for (auto&& childIt : m_storage.GetChildren()) { auto it = FindViewEntry(childIt.key()); @@ -65,7 +65,7 @@ void HALProvider::DisplayMenu() { } } -glass::Model* HALProvider::GetModel(std::string_view name) { +wpi::glass::Model* HALProvider::GetModel(std::string_view name) { auto it = FindModelEntry(name); if (it == m_modelEntries.end() || (*it)->name != name) { return nullptr; @@ -79,7 +79,7 @@ glass::Model* HALProvider::GetModel(std::string_view name) { return entry->model.get(); } -void HALProvider::Show(ViewEntry* entry, glass::Window* window) { +void HALProvider::Show(ViewEntry* entry, wpi::glass::Window* window) { // if there's already a window, we're done if (entry->window) { return; @@ -97,7 +97,7 @@ void HALProvider::Show(ViewEntry* entry, glass::Window* window) { if (!window) { window = GetOrAddWindow( entry->name, true, - entry->showDefault ? glass::Window::kShow : glass::Window::kHide); + entry->showDefault ? wpi::glass::Window::kShow : wpi::glass::Window::kHide); } if (!window) { return; diff --git a/simulation/halsim_gui/src/main/native/cpp/HALSimGui.cpp b/simulation/halsim_gui/src/main/native/cpp/HALSimGui.cpp index 4402f47c6d..48bf8348f1 100644 --- a/simulation/halsim_gui/src/main/native/cpp/HALSimGui.cpp +++ b/simulation/halsim_gui/src/main/native/cpp/HALSimGui.cpp @@ -15,25 +15,25 @@ using namespace halsimgui; -glass::MainMenuBar HALSimGui::mainMenu; -std::unique_ptr HALSimGui::manager; +wpi::glass::MainMenuBar HALSimGui::mainMenu; +std::unique_ptr HALSimGui::manager; std::unique_ptr HALSimGui::halProvider; -std::unique_ptr HALSimGui::ntProvider; +std::unique_ptr HALSimGui::ntProvider; void HALSimGui::GlobalInit() { - manager = std::make_unique( - glass::GetStorageRoot().GetChild("SimWindow")); + manager = std::make_unique( + wpi::glass::GetStorageRoot().GetChild("SimWindow")); manager->GlobalInit(); halProvider = std::make_unique( - glass::GetStorageRoot().GetChild("HALProvider")); + wpi::glass::GetStorageRoot().GetChild("HALProvider")); halProvider->GlobalInit(); - ntProvider = std::make_unique( - glass::GetStorageRoot().GetChild("NTProvider")); + ntProvider = std::make_unique( + wpi::glass::GetStorageRoot().GetChild("NTProvider")); ntProvider->GlobalInit(); wpi::gui::AddLateExecute([] { mainMenu.Display(); }); - glass::AddStandardNetworkTablesViews(*ntProvider); + wpi::glass::AddStandardNetworkTablesViews(*ntProvider); } namespace halsimgui { diff --git a/simulation/halsim_gui/src/main/native/cpp/NetworkTablesSimGui.cpp b/simulation/halsim_gui/src/main/native/cpp/NetworkTablesSimGui.cpp index 0ee72f9d8a..4e2816d205 100644 --- a/simulation/halsim_gui/src/main/native/cpp/NetworkTablesSimGui.cpp +++ b/simulation/halsim_gui/src/main/native/cpp/NetworkTablesSimGui.cpp @@ -14,32 +14,32 @@ using namespace halsimgui; -static std::unique_ptr gNetworkTablesModel; -static std::unique_ptr gNetworkTablesWindow; -static std::unique_ptr gNetworkTablesInfoWindow; +static std::unique_ptr gNetworkTablesModel; +static std::unique_ptr gNetworkTablesWindow; +static std::unique_ptr gNetworkTablesInfoWindow; void NetworkTablesSimGui::Initialize() { - gNetworkTablesModel = std::make_unique(); + gNetworkTablesModel = std::make_unique(); wpi::gui::AddEarlyExecute([] { gNetworkTablesModel->Update(); }); - gNetworkTablesWindow = std::make_unique( - glass::GetStorageRoot().GetChild("NetworkTables View"), "NetworkTables"); + gNetworkTablesWindow = std::make_unique( + wpi::glass::GetStorageRoot().GetChild("NetworkTables View"), "NetworkTables"); gNetworkTablesWindow->SetView( - std::make_unique(gNetworkTablesModel.get())); + std::make_unique(gNetworkTablesModel.get())); gNetworkTablesWindow->SetDefaultPos(250, 277); gNetworkTablesWindow->SetDefaultSize(750, 185); gNetworkTablesWindow->DisableRenamePopup(); wpi::gui::AddLateExecute([] { gNetworkTablesWindow->Display(); }); // NetworkTables info window - gNetworkTablesInfoWindow = std::make_unique( - glass::GetStorageRoot().GetChild("NetworkTables Info"), + gNetworkTablesInfoWindow = std::make_unique( + wpi::glass::GetStorageRoot().GetChild("NetworkTables Info"), "NetworkTables Info"); - gNetworkTablesInfoWindow->SetView(glass::MakeFunctionView( - [&] { glass::DisplayNetworkTablesInfo(gNetworkTablesModel.get()); })); + gNetworkTablesInfoWindow->SetView(wpi::glass::MakeFunctionView( + [&] { wpi::glass::DisplayNetworkTablesInfo(gNetworkTablesModel.get()); })); gNetworkTablesInfoWindow->SetDefaultPos(250, 130); gNetworkTablesInfoWindow->SetDefaultSize(750, 145); - gNetworkTablesInfoWindow->SetDefaultVisibility(glass::Window::kHide); + gNetworkTablesInfoWindow->SetDefaultVisibility(wpi::glass::Window::kHide); gNetworkTablesInfoWindow->DisableRenamePopup(); wpi::gui::AddLateExecute([] { gNetworkTablesInfoWindow->Display(); }); diff --git a/simulation/halsim_gui/src/main/native/cpp/PCMSimGui.cpp b/simulation/halsim_gui/src/main/native/cpp/PCMSimGui.cpp index 90e3fbd6a1..ee663207f2 100644 --- a/simulation/halsim_gui/src/main/native/cpp/PCMSimGui.cpp +++ b/simulation/halsim_gui/src/main/native/cpp/PCMSimGui.cpp @@ -27,7 +27,7 @@ HALSIMGUI_DATASOURCE_DOUBLE_INDEXED(CTREPCMCompressorCurrent, "Compressor Current"); HALSIMGUI_DATASOURCE_BOOLEAN_INDEXED2(CTREPCMSolenoidOutput, "Solenoid"); -class CompressorSimModel : public glass::CompressorModel { +class CompressorSimModel : public wpi::glass::CompressorModel { public: explicit CompressorSimModel(int32_t index) : m_index{index}, @@ -40,12 +40,12 @@ class CompressorSimModel : public glass::CompressorModel { bool Exists() override { return HALSIM_GetCTREPCMInitialized(m_index); } - glass::BooleanSource* GetRunningData() override { return &m_running; } - glass::BooleanSource* GetEnabledData() override { return &m_enabled; } - glass::BooleanSource* GetPressureSwitchData() override { + wpi::glass::BooleanSource* GetRunningData() override { return &m_running; } + wpi::glass::BooleanSource* GetEnabledData() override { return &m_enabled; } + wpi::glass::BooleanSource* GetPressureSwitchData() override { return &m_pressureSwitch; } - glass::DoubleSource* GetCurrentData() override { return &m_current; } + wpi::glass::DoubleSource* GetCurrentData() override { return &m_current; } void SetRunning(bool val) override { HALSIM_SetCTREPCMCompressorOn(m_index, val); @@ -68,7 +68,7 @@ class CompressorSimModel : public glass::CompressorModel { CTREPCMCompressorCurrentSource m_current; }; -class SolenoidSimModel : public glass::SolenoidModel { +class SolenoidSimModel : public wpi::glass::SolenoidModel { public: SolenoidSimModel(int32_t index, int32_t channel) : m_index{index}, m_channel{channel}, m_output{index, channel} {} @@ -77,7 +77,7 @@ class SolenoidSimModel : public glass::SolenoidModel { bool Exists() override { return HALSIM_GetCTREPCMInitialized(m_index); } - glass::BooleanSource* GetOutputData() override { return &m_output; } + wpi::glass::BooleanSource* GetOutputData() override { return &m_output; } void SetOutput(bool val) override { HALSIM_SetCTREPCMSolenoidOutput(m_index, m_channel, val); @@ -89,7 +89,7 @@ class SolenoidSimModel : public glass::SolenoidModel { CTREPCMSolenoidOutputSource m_output; }; -class PCMSimModel : public glass::PneumaticControlModel { +class PCMSimModel : public wpi::glass::PneumaticControlModel { public: explicit PCMSimModel(int32_t index) : m_index{index}, @@ -103,7 +103,7 @@ class PCMSimModel : public glass::PneumaticControlModel { CompressorSimModel* GetCompressor() override { return &m_compressor; } void ForEachSolenoid( - wpi::function_ref func) + wpi::util::function_ref func) override; std::string_view GetName() override { return "PCM"; } @@ -117,7 +117,7 @@ class PCMSimModel : public glass::PneumaticControlModel { int m_solenoidInitCount = 0; }; -class PCMsSimModel : public glass::PneumaticControlsModel { +class PCMsSimModel : public wpi::glass::PneumaticControlsModel { public: PCMsSimModel() : m_models(HAL_GetNumCTREPCMModules()) {} @@ -126,7 +126,7 @@ class PCMsSimModel : public glass::PneumaticControlsModel { bool Exists() override { return true; } void ForEachPneumaticControl( - wpi::function_ref + wpi::util::function_ref func) override; private: @@ -151,7 +151,7 @@ void PCMSimModel::Update() { } void PCMSimModel::ForEachSolenoid( - wpi::function_ref func) { + wpi::util::function_ref func) { if (m_solenoidInitCount == 0) { return; } @@ -179,7 +179,7 @@ void PCMsSimModel::Update() { } void PCMsSimModel::ForEachPneumaticControl( - wpi::function_ref + wpi::util::function_ref func) { int32_t numCTREPCMs = m_models.size(); for (int32_t i = 0; i < numCTREPCMs; ++i) { @@ -199,10 +199,10 @@ bool PCMSimGui::PCMsAnyInitialized() { return false; } -bool PCMSimGui::PCMsAnySolenoids(glass::PneumaticControlsModel* model) { +bool PCMSimGui::PCMsAnySolenoids(wpi::glass::PneumaticControlsModel* model) { bool any = false; static_cast(model)->ForEachPneumaticControl( - [&](glass::PneumaticControlModel& CTREPCM, int) { + [&](wpi::glass::PneumaticControlModel& CTREPCM, int) { if (static_cast(&CTREPCM)->GetNumSolenoids() > 0) { any = true; } @@ -210,7 +210,7 @@ bool PCMSimGui::PCMsAnySolenoids(glass::PneumaticControlsModel* model) { return any; } -std::unique_ptr PCMSimGui::GetPCMsModel() { +std::unique_ptr PCMSimGui::GetPCMsModel() { return std::make_unique(); } @@ -220,8 +220,8 @@ void PCMSimGui::Initialize() { [] { return std::make_unique(); }); SimDeviceGui::GetDeviceTree().Add( - HALSimGui::halProvider->GetModel("CTREPCMs"), [](glass::Model* model) { - glass::DisplayCompressorsDevice( + HALSimGui::halProvider->GetModel("CTREPCMs"), [](wpi::glass::Model* model) { + wpi::glass::DisplayCompressorsDevice( static_cast(model), HALSimGui::halProvider->AreOutputsEnabled()); }); diff --git a/simulation/halsim_gui/src/main/native/cpp/PCMSimGui.hpp b/simulation/halsim_gui/src/main/native/cpp/PCMSimGui.hpp index 31d43597d7..465487aba1 100644 --- a/simulation/halsim_gui/src/main/native/cpp/PCMSimGui.hpp +++ b/simulation/halsim_gui/src/main/native/cpp/PCMSimGui.hpp @@ -13,8 +13,8 @@ class PCMSimGui { public: static void Initialize(); static bool PCMsAnyInitialized(); - static bool PCMsAnySolenoids(glass::PneumaticControlsModel* model); - static std::unique_ptr GetPCMsModel(); + static bool PCMsAnySolenoids(wpi::glass::PneumaticControlsModel* model); + static std::unique_ptr GetPCMsModel(); }; } // namespace halsimgui diff --git a/simulation/halsim_gui/src/main/native/cpp/PHSimGui.cpp b/simulation/halsim_gui/src/main/native/cpp/PHSimGui.cpp index 31701b041d..d0a5ac1fb3 100644 --- a/simulation/halsim_gui/src/main/native/cpp/PHSimGui.cpp +++ b/simulation/halsim_gui/src/main/native/cpp/PHSimGui.cpp @@ -26,7 +26,7 @@ HALSIMGUI_DATASOURCE_DOUBLE_INDEXED(REVPHCompressorCurrent, "Compressor Current"); HALSIMGUI_DATASOURCE_BOOLEAN_INDEXED2(REVPHSolenoidOutput, "Solenoid"); -class CompressorSimModel : public glass::CompressorModel { +class CompressorSimModel : public wpi::glass::CompressorModel { public: explicit CompressorSimModel(int32_t index) : m_index{index}, @@ -38,12 +38,12 @@ class CompressorSimModel : public glass::CompressorModel { bool Exists() override { return HALSIM_GetREVPHInitialized(m_index); } - glass::BooleanSource* GetRunningData() override { return &m_running; } - glass::BooleanSource* GetEnabledData() override { return nullptr; } - glass::BooleanSource* GetPressureSwitchData() override { + wpi::glass::BooleanSource* GetRunningData() override { return &m_running; } + wpi::glass::BooleanSource* GetEnabledData() override { return nullptr; } + wpi::glass::BooleanSource* GetPressureSwitchData() override { return &m_pressureSwitch; } - glass::DoubleSource* GetCurrentData() override { return &m_current; } + wpi::glass::DoubleSource* GetCurrentData() override { return &m_current; } void SetRunning(bool val) override { HALSIM_SetREVPHCompressorOn(m_index, val); @@ -63,7 +63,7 @@ class CompressorSimModel : public glass::CompressorModel { REVPHCompressorCurrentSource m_current; }; -class SolenoidSimModel : public glass::SolenoidModel { +class SolenoidSimModel : public wpi::glass::SolenoidModel { public: SolenoidSimModel(int32_t index, int32_t channel) : m_index{index}, m_channel{channel}, m_output{index, channel} {} @@ -72,7 +72,7 @@ class SolenoidSimModel : public glass::SolenoidModel { bool Exists() override { return HALSIM_GetREVPHInitialized(m_index); } - glass::BooleanSource* GetOutputData() override { return &m_output; } + wpi::glass::BooleanSource* GetOutputData() override { return &m_output; } void SetOutput(bool val) override { HALSIM_SetREVPHSolenoidOutput(m_index, m_channel, val); @@ -84,7 +84,7 @@ class SolenoidSimModel : public glass::SolenoidModel { REVPHSolenoidOutputSource m_output; }; -class PHSimModel : public glass::PneumaticControlModel { +class PHSimModel : public wpi::glass::PneumaticControlModel { public: explicit PHSimModel(int32_t index) : m_index{index}, @@ -98,7 +98,7 @@ class PHSimModel : public glass::PneumaticControlModel { CompressorSimModel* GetCompressor() override { return &m_compressor; } void ForEachSolenoid( - wpi::function_ref func) + wpi::util::function_ref func) override; std::string_view GetName() override { return "PH"; } @@ -112,7 +112,7 @@ class PHSimModel : public glass::PneumaticControlModel { int m_solenoidInitCount = 0; }; -class PHsSimModel : public glass::PneumaticControlsModel { +class PHsSimModel : public wpi::glass::PneumaticControlsModel { public: PHsSimModel() : m_models(HAL_GetNumREVPHModules()) {} @@ -121,7 +121,7 @@ class PHsSimModel : public glass::PneumaticControlsModel { bool Exists() override { return true; } void ForEachPneumaticControl( - wpi::function_ref + wpi::util::function_ref func) override; private: @@ -146,7 +146,7 @@ void PHSimModel::Update() { } void PHSimModel::ForEachSolenoid( - wpi::function_ref func) { + wpi::util::function_ref func) { if (m_solenoidInitCount == 0) { return; } @@ -174,7 +174,7 @@ void PHsSimModel::Update() { } void PHsSimModel::ForEachPneumaticControl( - wpi::function_ref + wpi::util::function_ref func) { int32_t numREVPHs = m_models.size(); for (int32_t i = 0; i < numREVPHs; ++i) { @@ -194,10 +194,10 @@ bool PHSimGui::PHsAnyInitialized() { return false; } -bool PHSimGui::PHsAnySolenoids(glass::PneumaticControlsModel* model) { +bool PHSimGui::PHsAnySolenoids(wpi::glass::PneumaticControlsModel* model) { bool any = false; static_cast(model)->ForEachPneumaticControl( - [&](glass::PneumaticControlModel& REVPH, int) { + [&](wpi::glass::PneumaticControlModel& REVPH, int) { if (static_cast(&REVPH)->GetNumSolenoids() > 0) { any = true; } @@ -205,7 +205,7 @@ bool PHSimGui::PHsAnySolenoids(glass::PneumaticControlsModel* model) { return any; } -std::unique_ptr PHSimGui::GetPHsModel() { +std::unique_ptr PHSimGui::GetPHsModel() { return std::make_unique(); } @@ -215,8 +215,8 @@ void PHSimGui::Initialize() { [] { return std::make_unique(); }); SimDeviceGui::GetDeviceTree().Add( - HALSimGui::halProvider->GetModel("REVPHs"), [](glass::Model* model) { - glass::DisplayCompressorsDevice( + HALSimGui::halProvider->GetModel("REVPHs"), [](wpi::glass::Model* model) { + wpi::glass::DisplayCompressorsDevice( static_cast(model), HALSimGui::halProvider->AreOutputsEnabled()); }); diff --git a/simulation/halsim_gui/src/main/native/cpp/PHSimGui.hpp b/simulation/halsim_gui/src/main/native/cpp/PHSimGui.hpp index 159e409e04..7c742d46e5 100644 --- a/simulation/halsim_gui/src/main/native/cpp/PHSimGui.hpp +++ b/simulation/halsim_gui/src/main/native/cpp/PHSimGui.hpp @@ -13,8 +13,8 @@ class PHSimGui { public: static void Initialize(); static bool PHsAnyInitialized(); - static bool PHsAnySolenoids(glass::PneumaticControlsModel* model); - static std::unique_ptr GetPHsModel(); + static bool PHsAnySolenoids(wpi::glass::PneumaticControlsModel* model); + static std::unique_ptr GetPHsModel(); }; } // namespace halsimgui diff --git a/simulation/halsim_gui/src/main/native/cpp/PWMSimGui.cpp b/simulation/halsim_gui/src/main/native/cpp/PWMSimGui.cpp index f857a74fe3..295223f337 100644 --- a/simulation/halsim_gui/src/main/native/cpp/PWMSimGui.cpp +++ b/simulation/halsim_gui/src/main/native/cpp/PWMSimGui.cpp @@ -19,7 +19,7 @@ using namespace halsimgui; namespace { HALSIMGUI_DATASOURCE_DOUBLE_INDEXED(PWMPulseMicrosecond, "PWM"); -class PWMSimModel : public glass::PWMModel { +class PWMSimModel : public wpi::glass::PWMModel { public: explicit PWMSimModel(int32_t index) : m_index{index}, m_speed{m_index} {} @@ -27,7 +27,7 @@ class PWMSimModel : public glass::PWMModel { bool Exists() override { return HALSIM_GetPWMInitialized(m_index); } - glass::DoubleSource* GetSpeedData() override { return &m_speed; } + wpi::glass::DoubleSource* GetSpeedData() override { return &m_speed; } void SetSpeed(double val) override { HALSIM_SetPWMPulseMicrosecond(m_index, val); @@ -38,7 +38,7 @@ class PWMSimModel : public glass::PWMModel { PWMPulseMicrosecondSource m_speed; }; -class PWMsSimModel : public glass::PWMsModel { +class PWMsSimModel : public wpi::glass::PWMsModel { public: PWMsSimModel() : m_sources(HAL_GetNumPWMChannels()) {} @@ -47,7 +47,7 @@ class PWMsSimModel : public glass::PWMsModel { bool Exists() override { return true; } void ForEachPWM( - wpi::function_ref func) override; + wpi::util::function_ref func) override; private: // indexed by channel @@ -70,7 +70,7 @@ void PWMsSimModel::Update() { } void PWMsSimModel::ForEachPWM( - wpi::function_ref func) { + wpi::util::function_ref func) { const int32_t numPWM = m_sources.size(); for (int32_t i = 0; i < numPWM; ++i) { if (auto model = m_sources[i].get()) { @@ -93,11 +93,11 @@ void PWMSimGui::Initialize() { HALSimGui::halProvider->Register( "PWM Outputs", PWMsAnyInitialized, [] { return std::make_unique(); }, - [](glass::Window* win, glass::Model* model) { + [](wpi::glass::Window* win, wpi::glass::Model* model) { win->SetFlags(ImGuiWindowFlags_AlwaysAutoResize); win->SetDefaultPos(910, 20); - return glass::MakeFunctionView([=] { - glass::DisplayPWMs(static_cast(model), + return wpi::glass::MakeFunctionView([=] { + wpi::glass::DisplayPWMs(static_cast(model), HALSimGui::halProvider->AreOutputsEnabled()); }); }); diff --git a/simulation/halsim_gui/src/main/native/cpp/PowerDistributionSimGui.cpp b/simulation/halsim_gui/src/main/native/cpp/PowerDistributionSimGui.cpp index f3adf2d6c5..eeaa7b4d4b 100644 --- a/simulation/halsim_gui/src/main/native/cpp/PowerDistributionSimGui.cpp +++ b/simulation/halsim_gui/src/main/native/cpp/PowerDistributionSimGui.cpp @@ -25,7 +25,7 @@ HALSIMGUI_DATASOURCE_DOUBLE_INDEXED(PowerDistributionVoltage, HALSIMGUI_DATASOURCE_DOUBLE_INDEXED2(PowerDistributionCurrent, "Power Distribution Current"); -class PowerDistributionSimModel : public glass::PowerDistributionModel { +class PowerDistributionSimModel : public wpi::glass::PowerDistributionModel { public: explicit PowerDistributionSimModel(int32_t index) : m_index{index}, m_temp{index}, m_voltage{index} { @@ -46,9 +46,9 @@ class PowerDistributionSimModel : public glass::PowerDistributionModel { int GetNumChannels() const override { return m_currents.size(); } - glass::DoubleSource* GetTemperatureData() override { return &m_temp; } - glass::DoubleSource* GetVoltageData() override { return &m_voltage; } - glass::DoubleSource* GetCurrentData(int channel) override { + wpi::glass::DoubleSource* GetTemperatureData() override { return &m_temp; } + wpi::glass::DoubleSource* GetVoltageData() override { return &m_voltage; } + wpi::glass::DoubleSource* GetCurrentData(int channel) override { return m_currents[channel].get(); } @@ -69,7 +69,7 @@ class PowerDistributionSimModel : public glass::PowerDistributionModel { std::vector> m_currents; }; -class PowerDistributionsSimModel : public glass::PowerDistributionsModel { +class PowerDistributionsSimModel : public wpi::glass::PowerDistributionsModel { public: PowerDistributionsSimModel() : m_models(HAL_GetNumREVPDHModules()) {} @@ -78,7 +78,7 @@ class PowerDistributionsSimModel : public glass::PowerDistributionsModel { bool Exists() override { return true; } void ForEachPowerDistribution( - wpi::function_ref + wpi::util::function_ref func) override; private: @@ -101,7 +101,7 @@ void PowerDistributionsSimModel::Update() { } void PowerDistributionsSimModel::ForEachPowerDistribution( - wpi::function_ref + wpi::util::function_ref func) { for (int32_t i = 0, iend = static_cast(m_models.size()); i < iend; ++i) { @@ -125,9 +125,9 @@ void PowerDistributionSimGui::Initialize() { HALSimGui::halProvider->Register( "PowerDistributions", PowerDistributionsAnyInitialized, [] { return std::make_unique(); }, - [](glass::Window* win, glass::Model* model) { + [](wpi::glass::Window* win, wpi::glass::Model* model) { win->SetDefaultPos(245, 155); - return glass::MakeFunctionView([=] { + return wpi::glass::MakeFunctionView([=] { DisplayPowerDistributions( static_cast(model)); }); diff --git a/simulation/halsim_gui/src/main/native/cpp/RoboRioSimGui.cpp b/simulation/halsim_gui/src/main/native/cpp/RoboRioSimGui.cpp index 8229c16838..dfadcc3c98 100644 --- a/simulation/halsim_gui/src/main/native/cpp/RoboRioSimGui.cpp +++ b/simulation/halsim_gui/src/main/native/cpp/RoboRioSimGui.cpp @@ -21,14 +21,14 @@ HALSIMGUI_DATASOURCE_BOOLEAN(RoboRioUserActive3V3, "Rio 3.3V Active"); HALSIMGUI_DATASOURCE_INT(RoboRioUserFaults3V3, "Rio 3.3V Faults"); HALSIMGUI_DATASOURCE_DOUBLE(RoboRioBrownoutVoltage, "Rio Brownout Voltage"); -class RoboRioUser3V3RailSimModel : public glass::RoboRioRailModel { +class RoboRioUser3V3RailSimModel : public wpi::glass::RoboRioRailModel { public: void Update() override {} bool Exists() override { return true; } - glass::DoubleSource* GetVoltageData() override { return &m_voltage; } - glass::DoubleSource* GetCurrentData() override { return &m_current; } - glass::BooleanSource* GetActiveData() override { return &m_active; } - glass::IntegerSource* GetFaultsData() override { return &m_faults; } + wpi::glass::DoubleSource* GetVoltageData() override { return &m_voltage; } + wpi::glass::DoubleSource* GetCurrentData() override { return &m_current; } + wpi::glass::BooleanSource* GetActiveData() override { return &m_active; } + wpi::glass::IntegerSource* GetFaultsData() override { return &m_faults; } void SetVoltage(double val) override { HALSIM_SetRoboRioUserVoltage3V3(val); } void SetCurrent(double val) override { HALSIM_SetRoboRioUserCurrent3V3(val); } @@ -42,16 +42,16 @@ class RoboRioUser3V3RailSimModel : public glass::RoboRioRailModel { RoboRioUserFaults3V3Source m_faults; }; -class RoboRioSimModel : public glass::RoboRioModel { +class RoboRioSimModel : public wpi::glass::RoboRioModel { public: void Update() override {} bool Exists() override { return true; } - glass::RoboRioRailModel* GetUser3V3Rail() override { return &m_user3V3Rail; } + wpi::glass::RoboRioRailModel* GetUser3V3Rail() override { return &m_user3V3Rail; } - glass::DoubleSource* GetVInVoltageData() override { return &m_vInVoltage; } - glass::DoubleSource* GetBrownoutVoltage() override { + wpi::glass::DoubleSource* GetVInVoltageData() override { return &m_vInVoltage; } + wpi::glass::DoubleSource* GetBrownoutVoltage() override { return &m_brownoutVoltage; } @@ -71,10 +71,10 @@ void RoboRioSimGui::Initialize() { HALSimGui::halProvider->Register( "RoboRIO", [] { return true; }, [] { return std::make_unique(); }, - [](glass::Window* win, glass::Model* model) { + [](wpi::glass::Window* win, wpi::glass::Model* model) { win->SetFlags(ImGuiWindowFlags_AlwaysAutoResize); win->SetDefaultPos(5, 125); - return glass::MakeFunctionView( + return wpi::glass::MakeFunctionView( [=] { DisplayRoboRio(static_cast(model)); }); }); } diff --git a/simulation/halsim_gui/src/main/native/cpp/SimDeviceGui.cpp b/simulation/halsim_gui/src/main/native/cpp/SimDeviceGui.cpp index cc97333267..23dd7d2e4a 100644 --- a/simulation/halsim_gui/src/main/native/cpp/SimDeviceGui.cpp +++ b/simulation/halsim_gui/src/main/native/cpp/SimDeviceGui.cpp @@ -23,7 +23,7 @@ using namespace halsimgui; namespace { #define DEFINE_SIMVALUESOURCE(Type, TYPE, v_type) \ - class Sim##Type##ValueSource : public glass::Type##Source { \ + class Sim##Type##ValueSource : public wpi::glass::Type##Source { \ public: \ explicit Sim##Type##ValueSource(HAL_SimValueHandle handle, \ const char* device, const char* name) \ @@ -51,7 +51,7 @@ namespace { DEFINE_SIMVALUESOURCE(Boolean, BOOLEAN, boolean) DEFINE_SIMVALUESOURCE(Double, DOUBLE, double) -class SimIntegerValueSource : public glass::IntegerSource { +class SimIntegerValueSource : public wpi::glass::IntegerSource { public: explicit SimIntegerValueSource(HAL_SimValueHandle handle, const char* device, const char* name) @@ -80,17 +80,17 @@ class SimIntegerValueSource : public glass::IntegerSource { int32_t m_callback; }; -class SimDevicesModel : public glass::Model { +class SimDevicesModel : public wpi::glass::Model { public: void Update() override; bool Exists() override { return true; } - glass::DataSource* GetSource(HAL_SimValueHandle handle) { + wpi::glass::DataSource* GetSource(HAL_SimValueHandle handle) { return m_sources[handle].get(); } private: - wpi::DenseMap> + wpi::util::DenseMap> m_sources; }; } // namespace @@ -150,7 +150,7 @@ static void DisplaySimValue(const char* name, void* data, switch (value->type) { case HAL_BOOLEAN: { bool v = value->data.v_boolean; - if (glass::DeviceBoolean(name, direction == HAL_SimValueOutput, &v, + if (wpi::glass::DeviceBoolean(name, direction == HAL_SimValueOutput, &v, model->GetSource(handle))) { valueCopy.data.v_boolean = v ? 1 : 0; HAL_SetSimValue(handle, valueCopy); @@ -158,7 +158,7 @@ static void DisplaySimValue(const char* name, void* data, break; } case HAL_DOUBLE: - if (glass::DeviceDouble(name, direction == HAL_SimValueOutput, + if (wpi::glass::DeviceDouble(name, direction == HAL_SimValueOutput, &valueCopy.data.v_double, model->GetSource(handle))) { HAL_SetSimValue(handle, valueCopy); @@ -167,7 +167,7 @@ static void DisplaySimValue(const char* name, void* data, case HAL_ENUM: { int32_t numOptions = 0; const char** options = HALSIM_GetSimValueEnumOptions(handle, &numOptions); - if (glass::DeviceEnum(name, direction == HAL_SimValueOutput, + if (wpi::glass::DeviceEnum(name, direction == HAL_SimValueOutput, &valueCopy.data.v_enum, options, numOptions, model->GetSource(handle))) { HAL_SetSimValue(handle, valueCopy); @@ -175,13 +175,13 @@ static void DisplaySimValue(const char* name, void* data, break; } case HAL_INT: - if (glass::DeviceInt(name, direction == HAL_SimValueOutput, + if (wpi::glass::DeviceInt(name, direction == HAL_SimValueOutput, &valueCopy.data.v_int, model->GetSource(handle))) { HAL_SetSimValue(handle, valueCopy); } break; case HAL_LONG: - if (glass::DeviceLong(name, direction == HAL_SimValueOutput, + if (wpi::glass::DeviceLong(name, direction == HAL_SimValueOutput, &valueCopy.data.v_long, model->GetSource(handle))) { HAL_SetSimValue(handle, valueCopy); } @@ -197,49 +197,49 @@ static void DisplaySimDevice(const char* name, void* data, if (!gSimDevicesShowPrefix) { // only show "Foo" portion of "Accel:Foo" std::string_view type; - std::tie(type, id) = wpi::split(id, ':'); + std::tie(type, id) = wpi::util::split(id, ':'); if (id.empty()) { id = type; } } - if (glass::BeginDevice(id.data())) { + if (wpi::glass::BeginDevice(id.data())) { HALSIM_EnumerateSimValues(handle, data, DisplaySimValue); - glass::EndDevice(); + wpi::glass::EndDevice(); } } void SimDeviceGui::Initialize() { HALSimGui::halProvider->Register( "Other Devices", [] { return true; }, - [] { return std::make_unique(); }, - [](glass::Window* win, glass::Model* model) { + [] { return std::make_unique(); }, + [](wpi::glass::Window* win, wpi::glass::Model* model) { win->SetDefaultPos(1025, 20); win->SetDefaultSize(250, 695); win->DisableRenamePopup(); - return glass::MakeFunctionView([=] { + return wpi::glass::MakeFunctionView([=] { if (ImGui::BeginPopupContextItem()) { ImGui::Checkbox("Show prefix", &gSimDevicesShowPrefix); ImGui::EndPopup(); } - static_cast(model)->Display(); + static_cast(model)->Display(); }); }); HALSimGui::halProvider->ShowDefault("Other Devices"); auto model = std::make_unique(); gSimDevicesModel = model.get(); - GetDeviceTree().Add(std::move(model), [](glass::Model* model) { + GetDeviceTree().Add(std::move(model), [](wpi::glass::Model* model) { HALSIM_EnumerateSimDevices("", static_cast(model), DisplaySimDevice); }); } -glass::DataSource* SimDeviceGui::GetValueSource(HAL_SimValueHandle handle) { +wpi::glass::DataSource* SimDeviceGui::GetValueSource(HAL_SimValueHandle handle) { return gSimDevicesModel->GetSource(handle); } -glass::DeviceTreeModel& SimDeviceGui::GetDeviceTree() { +wpi::glass::DeviceTreeModel& SimDeviceGui::GetDeviceTree() { static auto model = HALSimGui::halProvider->GetModel("Other Devices"); assert(model); - return *static_cast(model); + return *static_cast(model); } diff --git a/simulation/halsim_gui/src/main/native/cpp/TimingGui.cpp b/simulation/halsim_gui/src/main/native/cpp/TimingGui.cpp index 92a5d17e64..41331b38ab 100644 --- a/simulation/halsim_gui/src/main/native/cpp/TimingGui.cpp +++ b/simulation/halsim_gui/src/main/native/cpp/TimingGui.cpp @@ -21,7 +21,7 @@ using namespace halsimgui; namespace { -class TimingModel : public glass::Model { +class TimingModel : public wpi::glass::Model { public: void Update() override {} bool Exists() override { return true; } @@ -74,11 +74,11 @@ void TimingGui::Initialize() { HALSimGui::halProvider->Register( "Timing", [] { return true; }, [] { return std::make_unique(); }, - [](glass::Window* win, glass::Model* model) { + [](wpi::glass::Window* win, wpi::glass::Model* model) { win->DisableRenamePopup(); win->SetFlags(ImGuiWindowFlags_AlwaysAutoResize); win->SetDefaultPos(5, 150); - return glass::MakeFunctionView(DisplayTiming); + return wpi::glass::MakeFunctionView(DisplayTiming); }); HALSimGui::halProvider->ShowDefault("Timing"); } diff --git a/simulation/halsim_gui/src/main/native/cpp/main.cpp b/simulation/halsim_gui/src/main/native/cpp/main.cpp index c708914c7b..651e1715c6 100644 --- a/simulation/halsim_gui/src/main/native/cpp/main.cpp +++ b/simulation/halsim_gui/src/main/native/cpp/main.cpp @@ -35,7 +35,7 @@ using namespace halsimgui; namespace gui = wpi::gui; -static std::unique_ptr gPlotProvider; +static std::unique_ptr gPlotProvider; extern "C" { #if defined(WIN32) || defined(_WIN32) @@ -45,9 +45,9 @@ int HALSIM_InitExtension(void) { std::puts("Simulator GUI Initializing."); gui::CreateContext(); - glass::CreateContext(); + wpi::glass::CreateContext(); - glass::SetStorageName("simgui"); + wpi::glass::SetStorageName("simgui"); gui::AddInit([] { ImGui::GetIO().ConfigDockingWithShift = true; }); @@ -66,12 +66,12 @@ int HALSIM_InitExtension(void) { reinterpret_cast((GetGuiContextFn)&gui::GetCurrentContext)); HAL_RegisterExtension( HALSIMGUI_EXT_GETGLASSCONTEXT, - reinterpret_cast((GetGlassContextFn)&glass::GetCurrentContext)); + reinterpret_cast((GetGlassContextFn)&wpi::glass::GetCurrentContext)); HALSimGui::GlobalInit(); DriverStationGui::GlobalInit(); - gPlotProvider = std::make_unique( - glass::GetStorageRoot().GetChild("Plot")); + gPlotProvider = std::make_unique( + wpi::glass::GetStorageRoot().GetChild("Plot")); gPlotProvider->GlobalInit(); // These need to initialize first @@ -95,28 +95,28 @@ int HALSIM_InitExtension(void) { return PCMSimGui::PCMsAnyInitialized() || PHSimGui::PHsAnyInitialized(); }, [] { - return std::make_unique( + return std::make_unique( PCMSimGui::GetPCMsModel(), PHSimGui::GetPHsModel()); }); HALSimGui::halProvider->RegisterView( "Solenoids", "AllPneumaticControls", - [](glass::Model* model) { + [](wpi::glass::Model* model) { auto pneumaticModel = - static_cast(model); + static_cast(model); return PCMSimGui::PCMsAnySolenoids(pneumaticModel->pcms.get()) || PHSimGui::PHsAnySolenoids(pneumaticModel->phs.get()); }, - [](glass::Window* win, glass::Model* model) { + [](wpi::glass::Window* win, wpi::glass::Model* model) { win->SetFlags(ImGuiWindowFlags_AlwaysAutoResize); win->SetDefaultPos(290, 20); - return glass::MakeFunctionView([=] { + return wpi::glass::MakeFunctionView([=] { auto pneumaticModel = - static_cast(model); - glass::DisplayPneumaticControlsSolenoids( + static_cast(model); + wpi::glass::DisplayPneumaticControlsSolenoids( pneumaticModel->pcms.get(), HALSimGui::halProvider->AreOutputsEnabled()); - glass::DisplayPneumaticControlsSolenoids( + wpi::glass::DisplayPneumaticControlsSolenoids( pneumaticModel->phs.get(), HALSimGui::halProvider->AreOutputsEnabled()); }); @@ -169,7 +169,7 @@ int HALSIM_InitExtension(void) { nullptr, [](void*) { gui::Main(); - glass::DestroyContext(); + wpi::glass::DestroyContext(); gui::DestroyContext(); }, [](void*) { gui::Exit(); }); diff --git a/simulation/halsim_gui/src/main/native/include/wpi/halsim/gui/HALDataSource.hpp b/simulation/halsim_gui/src/main/native/include/wpi/halsim/gui/HALDataSource.hpp index 0de9290032..ba69301d6f 100644 --- a/simulation/halsim_gui/src/main/native/include/wpi/halsim/gui/HALDataSource.hpp +++ b/simulation/halsim_gui/src/main/native/include/wpi/halsim/gui/HALDataSource.hpp @@ -7,7 +7,7 @@ #include "wpi/glass/DataSource.hpp" #define HALSIMGUI_DATASOURCE(cbname, id, TYPE, Type, vtype) \ - class cbname##Source : public ::glass::Type##Source { \ + class cbname##Source : public ::wpi::glass::Type##Source { \ public: \ cbname##Source() \ : Type##Source{id}, \ @@ -39,10 +39,10 @@ HALSIMGUI_DATASOURCE(cbname, id, INT, Integer, int) #define HALSIMGUI_DATASOURCE_INDEXED(cbname, id, TYPE, Type, vtype) \ - class cbname##Source : public ::glass::Type##Source { \ + class cbname##Source : public ::wpi::glass::Type##Source { \ public: \ explicit cbname##Source(int32_t index, int channel = -1) \ - : Type##Source{::glass::MakeSourceId(id, \ + : Type##Source{::wpi::glass::MakeSourceId(id, \ channel < 0 ? index : channel)}, \ m_index{index}, \ m_channel{channel < 0 ? index : channel}, \ @@ -77,10 +77,10 @@ HALSIMGUI_DATASOURCE_INDEXED(cbname, id, DOUBLE, Double, double) #define HALSIMGUI_DATASOURCE_INDEXED2(cbname, id, TYPE, Type, vtype) \ - class cbname##Source : public ::glass::Type##Source { \ + class cbname##Source : public ::wpi::glass::Type##Source { \ public: \ explicit cbname##Source(int32_t index, int32_t channel) \ - : Type##Source{::glass::MakeSourceId(id, index, channel)}, \ + : Type##Source{::wpi::glass::MakeSourceId(id, index, channel)}, \ m_index{index}, \ m_channel{channel}, \ m_callback{HALSIM_Register##cbname##Callback( \ diff --git a/simulation/halsim_gui/src/main/native/include/wpi/halsim/gui/HALProvider.hpp b/simulation/halsim_gui/src/main/native/include/wpi/halsim/gui/HALProvider.hpp index a8fdfd2f75..646e4203d7 100644 --- a/simulation/halsim_gui/src/main/native/include/wpi/halsim/gui/HALProvider.hpp +++ b/simulation/halsim_gui/src/main/native/include/wpi/halsim/gui/HALProvider.hpp @@ -15,9 +15,9 @@ namespace halsimgui { -class HALProvider : private glass::Provider<> { +class HALProvider : private wpi::glass::Provider<> { public: - explicit HALProvider(glass::Storage& storage); + explicit HALProvider(wpi::glass::Storage& storage); using Provider::GlobalInit; using Provider::Register; @@ -27,7 +27,7 @@ class HALProvider : private glass::Provider<> { void DisplayMenu() override; - glass::Model* GetModel(std::string_view name); + wpi::glass::Model* GetModel(std::string_view name); /** * Returns true if outputs are disabled. @@ -44,7 +44,7 @@ class HALProvider : private glass::Provider<> { static bool AreOutputsEnabled() { return !AreOutputsDisabled(); } private: - void Show(ViewEntry* entry, glass::Window* window) override; + void Show(ViewEntry* entry, wpi::glass::Window* window) override; }; } // namespace halsimgui diff --git a/simulation/halsim_gui/src/main/native/include/wpi/halsim/gui/HALSimGui.hpp b/simulation/halsim_gui/src/main/native/include/wpi/halsim/gui/HALSimGui.hpp index 21a38c485a..e52a5ae31f 100644 --- a/simulation/halsim_gui/src/main/native/include/wpi/halsim/gui/HALSimGui.hpp +++ b/simulation/halsim_gui/src/main/native/include/wpi/halsim/gui/HALSimGui.hpp @@ -18,11 +18,11 @@ class HALSimGui { public: static void GlobalInit(); - static glass::MainMenuBar mainMenu; - static std::unique_ptr manager; + static wpi::glass::MainMenuBar mainMenu; + static std::unique_ptr manager; static std::unique_ptr halProvider; - static std::unique_ptr ntProvider; + static std::unique_ptr ntProvider; }; void AddGuiInit(std::function initialize); diff --git a/simulation/halsim_gui/src/main/native/include/wpi/halsim/gui/HALSimGuiExt.hpp b/simulation/halsim_gui/src/main/native/include/wpi/halsim/gui/HALSimGuiExt.hpp index 377518f6db..a1a2e9fda5 100644 --- a/simulation/halsim_gui/src/main/native/include/wpi/halsim/gui/HALSimGuiExt.hpp +++ b/simulation/halsim_gui/src/main/native/include/wpi/halsim/gui/HALSimGuiExt.hpp @@ -8,7 +8,7 @@ struct ImGuiContext; -namespace glass { +namespace wpi::glass { class Context; } // namespace glass @@ -40,6 +40,6 @@ using GetImguiContextFn = ImGuiContext* (*)(); using GetGuiContextFn = wpi::gui::Context* (*)(); #define HALSIMGUI_EXT_GETGLASSCONTEXT "halsimgui::GetGlassContext" -using GetGlassContextFn = glass::Context* (*)(); +using GetGlassContextFn = wpi::glass::Context* (*)(); } // namespace halsimgui diff --git a/simulation/halsim_gui/src/main/native/include/wpi/halsim/gui/SimDeviceGui.hpp b/simulation/halsim_gui/src/main/native/include/wpi/halsim/gui/SimDeviceGui.hpp index a80f5bdebe..0c32a893af 100644 --- a/simulation/halsim_gui/src/main/native/include/wpi/halsim/gui/SimDeviceGui.hpp +++ b/simulation/halsim_gui/src/main/native/include/wpi/halsim/gui/SimDeviceGui.hpp @@ -6,7 +6,7 @@ #include "wpi/hal/SimDevice.h" -namespace glass { +namespace wpi::glass { class DataSource; class DeviceTreeModel; } // namespace glass @@ -16,8 +16,8 @@ namespace halsimgui { class SimDeviceGui { public: static void Initialize(); - static glass::DataSource* GetValueSource(HAL_SimValueHandle handle); - static glass::DeviceTreeModel& GetDeviceTree(); + static wpi::glass::DataSource* GetValueSource(HAL_SimValueHandle handle); + static wpi::glass::DeviceTreeModel& GetDeviceTree(); }; } // namespace halsimgui diff --git a/simulation/halsim_ws_client/src/dev/native/cpp/main.cpp b/simulation/halsim_ws_client/src/dev/native/cpp/main.cpp index 0f8d4ee5e0..f15a149385 100644 --- a/simulation/halsim_ws_client/src/dev/native/cpp/main.cpp +++ b/simulation/halsim_ws_client/src/dev/native/cpp/main.cpp @@ -21,9 +21,9 @@ int main() { while (cycleCount < 100) { std::this_thread::sleep_for(std::chrono::milliseconds(100)); cycleCount++; - wpi::print("Count: {}\n", cycleCount); + wpi::util::print("Count: {}\n", cycleCount); } - wpi::print("DONE\n"); + wpi::util::print("DONE\n"); HAL_ExitMain(); } diff --git a/simulation/halsim_ws_client/src/main/native/cpp/HALSimWS.cpp b/simulation/halsim_ws_client/src/main/native/cpp/HALSimWS.cpp index 2c8ae0d901..2575f592ac 100644 --- a/simulation/halsim_ws_client/src/main/native/cpp/HALSimWS.cpp +++ b/simulation/halsim_ws_client/src/main/native/cpp/HALSimWS.cpp @@ -16,17 +16,17 @@ static constexpr int kTcpConnectAttemptTimeout = 1000; -namespace uv = wpi::uv; +namespace uv = wpi::net::uv; using namespace wpilibws; -HALSimWS::HALSimWS(wpi::uv::Loop& loop, ProviderContainer& providers, +HALSimWS::HALSimWS(wpi::net::uv::Loop& loop, ProviderContainer& providers, HALSimWSProviderSimDevices& simDevicesProvider) : m_loop(loop), m_providers(providers), m_simDevicesProvider(simDevicesProvider) { m_loop.error.connect([](uv::Error err) { - wpi::print(stderr, "HALSim WS Client libuv Error: {}\n", err.str()); + wpi::util::print(stderr, "HALSim WS Client libuv Error: {}\n", err.str()); }); m_tcp_client = uv::Tcp::Create(m_loop); @@ -54,7 +54,7 @@ bool HALSimWS::Initialize() { try { m_port = std::stoi(port); } catch (const std::invalid_argument& err) { - wpi::print(stderr, "Error decoding HALSIMWS_PORT ({})\n", err.what()); + wpi::util::print(stderr, "Error decoding HALSIMWS_PORT ({})\n", err.what()); return false; } } else { @@ -71,8 +71,8 @@ bool HALSimWS::Initialize() { const char* msgFilters = std::getenv("HALSIMWS_FILTERS"); if (msgFilters != nullptr) { m_useMsgFiltering = true; - wpi::split(wpi::trim(msgFilters), ',', -1, false, - [&](auto val) { m_msgFilters[wpi::trim(val)] = true; }); + wpi::util::split(wpi::util::trim(msgFilters), ',', -1, false, + [&](auto val) { m_msgFilters[wpi::util::trim(val)] = true; }); } else { m_useMsgFiltering = false; } @@ -85,7 +85,7 @@ void HALSimWS::Start() { // Hook up TCP client events m_tcp_client->error.connect( - [this, socket = m_tcp_client.get()](wpi::uv::Error err) { + [this, socket = m_tcp_client.get()](wpi::net::uv::Error err) { if (m_tcp_connected) { m_tcp_connected = false; m_connect_attempts = 0; @@ -102,16 +102,16 @@ void HALSimWS::Start() { // Print any filters we are using if (m_useMsgFiltering) { - wpi::print("WS Message Filters:"); + wpi::util::print("WS Message Filters:"); for (auto&& filter : m_msgFilters) { - wpi::print("* \"{}\"\n", filter.first); + wpi::util::print("* \"{}\"\n", filter.first); } } else { - wpi::print("No WS Message Filters specified"); + wpi::util::print("No WS Message Filters specified"); } // Set up the connection timer - wpi::print("Will attempt to connect to ws://{}:{}{}\n", m_host, m_port, + wpi::util::print("Will attempt to connect to ws://{}:{}{}\n", m_host, m_port, m_uri); // Set up the timer to attempt connection @@ -125,7 +125,7 @@ void HALSimWS::Start() { void HALSimWS::AttemptConnect() { m_connect_attempts++; - wpi::print("Connection Attempt {}\n", m_connect_attempts); + wpi::util::print("Connection Attempt {}\n", m_connect_attempts); struct sockaddr_in dest; uv::NameToAddr(m_host, m_port, &dest); @@ -170,7 +170,7 @@ void HALSimWS::CloseWebsocket( } } -void HALSimWS::OnNetValueChanged(const wpi::json& msg) { +void HALSimWS::OnNetValueChanged(const wpi::util::json& msg) { // Look for "type" and "device" fields so that we can // generate the key @@ -178,7 +178,7 @@ void HALSimWS::OnNetValueChanged(const wpi::json& msg) { auto& type = msg.at("type").get_ref(); auto& device = msg.at("device").get_ref(); - wpi::SmallString<64> key; + wpi::util::SmallString<64> key; key.append(type); if (!device.empty()) { key.append("/"); @@ -189,8 +189,8 @@ void HALSimWS::OnNetValueChanged(const wpi::json& msg) { if (provider) { provider->OnNetValueChanged(msg.at("data")); } - } catch (wpi::json::exception& e) { - wpi::print(stderr, "Error with incoming message: {}\n", e.what()); + } catch (wpi::util::json::exception& e) { + wpi::util::print(stderr, "Error with incoming message: {}\n", e.what()); } } diff --git a/simulation/halsim_ws_client/src/main/native/cpp/HALSimWSClient.cpp b/simulation/halsim_ws_client/src/main/native/cpp/HALSimWSClient.cpp index 29ee16458d..e0a71d7e8a 100644 --- a/simulation/halsim_ws_client/src/main/native/cpp/HALSimWSClient.cpp +++ b/simulation/halsim_ws_client/src/main/native/cpp/HALSimWSClient.cpp @@ -25,7 +25,7 @@ using namespace wpilibws; bool HALSimWSClient::Initialize() { bool result = true; - runner.ExecSync([&](wpi::uv::Loop& loop) { + runner.ExecSync([&](wpi::net::uv::Loop& loop) { simws = std::make_shared(loop, providers, simDevices); if (!simws->Initialize()) { diff --git a/simulation/halsim_ws_client/src/main/native/cpp/HALSimWSClientConnection.cpp b/simulation/halsim_ws_client/src/main/native/cpp/HALSimWSClientConnection.cpp index a26c45938b..c7203587af 100644 --- a/simulation/halsim_ws_client/src/main/native/cpp/HALSimWSClientConnection.cpp +++ b/simulation/halsim_ws_client/src/main/native/cpp/HALSimWSClientConnection.cpp @@ -13,7 +13,7 @@ #include "wpi/net/raw_uv_ostream.hpp" #include "wpi/util/print.hpp" -namespace uv = wpi::uv; +namespace uv = wpi::net::uv; using namespace wpilibws; @@ -21,7 +21,7 @@ void HALSimWSClientConnection::Initialize() { // Get a shared pointer to ourselves auto self = this->shared_from_this(); - auto ws = wpi::WebSocket::CreateClient( + auto ws = wpi::net::WebSocket::CreateClient( *m_stream, m_client->GetTargetUri(), fmt::format("{}:{}", m_client->GetTargetHost(), m_client->GetTargetPort())); @@ -48,13 +48,13 @@ void HALSimWSClientConnection::Initialize() { return; } - wpi::json j; + wpi::util::json j; try { - j = wpi::json::parse(msg); - } catch (const wpi::json::parse_error& e) { + j = wpi::util::json::parse(msg); + } catch (const wpi::util::json::parse_error& e) { std::string err("JSON parse failed: "); err += e.what(); - wpi::print(stderr, "{}\n", err); + wpi::util::print(stderr, "{}\n", err); m_websocket->Fail(1003, err); return; } @@ -72,7 +72,7 @@ void HALSimWSClientConnection::Initialize() { }); } -void HALSimWSClientConnection::OnSimValueChanged(const wpi::json& msg) { +void HALSimWSClientConnection::OnSimValueChanged(const wpi::util::json& msg) { if (msg.empty()) { return; } @@ -83,12 +83,12 @@ void HALSimWSClientConnection::OnSimValueChanged(const wpi::json& msg) { if (!m_client->CanSendMessage(type)) { return; } - } catch (wpi::json::exception& e) { - wpi::print(stderr, "Error with message: {}\n", e.what()); + } catch (wpi::util::json::exception& e) { + wpi::util::print(stderr, "Error with message: {}\n", e.what()); } - wpi::SmallVector sendBufs; - wpi::raw_uv_ostream os{sendBufs, [this]() -> uv::Buffer { + wpi::util::SmallVector sendBufs; + wpi::net::raw_uv_ostream os{sendBufs, [this]() -> uv::Buffer { std::lock_guard lock(m_buffers_mutex); return m_buffers.Allocate(); }}; @@ -98,14 +98,14 @@ void HALSimWSClientConnection::OnSimValueChanged(const wpi::json& msg) { // Call the websocket send function on the uv loop m_client->GetExec().Send([self = shared_from_this(), sendBufs] { self->m_websocket->SendText(sendBufs, - [self](auto bufs, wpi::uv::Error err) { + [self](auto bufs, wpi::net::uv::Error err) { { std::lock_guard lock(self->m_buffers_mutex); self->m_buffers.Release(bufs); } if (err) { - wpi::print(stderr, "{}\n", err.str()); + wpi::util::print(stderr, "{}\n", err.str()); std::fflush(stderr); } }); diff --git a/simulation/halsim_ws_client/src/main/native/include/wpi/halsim/ws_client/HALSimWS.hpp b/simulation/halsim_ws_client/src/main/native/include/wpi/halsim/ws_client/HALSimWS.hpp index 0235d720a5..ca8ec6df2a 100644 --- a/simulation/halsim_ws_client/src/main/native/include/wpi/halsim/ws_client/HALSimWS.hpp +++ b/simulation/halsim_ws_client/src/main/native/include/wpi/halsim/ws_client/HALSimWS.hpp @@ -25,9 +25,9 @@ class HALSimWSClientConnection; class HALSimWS : public std::enable_shared_from_this { public: using LoopFunc = std::function; - using UvExecFunc = wpi::uv::Async; + using UvExecFunc = wpi::net::uv::Async; - HALSimWS(wpi::uv::Loop& loop, ProviderContainer& providers, + HALSimWS(wpi::net::uv::Loop& loop, ProviderContainer& providers, HALSimWSProviderSimDevices& simDevicesProvider); HALSimWS(const HALSimWS&) = delete; HALSimWS& operator=(const HALSimWS&) = delete; @@ -38,14 +38,14 @@ class HALSimWS : public std::enable_shared_from_this { bool RegisterWebsocket(std::shared_ptr hws); void CloseWebsocket(std::shared_ptr hws); - void OnNetValueChanged(const wpi::json& msg); + void OnNetValueChanged(const wpi::util::json& msg); bool CanSendMessage(std::string_view type); const std::string& GetTargetHost() const { return m_host; } const std::string& GetTargetUri() const { return m_uri; } int GetTargetPort() const { return m_port; } - wpi::uv::Loop& GetLoop() { return m_loop; } + wpi::net::uv::Loop& GetLoop() { return m_loop; } UvExecFunc& GetExec() { return *m_exec; } @@ -53,13 +53,13 @@ class HALSimWS : public std::enable_shared_from_this { void AttemptConnect(); bool m_tcp_connected = false; - std::shared_ptr m_connect_timer; + std::shared_ptr m_connect_timer; int m_connect_attempts = 0; std::weak_ptr m_hws; - wpi::uv::Loop& m_loop; - std::shared_ptr m_tcp_client; + wpi::net::uv::Loop& m_loop; + std::shared_ptr m_tcp_client; std::shared_ptr m_exec; ProviderContainer& m_providers; @@ -70,7 +70,7 @@ class HALSimWS : public std::enable_shared_from_this { int m_port; bool m_useMsgFiltering; - wpi::StringMap m_msgFilters; + wpi::util::StringMap m_msgFilters; }; } // namespace wpilibws diff --git a/simulation/halsim_ws_client/src/main/native/include/wpi/halsim/ws_client/HALSimWSClient.hpp b/simulation/halsim_ws_client/src/main/native/include/wpi/halsim/ws_client/HALSimWSClient.hpp index 505cb7ccec..b4efdc674b 100644 --- a/simulation/halsim_ws_client/src/main/native/include/wpi/halsim/ws_client/HALSimWSClient.hpp +++ b/simulation/halsim_ws_client/src/main/native/include/wpi/halsim/ws_client/HALSimWSClient.hpp @@ -23,7 +23,7 @@ class HALSimWSClient { ProviderContainer providers; HALSimWSProviderSimDevices simDevices{providers}; - wpi::EventLoopRunner runner; + wpi::net::EventLoopRunner runner; std::shared_ptr simws; }; diff --git a/simulation/halsim_ws_client/src/main/native/include/wpi/halsim/ws_client/HALSimWSClientConnection.hpp b/simulation/halsim_ws_client/src/main/native/include/wpi/halsim/ws_client/HALSimWSClientConnection.hpp index bdc9f0b46e..573efac95d 100644 --- a/simulation/halsim_ws_client/src/main/native/include/wpi/halsim/ws_client/HALSimWSClientConnection.hpp +++ b/simulation/halsim_ws_client/src/main/native/include/wpi/halsim/ws_client/HALSimWSClientConnection.hpp @@ -24,23 +24,23 @@ class HALSimWSClientConnection public std::enable_shared_from_this { public: explicit HALSimWSClientConnection(std::shared_ptr client, - std::shared_ptr stream) + std::shared_ptr stream) : m_client(std::move(client)), m_stream(std::move(stream)), m_buffers(128) {} public: - void OnSimValueChanged(const wpi::json& msg) override; + void OnSimValueChanged(const wpi::util::json& msg) override; void Initialize(); private: std::shared_ptr m_client; - std::shared_ptr m_stream; + std::shared_ptr m_stream; bool m_ws_connected = false; - wpi::WebSocket* m_websocket = nullptr; + wpi::net::WebSocket* m_websocket = nullptr; - wpi::uv::SimpleBufferPool<4> m_buffers; + wpi::net::uv::SimpleBufferPool<4> m_buffers; std::mutex m_buffers_mutex; }; diff --git a/simulation/halsim_ws_core/src/main/native/cpp/WSBaseProvider.cpp b/simulation/halsim_ws_core/src/main/native/cpp/WSBaseProvider.cpp index 42bf642d5f..d325a116fd 100644 --- a/simulation/halsim_ws_core/src/main/native/cpp/WSBaseProvider.cpp +++ b/simulation/halsim_ws_core/src/main/native/cpp/WSBaseProvider.cpp @@ -12,7 +12,7 @@ HALSimWSBaseProvider::HALSimWSBaseProvider(std::string_view key, std::string_view type) : m_key(key), m_type(type) {} -void HALSimWSBaseProvider::OnNetValueChanged(const wpi::json& json) { +void HALSimWSBaseProvider::OnNetValueChanged(const wpi::util::json& json) { // empty } diff --git a/simulation/halsim_ws_core/src/main/native/cpp/WSHalProviders.cpp b/simulation/halsim_ws_core/src/main/native/cpp/WSHalProviders.cpp index d53afb3ae2..bd8b83dfa5 100644 --- a/simulation/halsim_ws_core/src/main/native/cpp/WSHalProviders.cpp +++ b/simulation/halsim_ws_core/src/main/native/cpp/WSHalProviders.cpp @@ -24,10 +24,10 @@ void HALSimWSHalProvider::OnNetworkDisconnected() { CancelCallbacks(); } -void HALSimWSHalProvider::ProcessHalCallback(const wpi::json& payload) { +void HALSimWSHalProvider::ProcessHalCallback(const wpi::util::json& payload) { auto ws = m_ws.lock(); if (ws) { - wpi::json netValue = { + wpi::util::json netValue = { {"type", m_type}, {"device", m_deviceId}, {"data", payload}}; ws->OnSimValueChanged(netValue); } diff --git a/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_AddressableLED.cpp b/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_AddressableLED.cpp index b68a4f5c3f..4b4baa80bb 100644 --- a/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_AddressableLED.cpp +++ b/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_AddressableLED.cpp @@ -43,14 +43,14 @@ void HALSimWSProviderAddressableLED::RegisterCallbacks() { const HAL_AddressableLEDData* data = reinterpret_cast(buffer); - std::vector jsonData; + std::vector jsonData; for (size_t i = 0; i < numLeds; ++i) { jsonData.push_back( {{"r", data[i].r}, {"g", data[i].g}, {"b", data[i].b}}); } - wpi::json payload; + wpi::util::json payload; payload["ProcessHalCallback(payload); diff --git a/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_Analog.cpp b/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_Analog.cpp index afb56587a2..423fe8a570 100644 --- a/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_Analog.cpp +++ b/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_Analog.cpp @@ -53,8 +53,8 @@ void HALSimWSProviderAnalogIn::DoCancelCallbacks() { m_voltageCbKey = 0; } -void HALSimWSProviderAnalogIn::OnNetValueChanged(const wpi::json& json) { - wpi::json::const_iterator it; +void HALSimWSProviderAnalogIn::OnNetValueChanged(const wpi::util::json& json) { + wpi::util::json::const_iterator it; if ((it = json.find(">voltage")) != json.end()) { HALSIM_SetAnalogInVoltage(m_channel, it.value()); } diff --git a/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_DIO.cpp b/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_DIO.cpp index 4366775ad2..68a86632b5 100644 --- a/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_DIO.cpp +++ b/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_DIO.cpp @@ -50,8 +50,8 @@ void HALSimWSProviderDIO::DoCancelCallbacks() { m_inputCbKey = 0; } -void HALSimWSProviderDIO::OnNetValueChanged(const wpi::json& json) { - wpi::json::const_iterator it; +void HALSimWSProviderDIO::OnNetValueChanged(const wpi::util::json& json) { + wpi::util::json::const_iterator it; if ((it = json.find("<>value")) != json.end()) { HALSIM_SetDIOValue(m_channel, static_cast(it.value())); } diff --git a/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_DriverStation.cpp b/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_DriverStation.cpp index 51f148e20d..02bcdd06e3 100644 --- a/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_DriverStation.cpp +++ b/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_DriverStation.cpp @@ -122,13 +122,13 @@ void HALSimWSProviderDriverStation::DoCancelCallbacks() { m_matchTimeCbKey = 0; } -void HALSimWSProviderDriverStation::OnNetValueChanged(const wpi::json& json) { +void HALSimWSProviderDriverStation::OnNetValueChanged(const wpi::util::json& json) { // ignore if DS connected if (gDSSocketConnected && *gDSSocketConnected) { return; } - wpi::json::const_iterator it; + wpi::util::json::const_iterator it; if ((it = json.find(">enabled")) != json.end()) { HALSIM_SetDriverStationEnabled(it.value()); } @@ -170,7 +170,7 @@ void HALSimWSProviderDriverStation::OnNetValueChanged(const wpi::json& json) { } if ((it = json.find(">game_data")) != json.end()) { std::string message = it.value().get_ref(); - auto str = wpi::make_string(message); + auto str = wpi::util::make_string(message); HALSIM_SetGameSpecificMessage(&str); } diff --git a/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_Encoder.cpp b/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_Encoder.cpp index 29ad8aba74..0d1dd33ada 100644 --- a/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_Encoder.cpp +++ b/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_Encoder.cpp @@ -36,7 +36,7 @@ void HALSimWSProviderEncoder::RegisterCallbacks() { auto provider = static_cast(param); bool init = static_cast(value->data.v_boolean); - wpi::json payload = {{"count")) != json.end()) { HALSIM_SetEncoderCount(m_channel, static_cast(it.value()) - m_countOffset); diff --git a/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_HAL.cpp b/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_HAL.cpp index d43a2523ac..04aae13c6c 100644 --- a/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_HAL.cpp +++ b/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_HAL.cpp @@ -52,7 +52,7 @@ void HALSimWSProviderHAL::DoCancelCallbacks() { m_simPeriodicAfterCbKey = 0; } -void HALSimWSProviderHAL::OnNetValueChanged(const wpi::json& json) { +void HALSimWSProviderHAL::OnNetValueChanged(const wpi::util::json& json) { // no-op. This is all one way } diff --git a/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_Joystick.cpp b/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_Joystick.cpp index 88df204857..c9570c16a1 100644 --- a/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_Joystick.cpp +++ b/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_Joystick.cpp @@ -30,7 +30,7 @@ void HALSimWSProviderJoystick::RegisterCallbacks() { auto provider = static_cast(param); // Grab all joystick data and send it at once - wpi::json payload; + wpi::util::json payload; // Axes data HAL_JoystickAxes axes{}; @@ -93,20 +93,20 @@ void HALSimWSProviderJoystick::DoCancelCallbacks() { m_dsNewDataCbKey = 0; } -void HALSimWSProviderJoystick::OnNetValueChanged(const wpi::json& json) { +void HALSimWSProviderJoystick::OnNetValueChanged(const wpi::util::json& json) { // ignore if DS connected if (gDSSocketConnected && *gDSSocketConnected) { return; } - wpi::json::const_iterator it; + wpi::util::json::const_iterator it; if ((it = json.find(">axes")) != json.end()) { HAL_JoystickAxes axes{}; - wpi::json::size_type axesCount = + wpi::util::json::size_type axesCount = std::min(it.value().size(), - static_cast(HAL_kMaxJoystickAxes)); + static_cast(HAL_kMaxJoystickAxes)); axes.available = (1 << axesCount) - 1; - for (wpi::json::size_type i = 0; i < axesCount; i++) { + for (wpi::util::json::size_type i = 0; i < axesCount; i++) { axes.axes[i] = it.value()[i]; } @@ -115,14 +115,14 @@ void HALSimWSProviderJoystick::OnNetValueChanged(const wpi::json& json) { if ((it = json.find(">buttons")) != json.end()) { HAL_JoystickButtons buttons{}; - wpi::json::size_type buttonsCount = - std::min(it.value().size(), static_cast(64)); + wpi::util::json::size_type buttonsCount = + std::min(it.value().size(), static_cast(64)); if (buttonsCount < 64) { buttons.available = (1ULL << buttonsCount) - 1; } else { buttons.available = (std::numeric_limits::max)(); } - for (wpi::json::size_type i = 0; i < buttonsCount; i++) { + for (wpi::util::json::size_type i = 0; i < buttonsCount; i++) { if (it.value()[i]) { buttons.buttons |= 1llu << i; } @@ -133,11 +133,11 @@ void HALSimWSProviderJoystick::OnNetValueChanged(const wpi::json& json) { if ((it = json.find(">povs")) != json.end()) { HAL_JoystickPOVs povs{}; - wpi::json::size_type povsCount = + wpi::util::json::size_type povsCount = std::min(it.value().size(), - static_cast(HAL_kMaxJoystickPOVs)); + static_cast(HAL_kMaxJoystickPOVs)); povs.available = (1 << povsCount) - 1; - for (wpi::json::size_type i = 0; i < povsCount; i++) { + for (wpi::util::json::size_type i = 0; i < povsCount; i++) { povs.povs[i] = it.value()[i]; } diff --git a/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_RoboRIO.cpp b/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_RoboRIO.cpp index 7a1e0bf028..3f660b2dfd 100644 --- a/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_RoboRIO.cpp +++ b/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_RoboRIO.cpp @@ -53,8 +53,8 @@ void HALSimWSProviderRoboRIO::DoCancelCallbacks() { m_3v3VoltageCbKey = 0; } -void HALSimWSProviderRoboRIO::OnNetValueChanged(const wpi::json& json) { - wpi::json::const_iterator it; +void HALSimWSProviderRoboRIO::OnNetValueChanged(const wpi::util::json& json) { + wpi::util::json::const_iterator it; if ((it = json.find(">vin_voltage")) != json.end()) { HALSIM_SetRoboRioVInVoltage(it.value()); } diff --git a/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_SimDevice.cpp b/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_SimDevice.cpp index fbfca9c02e..8141821323 100644 --- a/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_SimDevice.cpp +++ b/simulation/halsim_ws_core/src/main/native/cpp/WSProvider_SimDevice.cpp @@ -61,7 +61,7 @@ void HALSimWSProviderSimDevice::CancelCallbacks() { m_simValueChangedCbKeys.clear(); } -void HALSimWSProviderSimDevice::OnNetValueChanged(const wpi::json& json) { +void HALSimWSProviderSimDevice::OnNetValueChanged(const wpi::util::json& json) { auto it = json.cbegin(); auto end = json.cend(); @@ -250,10 +250,10 @@ void HALSimWSProviderSimDevice::OnValueReset(SimDeviceValueData* valueData, } } -void HALSimWSProviderSimDevice::ProcessHalCallback(const wpi::json& payload) { +void HALSimWSProviderSimDevice::ProcessHalCallback(const wpi::util::json& payload) { auto ws = m_ws.lock(); if (ws) { - wpi::json netValue = { + wpi::util::json netValue = { {"type", m_type}, {"device", m_deviceId}, {"data", payload}}; ws->OnSimValueChanged(netValue); } @@ -266,7 +266,7 @@ HALSimWSProviderSimDevices::~HALSimWSProviderSimDevices() { void HALSimWSProviderSimDevices::DeviceCreatedCallback( const char* name, HAL_SimDeviceHandle handle) { // Map "Accel:Foo" -> type=Accel, device=Foo - auto [type, id] = wpi::split(name, ':'); + auto [type, id] = wpi::util::split(name, ':'); std::shared_ptr dev; if (id.empty()) { auto key = fmt::format("SimDevice/{}", type); @@ -289,7 +289,7 @@ void HALSimWSProviderSimDevices::DeviceFreedCallback( m_providers.Delete(name); } -void HALSimWSProviderSimDevices::Initialize(wpi::uv::Loop& loop) { +void HALSimWSProviderSimDevices::Initialize(wpi::net::uv::Loop& loop) { m_deviceCreatedCbKey = HALSIM_RegisterSimDeviceCreatedCallback( "", this, HALSimWSProviderSimDevices::DeviceCreatedCallbackStatic, 1); m_deviceFreedCbKey = HALSIM_RegisterSimDeviceFreedCallback( diff --git a/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/HALSimBaseWebSocketConnection.hpp b/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/HALSimBaseWebSocketConnection.hpp index d17ad019c0..90930ec443 100644 --- a/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/HALSimBaseWebSocketConnection.hpp +++ b/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/HALSimBaseWebSocketConnection.hpp @@ -12,7 +12,7 @@ namespace wpilibws { class HALSimBaseWebSocketConnection { public: - virtual void OnSimValueChanged(const wpi::json& msg) = 0; + virtual void OnSimValueChanged(const wpi::util::json& msg) = 0; protected: virtual ~HALSimBaseWebSocketConnection() = default; diff --git a/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/WSBaseProvider.hpp b/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/WSBaseProvider.hpp index 854248436c..7434385ca9 100644 --- a/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/WSBaseProvider.hpp +++ b/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/WSBaseProvider.hpp @@ -33,7 +33,7 @@ class HALSimWSBaseProvider { virtual void OnNetworkDisconnected() = 0; // network -> sim - virtual void OnNetValueChanged(const wpi::json& json); + virtual void OnNetValueChanged(const wpi::util::json& json); const std::string& GetDeviceType() { return m_type; } const std::string& GetDeviceId() { return m_deviceId; } diff --git a/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/WSHalProviders.hpp b/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/WSHalProviders.hpp index 730b0d34a0..5c7d5f62b0 100644 --- a/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/WSHalProviders.hpp +++ b/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/WSHalProviders.hpp @@ -33,7 +33,7 @@ class HALSimWSHalProvider : public HALSimWSBaseProvider { std::shared_ptr ws) override; void OnNetworkDisconnected() override; - void ProcessHalCallback(const wpi::json& payload); + void ProcessHalCallback(const wpi::util::json& payload); protected: virtual void RegisterCallbacks() = 0; diff --git a/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/WSProviderContainer.hpp b/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/WSProviderContainer.hpp index 341c67e7ef..abb3b2ae2b 100644 --- a/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/WSProviderContainer.hpp +++ b/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/WSProviderContainer.hpp @@ -51,7 +51,7 @@ class ProviderContainer { private: std::shared_mutex m_mutex; - wpi::StringMap> m_providers; + wpi::util::StringMap> m_providers; }; } // namespace wpilibws diff --git a/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/WSProvider_Analog.hpp b/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/WSProvider_Analog.hpp index 53e56f9282..97f63a3b7c 100644 --- a/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/WSProvider_Analog.hpp +++ b/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/WSProvider_Analog.hpp @@ -17,7 +17,7 @@ class HALSimWSProviderAnalogIn : public HALSimWSHalChanProvider { using HALSimWSHalChanProvider::HALSimWSHalChanProvider; ~HALSimWSProviderAnalogIn() override; - void OnNetValueChanged(const wpi::json& json) override; + void OnNetValueChanged(const wpi::util::json& json) override; protected: void RegisterCallbacks() override; diff --git a/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/WSProvider_DIO.hpp b/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/WSProvider_DIO.hpp index cdc0a3d3cc..85c27fcc90 100644 --- a/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/WSProvider_DIO.hpp +++ b/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/WSProvider_DIO.hpp @@ -17,7 +17,7 @@ class HALSimWSProviderDIO : public HALSimWSHalChanProvider { using HALSimWSHalChanProvider::HALSimWSHalChanProvider; ~HALSimWSProviderDIO() override; - void OnNetValueChanged(const wpi::json& json) override; + void OnNetValueChanged(const wpi::util::json& json) override; protected: void RegisterCallbacks() override; diff --git a/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/WSProvider_DriverStation.hpp b/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/WSProvider_DriverStation.hpp index c297189f64..e4f3da8952 100644 --- a/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/WSProvider_DriverStation.hpp +++ b/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/WSProvider_DriverStation.hpp @@ -17,7 +17,7 @@ class HALSimWSProviderDriverStation : public HALSimWSHalProvider { using HALSimWSHalProvider::HALSimWSHalProvider; ~HALSimWSProviderDriverStation() override; - void OnNetValueChanged(const wpi::json& json) override; + void OnNetValueChanged(const wpi::util::json& json) override; protected: void RegisterCallbacks() override; diff --git a/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/WSProvider_Encoder.hpp b/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/WSProvider_Encoder.hpp index 5601e40da9..271020350c 100644 --- a/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/WSProvider_Encoder.hpp +++ b/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/WSProvider_Encoder.hpp @@ -17,7 +17,7 @@ class HALSimWSProviderEncoder : public HALSimWSHalChanProvider { using HALSimWSHalChanProvider::HALSimWSHalChanProvider; ~HALSimWSProviderEncoder() override; - void OnNetValueChanged(const wpi::json& json) override; + void OnNetValueChanged(const wpi::util::json& json) override; protected: void RegisterCallbacks() override; diff --git a/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/WSProvider_HAL.hpp b/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/WSProvider_HAL.hpp index 48cdd6ada6..8055445f59 100644 --- a/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/WSProvider_HAL.hpp +++ b/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/WSProvider_HAL.hpp @@ -17,7 +17,7 @@ class HALSimWSProviderHAL : public HALSimWSHalProvider { using HALSimWSHalProvider::HALSimWSHalProvider; ~HALSimWSProviderHAL() override; - void OnNetValueChanged(const wpi::json& json) override; + void OnNetValueChanged(const wpi::util::json& json) override; protected: void RegisterCallbacks() override; diff --git a/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/WSProvider_Joystick.hpp b/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/WSProvider_Joystick.hpp index d69a44ce4a..5016185ca3 100644 --- a/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/WSProvider_Joystick.hpp +++ b/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/WSProvider_Joystick.hpp @@ -17,7 +17,7 @@ class HALSimWSProviderJoystick : public HALSimWSHalChanProvider { using HALSimWSHalChanProvider::HALSimWSHalChanProvider; ~HALSimWSProviderJoystick() override; - void OnNetValueChanged(const wpi::json& json) override; + void OnNetValueChanged(const wpi::util::json& json) override; protected: void RegisterCallbacks() override; diff --git a/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/WSProvider_RoboRIO.hpp b/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/WSProvider_RoboRIO.hpp index c95e279ce7..1a35d3cbd8 100644 --- a/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/WSProvider_RoboRIO.hpp +++ b/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/WSProvider_RoboRIO.hpp @@ -17,7 +17,7 @@ class HALSimWSProviderRoboRIO : public HALSimWSHalProvider { using HALSimWSHalProvider::HALSimWSHalProvider; ~HALSimWSProviderRoboRIO() override; - void OnNetValueChanged(const wpi::json& json) override; + void OnNetValueChanged(const wpi::util::json& json) override; protected: void RegisterCallbacks() override; diff --git a/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/WSProvider_SimDevice.hpp b/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/WSProvider_SimDevice.hpp index 45ae515be5..3e0b302954 100644 --- a/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/WSProvider_SimDevice.hpp +++ b/simulation/halsim_ws_core/src/main/native/include/wpi/halsim/ws_core/WSProvider_SimDevice.hpp @@ -48,9 +48,9 @@ class HALSimWSProviderSimDevice : public HALSimWSBaseProvider { void OnNetworkDisconnected() override; - void OnNetValueChanged(const wpi::json& json) override; + void OnNetValueChanged(const wpi::util::json& json) override; - void ProcessHalCallback(const wpi::json& payload); + void ProcessHalCallback(const wpi::util::json& payload); private: static void OnValueCreatedStatic(const char* name, void* param, @@ -73,7 +73,7 @@ class HALSimWSProviderSimDevice : public HALSimWSBaseProvider { void CancelCallbacks(); - wpi::StringMap m_valueHandles; + wpi::util::StringMap m_valueHandles; std::shared_mutex m_vhLock; HAL_SimDeviceHandle m_handle; @@ -81,19 +81,19 @@ class HALSimWSProviderSimDevice : public HALSimWSBaseProvider { std::shared_ptr m_simDevicesBase; int32_t m_simValueCreatedCbKey = 0; - wpi::StringMap m_simValueChangedCbKeys; + wpi::util::StringMap m_simValueChangedCbKeys; }; class HALSimWSProviderSimDevices { public: using LoopFn = std::function; - using UvExecFn = wpi::uv::AsyncFunction; + using UvExecFn = wpi::net::uv::AsyncFunction; explicit HALSimWSProviderSimDevices(ProviderContainer& providers) : m_providers(providers) {} ~HALSimWSProviderSimDevices(); - void Initialize(wpi::uv::Loop& loop); + void Initialize(wpi::net::uv::Loop& loop); void OnNetworkConnected(std::shared_ptr hws); void OnNetworkDisconnected(); diff --git a/simulation/halsim_ws_server/src/dev/native/cpp/main.cpp b/simulation/halsim_ws_server/src/dev/native/cpp/main.cpp index 669548f13d..34a121b065 100644 --- a/simulation/halsim_ws_server/src/dev/native/cpp/main.cpp +++ b/simulation/halsim_ws_server/src/dev/native/cpp/main.cpp @@ -24,7 +24,7 @@ int main() { while (cycleCount < 1000) { std::this_thread::sleep_for(std::chrono::milliseconds(100)); cycleCount++; - wpi::print("Count: {}\n", cycleCount); + wpi::util::print("Count: {}\n", cycleCount); } std::puts("DONE"); diff --git a/simulation/halsim_ws_server/src/main/native/cpp/HALSimHttpConnection.cpp b/simulation/halsim_ws_server/src/main/native/cpp/HALSimHttpConnection.cpp index 59532fb3a8..26a022e07d 100644 --- a/simulation/halsim_ws_server/src/main/native/cpp/HALSimHttpConnection.cpp +++ b/simulation/halsim_ws_server/src/main/native/cpp/HALSimHttpConnection.cpp @@ -20,7 +20,7 @@ #include "wpi/util/fs.hpp" #include "wpi/util/print.hpp" -namespace uv = wpi::uv; +namespace uv = wpi::net::uv; using namespace wpilibws; @@ -54,10 +54,10 @@ void HALSimHttpConnection::ProcessWsUpgrade() { return; } - wpi::json j; + wpi::util::json j; try { - j = wpi::json::parse(msg); - } catch (const wpi::json::parse_error& e) { + j = wpi::util::json::parse(msg); + } catch (const wpi::util::json::parse_error& e) { std::string err("JSON parse failed: "); err += e.what(); m_websocket->Fail(400, err); @@ -77,20 +77,20 @@ void HALSimHttpConnection::ProcessWsUpgrade() { }); } -void HALSimHttpConnection::OnSimValueChanged(const wpi::json& msg) { +void HALSimHttpConnection::OnSimValueChanged(const wpi::util::json& msg) { // Skip sending if this message is not in the allowed filter list try { auto& type = msg.at("type").get_ref(); if (!m_server->CanSendMessage(type)) { return; } - } catch (wpi::json::exception& e) { - wpi::print(stderr, "Error with message: {}\n", e.what()); + } catch (wpi::util::json::exception& e) { + wpi::util::print(stderr, "Error with message: {}\n", e.what()); } // render json to buffers - wpi::SmallVector sendBufs; - wpi::raw_uv_ostream os{sendBufs, [this]() -> uv::Buffer { + wpi::util::SmallVector sendBufs; + wpi::net::raw_uv_ostream os{sendBufs, [this]() -> uv::Buffer { std::lock_guard lock(m_buffers_mutex); return m_buffers.Allocate(); }}; @@ -99,14 +99,14 @@ void HALSimHttpConnection::OnSimValueChanged(const wpi::json& msg) { // call the websocket send function on the uv loop m_server->GetExec().Send([self = shared_from_this(), sendBufs] { self->m_websocket->SendText(sendBufs, - [self](auto bufs, wpi::uv::Error err) { + [self](auto bufs, wpi::net::uv::Error err) { { std::lock_guard lock(self->m_buffers_mutex); self->m_buffers.Release(bufs); } if (err) { - wpi::print(stderr, "{}\n", err.str()); + wpi::util::print(stderr, "{}\n", err.str()); std::fflush(stderr); } }); @@ -127,22 +127,22 @@ void HALSimHttpConnection::SendFileResponse(int code, std::string_view codeText, } // open file - auto fileBuffer = wpi::MemoryBuffer::GetFile(filename); + auto fileBuffer = wpi::util::MemoryBuffer::GetFile(filename); if (!fileBuffer) { MySendError(404, "error opening file"); return; } - wpi::SmallVector toSend; - wpi::raw_uv_ostream os{toSend, 4096}; + wpi::util::SmallVector toSend; + wpi::net::raw_uv_ostream os{toSend, 4096}; BuildHeader(os, code, codeText, contentType, size, extraHeader); SendData(os.bufs(), false); Log(code); // Read the file byte by byte - wpi::SmallVector bodyData; - wpi::raw_uv_ostream bodyOs{bodyData, 4096}; + wpi::util::SmallVector bodyData; + wpi::net::raw_uv_ostream bodyOs{bodyData, 4096}; bodyOs << fileBuffer.value()->GetBuffer(); @@ -153,8 +153,8 @@ void HALSimHttpConnection::SendFileResponse(int code, std::string_view codeText, } void HALSimHttpConnection::ProcessRequest() { - wpi::UrlParser url{m_request.GetUrl(), - m_request.GetMethod() == wpi::HTTP_CONNECT}; + wpi::net::UrlParser url{m_request.GetUrl(), + m_request.GetMethod() == wpi::net::HTTP_CONNECT}; if (!url.IsValid()) { // failed to parse URL MySendError(400, "Invalid URL"); @@ -166,17 +166,17 @@ void HALSimHttpConnection::ProcessRequest() { path = url.GetPath(); } - if (m_request.GetMethod() == wpi::HTTP_GET && wpi::starts_with(path, '/') && - !wpi::contains(path, "..") && !wpi::contains(path, "//")) { + if (m_request.GetMethod() == wpi::net::HTTP_GET && wpi::util::starts_with(path, '/') && + !wpi::util::contains(path, "..") && !wpi::util::contains(path, "//")) { // convert to fs native representation fs::path nativePath; - if (auto userPath = wpi::remove_prefix(path, "/user/")) { + if (auto userPath = wpi::util::remove_prefix(path, "/user/")) { nativePath = fs::path{m_server->GetWebrootSys()} / fs::path{*userPath, fs::path::format::generic_format}; } else { nativePath = fs::path{m_server->GetWebrootSys()} / - fs::path{wpi::drop_front(path), fs::path::format::generic_format}; + fs::path{wpi::util::drop_front(path), fs::path::format::generic_format}; } if (fs::is_directory(nativePath)) { @@ -186,7 +186,7 @@ void HALSimHttpConnection::ProcessRequest() { if (!fs::exists(nativePath) || fs::is_directory(nativePath)) { MySendError(404, fmt::format("Resource '{}' not found", path)); } else { - auto contentType = wpi::MimeTypeFromPath(nativePath.string()); + auto contentType = wpi::net::MimeTypeFromPath(nativePath.string()); SendFileResponse(200, "OK", contentType, nativePath.string()); } } else { @@ -200,7 +200,7 @@ void HALSimHttpConnection::MySendError(int code, std::string_view message) { } void HALSimHttpConnection::Log(int code) { - auto method = wpi::http_method_str(m_request.GetMethod()); - wpi::print(stderr, "{} {} HTTP/{}.{} {}\n", method, m_request.GetUrl(), + auto method = wpi::net::http_method_str(m_request.GetMethod()); + wpi::util::print(stderr, "{} {} HTTP/{}.{} {}\n", method, m_request.GetUrl(), m_request.GetMajor(), m_request.GetMinor(), code); } diff --git a/simulation/halsim_ws_server/src/main/native/cpp/HALSimWSServer.cpp b/simulation/halsim_ws_server/src/main/native/cpp/HALSimWSServer.cpp index 286788dd08..a4fad4bc9c 100644 --- a/simulation/halsim_ws_server/src/main/native/cpp/HALSimWSServer.cpp +++ b/simulation/halsim_ws_server/src/main/native/cpp/HALSimWSServer.cpp @@ -24,7 +24,7 @@ using namespace wpilibws; bool HALSimWSServer::Initialize() { bool result = true; - runner.ExecSync([&](wpi::uv::Loop& loop) { + runner.ExecSync([&](wpi::net::uv::Loop& loop) { simWeb = std::make_shared(loop, providers, simDevices); if (!simWeb->Initialize()) { diff --git a/simulation/halsim_ws_server/src/main/native/cpp/HALSimWeb.cpp b/simulation/halsim_ws_server/src/main/native/cpp/HALSimWeb.cpp index 1a9eff2507..af3b4f4f04 100644 --- a/simulation/halsim_ws_server/src/main/native/cpp/HALSimWeb.cpp +++ b/simulation/halsim_ws_server/src/main/native/cpp/HALSimWeb.cpp @@ -17,17 +17,17 @@ #include "wpi/util/fs.hpp" #include "wpi/util/print.hpp" -namespace uv = wpi::uv; +namespace uv = wpi::net::uv; using namespace wpilibws; -HALSimWeb::HALSimWeb(wpi::uv::Loop& loop, ProviderContainer& providers, +HALSimWeb::HALSimWeb(wpi::net::uv::Loop& loop, ProviderContainer& providers, HALSimWSProviderSimDevices& simDevicesProvider) : m_loop(loop), m_providers(providers), m_simDevicesProvider(simDevicesProvider) { m_loop.error.connect([](uv::Error err) { - wpi::print(stderr, "HALSim WS Server libuv ERROR: {}\n", err.str()); + wpi::util::print(stderr, "HALSim WS Server libuv ERROR: {}\n", err.str()); }); m_server = uv::Tcp::Create(m_loop); @@ -72,7 +72,7 @@ bool HALSimWeb::Initialize() { try { m_port = std::stoi(port); } catch (const std::invalid_argument& err) { - wpi::print(stderr, "Error decoding HALSIMWS_PORT ({})\n", err.what()); + wpi::util::print(stderr, "Error decoding HALSIMWS_PORT ({})\n", err.what()); return false; } } else { @@ -82,8 +82,8 @@ bool HALSimWeb::Initialize() { const char* msgFilters = std::getenv("HALSIMWS_FILTERS"); if (msgFilters != nullptr) { m_useMsgFiltering = true; - wpi::split(wpi::trim(msgFilters), ',', -1, false, - [&](auto val) { m_msgFilters[wpi::trim(val)] = true; }); + wpi::util::split(wpi::util::trim(msgFilters), ',', -1, false, + [&](auto val) { m_msgFilters[wpi::util::trim(val)] = true; }); } else { m_useMsgFiltering = false; } @@ -109,17 +109,17 @@ void HALSimWeb::Start() { // start listening for incoming connections m_server->Listen(); - wpi::print("Listening at http://localhost:{}\n", m_port); - wpi::print("WebSocket URI: {}\n", m_uri); + wpi::util::print("Listening at http://localhost:{}\n", m_port); + wpi::util::print("WebSocket URI: {}\n", m_uri); // Print any filters we are using if (m_useMsgFiltering) { - wpi::print("WS Message Filters:"); + wpi::util::print("WS Message Filters:"); for (auto&& filter : m_msgFilters) { - wpi::print("* \"{}\"\n", filter.first); + wpi::util::print("* \"{}\"\n", filter.first); } } else { - wpi::print("No WS Message Filters specified"); + wpi::util::print("No WS Message Filters specified"); } } @@ -155,7 +155,7 @@ void HALSimWeb::CloseWebsocket( } } -void HALSimWeb::OnNetValueChanged(const wpi::json& msg) { +void HALSimWeb::OnNetValueChanged(const wpi::util::json& msg) { // Look for "type" and "device" fields so that we can // generate the key @@ -163,7 +163,7 @@ void HALSimWeb::OnNetValueChanged(const wpi::json& msg) { auto& type = msg.at("type").get_ref(); auto& device = msg.at("device").get_ref(); - wpi::SmallString<64> key; + wpi::util::SmallString<64> key; key.append(type); if (!device.empty()) { key.append("/"); @@ -174,8 +174,8 @@ void HALSimWeb::OnNetValueChanged(const wpi::json& msg) { if (provider) { provider->OnNetValueChanged(msg.at("data")); } - } catch (wpi::json::exception& e) { - wpi::print(stderr, "Error with incoming message: {}\n", e.what()); + } catch (wpi::util::json::exception& e) { + wpi::util::print(stderr, "Error with incoming message: {}\n", e.what()); } } diff --git a/simulation/halsim_ws_server/src/main/native/include/wpi/halsim/ws_server/HALSimHttpConnection.hpp b/simulation/halsim_ws_server/src/main/native/include/wpi/halsim/ws_server/HALSimHttpConnection.hpp index 8fec5cc299..0ee5c96216 100644 --- a/simulation/halsim_ws_server/src/main/native/include/wpi/halsim/ws_server/HALSimHttpConnection.hpp +++ b/simulation/halsim_ws_server/src/main/native/include/wpi/halsim/ws_server/HALSimHttpConnection.hpp @@ -20,18 +20,18 @@ namespace wpilibws { class HALSimHttpConnection - : public wpi::HttpWebSocketServerConnection, + : public wpi::net::HttpWebSocketServerConnection, public HALSimBaseWebSocketConnection { public: HALSimHttpConnection(std::shared_ptr server, - std::shared_ptr stream) - : wpi::HttpWebSocketServerConnection(stream, {}), + std::shared_ptr stream) + : wpi::net::HttpWebSocketServerConnection(stream, {}), m_server(std::move(server)), m_buffers(128) {} public: // callable from any thread - void OnSimValueChanged(const wpi::json& msg) override; + void OnSimValueChanged(const wpi::util::json& msg) override; protected: void ProcessRequest() override; @@ -51,7 +51,7 @@ class HALSimHttpConnection bool m_isWsConnected = false; // these are only valid if the websocket is connected - wpi::uv::SimpleBufferPool<4> m_buffers; + wpi::net::uv::SimpleBufferPool<4> m_buffers; std::mutex m_buffers_mutex; }; diff --git a/simulation/halsim_ws_server/src/main/native/include/wpi/halsim/ws_server/HALSimWSServer.hpp b/simulation/halsim_ws_server/src/main/native/include/wpi/halsim/ws_server/HALSimWSServer.hpp index 22a2d536ae..a23bb0da54 100644 --- a/simulation/halsim_ws_server/src/main/native/include/wpi/halsim/ws_server/HALSimWSServer.hpp +++ b/simulation/halsim_ws_server/src/main/native/include/wpi/halsim/ws_server/HALSimWSServer.hpp @@ -23,7 +23,7 @@ class HALSimWSServer { ProviderContainer providers; HALSimWSProviderSimDevices simDevices{providers}; - wpi::EventLoopRunner runner; + wpi::net::EventLoopRunner runner; std::shared_ptr simWeb; }; diff --git a/simulation/halsim_ws_server/src/main/native/include/wpi/halsim/ws_server/HALSimWeb.hpp b/simulation/halsim_ws_server/src/main/native/include/wpi/halsim/ws_server/HALSimWeb.hpp index e57556430a..0fa352424c 100644 --- a/simulation/halsim_ws_server/src/main/native/include/wpi/halsim/ws_server/HALSimWeb.hpp +++ b/simulation/halsim_ws_server/src/main/native/include/wpi/halsim/ws_server/HALSimWeb.hpp @@ -23,9 +23,9 @@ namespace wpilibws { class HALSimWeb : public std::enable_shared_from_this { public: using LoopFunc = std::function; - using UvExecFunc = wpi::uv::Async; + using UvExecFunc = wpi::net::uv::Async; - HALSimWeb(wpi::uv::Loop& loop, ProviderContainer& providers, + HALSimWeb(wpi::net::uv::Loop& loop, ProviderContainer& providers, HALSimWSProviderSimDevices& simDevicesProvider); HALSimWeb(const HALSimWeb&) = delete; @@ -38,7 +38,7 @@ class HALSimWeb : public std::enable_shared_from_this { void CloseWebsocket(std::shared_ptr hws); // network -> sim - void OnNetValueChanged(const wpi::json& msg); + void OnNetValueChanged(const wpi::util::json& msg); bool CanSendMessage(std::string_view type); @@ -46,7 +46,7 @@ class HALSimWeb : public std::enable_shared_from_this { const std::string& GetWebrootUser() const { return m_webroot_user; } const std::string& GetServerUri() const { return m_uri; } int GetServerPort() const { return m_port; } - wpi::uv::Loop& GetLoop() { return m_loop; } + wpi::net::uv::Loop& GetLoop() { return m_loop; } UvExecFunc& GetExec() { return *m_exec; } @@ -54,8 +54,8 @@ class HALSimWeb : public std::enable_shared_from_this { // connected http connection that contains active websocket std::weak_ptr m_hws; - wpi::uv::Loop& m_loop; - std::shared_ptr m_server; + wpi::net::uv::Loop& m_loop; + std::shared_ptr m_server; std::shared_ptr m_exec; // list of providers @@ -72,7 +72,7 @@ class HALSimWeb : public std::enable_shared_from_this { int m_port; bool m_useMsgFiltering; - wpi::StringMap m_msgFilters; + wpi::util::StringMap m_msgFilters; }; } // namespace wpilibws diff --git a/simulation/halsim_ws_server/src/test/native/cpp/WebServerClientTest.cpp b/simulation/halsim_ws_server/src/test/native/cpp/WebServerClientTest.cpp index e31dbb1bcd..127359c577 100644 --- a/simulation/halsim_ws_server/src/test/native/cpp/WebServerClientTest.cpp +++ b/simulation/halsim_ws_server/src/test/native/cpp/WebServerClientTest.cpp @@ -17,15 +17,15 @@ static constexpr int kTcpConnectAttemptTimeout = 1000; -namespace uv = wpi::uv; +namespace uv = wpi::net::uv; namespace wpilibws { // Create Web Socket and specify event callbacks void WebServerClientTest::InitializeWebSocket(const std::string& host, int port, const std::string& uri) { - wpi::print("Will attempt to connect to: {}:{}{}\n", host, port, uri); - m_websocket = wpi::WebSocket::CreateClient(*m_tcp_client.get(), uri, + wpi::util::print("Will attempt to connect to: {}:{}{}\n", host, port, uri); + m_websocket = wpi::net::WebSocket::CreateClient(*m_tcp_client.get(), uri, fmt::format("{}:{}", host, port)); // Hook up events @@ -44,13 +44,13 @@ void WebServerClientTest::InitializeWebSocket(const std::string& host, int port, }); m_websocket->text.connect([this](auto msg, bool) { - wpi::json j; + wpi::util::json j; try { - j = wpi::json::parse(msg); - } catch (const wpi::json::parse_error& e) { + j = wpi::util::json::parse(msg); + } catch (const wpi::util::json::parse_error& e) { std::string err("JSON parse failed: "); err += e.what(); - wpi::print(stderr, "{}\n", err); + wpi::util::print(stderr, "{}\n", err); m_websocket->Fail(1003, err); return; } @@ -69,7 +69,7 @@ void WebServerClientTest::InitializeWebSocket(const std::string& host, int port, // Create tcp client, specify callbacks, and create timers for loop bool WebServerClientTest::Initialize() { m_loop.error.connect( - [](uv::Error err) { wpi::print(stderr, "uv Error: {}\n", err.str()); }); + [](uv::Error err) { wpi::util::print(stderr, "uv Error: {}\n", err.str()); }); m_tcp_client = uv::Tcp::Create(m_loop); if (!m_tcp_client) { @@ -79,7 +79,7 @@ bool WebServerClientTest::Initialize() { // Hook up TCP client events m_tcp_client->error.connect( - [this, socket = m_tcp_client.get()](wpi::uv::Error err) { + [this, socket = m_tcp_client.get()](wpi::net::uv::Error err) { if (m_tcp_connected) { m_tcp_connected = false; m_connect_attempts = 0; @@ -110,7 +110,7 @@ bool WebServerClientTest::Initialize() { void WebServerClientTest::AttemptConnect() { m_connect_attempts++; - wpi::print("Test Client Connection Attempt {}\n", m_connect_attempts); + wpi::util::print("Test Client Connection Attempt {}\n", m_connect_attempts); if (m_connect_attempts >= 5) { std::fputs("Test Client Timeout. Unable to connect\n", stderr); @@ -126,15 +126,15 @@ void WebServerClientTest::AttemptConnect() { }); } -void WebServerClientTest::SendMessage(const wpi::json& msg) { +void WebServerClientTest::SendMessage(const wpi::util::json& msg) { if (msg.empty()) { std::fputs("Message to send is empty\n", stderr); return; } - wpi::SmallVector sendBufs; + wpi::util::SmallVector sendBufs; - wpi::raw_uv_ostream os{sendBufs, [this]() -> uv::Buffer { + wpi::net::raw_uv_ostream os{sendBufs, [this]() -> uv::Buffer { std::lock_guard lock(m_buffers_mutex); return m_buffers->Allocate(); }}; @@ -142,20 +142,20 @@ void WebServerClientTest::SendMessage(const wpi::json& msg) { // Call the websocket send function on the uv loop m_exec->Call([this, sendBufs]() mutable { - m_websocket->SendText(sendBufs, [this](auto bufs, wpi::uv::Error err) { + m_websocket->SendText(sendBufs, [this](auto bufs, wpi::net::uv::Error err) { { std::lock_guard lock(m_buffers_mutex); m_buffers->Release(bufs); } if (err) { - wpi::print(stderr, "{}\n", err.str()); + wpi::util::print(stderr, "{}\n", err.str()); std::fflush(stderr); } }); }); } -const wpi::json& WebServerClientTest::GetLastMessage() { +const wpi::util::json& WebServerClientTest::GetLastMessage() { return m_json; } diff --git a/simulation/halsim_ws_server/src/test/native/cpp/main.cpp b/simulation/halsim_ws_server/src/test/native/cpp/main.cpp index 45f35f74fe..1a7109a647 100644 --- a/simulation/halsim_ws_server/src/test/native/cpp/main.cpp +++ b/simulation/halsim_ws_server/src/test/native/cpp/main.cpp @@ -17,7 +17,7 @@ #include "wpi/net/uv/Loop.hpp" #include "wpi/util/print.hpp" -namespace uv = wpi::uv; +namespace uv = wpi::net::uv; using namespace wpilibws; @@ -51,13 +51,13 @@ TEST_F(WebServerIntegrationTest, DISABLED_DigitalOutput) { // Attach timer to loop for test function m_server.runner.ExecSync([&](auto& loop) { - auto timer = wpi::uv::Timer::Create(loop); + auto timer = wpi::net::uv::Timer::Create(loop); timer->timeout.connect([&] { if (done) { return; } if (IsConnectedClientWS()) { - wpi::print("***** Setting DIO value for pin {} to {}\n", PIN, + wpi::util::print("***** Setting DIO value for pin {} to {}\n", PIN, (EXPECTED_VALUE ? "true" : "false")); HALSIM_SetDIOValue(PIN, EXPECTED_VALUE); done = true; @@ -80,12 +80,12 @@ TEST_F(WebServerIntegrationTest, DISABLED_DigitalOutput) { test_type = msg.at("type").get_ref(); test_device = msg.at("device").get_ref(); auto& data = msg.at("data"); - wpi::json::const_iterator it = data.find("<>value"); + wpi::util::json::const_iterator it = data.find("<>value"); if (it != data.end()) { test_value = it.value(); } - } catch (wpi::json::exception& e) { - wpi::print(stderr, "Error with incoming message: {}\n", e.what()); + } catch (wpi::util::json::exception& e) { + wpi::util::print(stderr, "Error with incoming message: {}\n", e.what()); } // Compare results @@ -102,16 +102,16 @@ TEST_F(WebServerIntegrationTest, DISABLED_DigitalInput) { // Attach timer to loop for test function m_server.runner.ExecSync([&](auto& loop) { - auto timer = wpi::uv::Timer::Create(loop); + auto timer = wpi::net::uv::Timer::Create(loop); timer->timeout.connect([&] { if (done) { return; } if (IsConnectedClientWS()) { - wpi::json msg = {{"type", "DIO"}, + wpi::util::json msg = {{"type", "DIO"}, {"device", std::to_string(PIN)}, {"data", {{"<>value", EXPECTED_VALUE}}}}; - wpi::print("***** Input JSON: {}\n", msg.dump()); + wpi::util::print("***** Input JSON: {}\n", msg.dump()); m_webserverClient->SendMessage(msg); done = true; } @@ -136,17 +136,17 @@ TEST_F(WebServerIntegrationTest, DriverStation) { // Attach timer to loop for test function m_server.runner.ExecSync([&](auto& loop) { - auto timer = wpi::uv::Timer::Create(loop); + auto timer = wpi::net::uv::Timer::Create(loop); timer->timeout.connect([&] { if (done) { return; } if (IsConnectedClientWS()) { - wpi::json msg = { + wpi::util::json msg = { {"type", "DriverStation"}, {"device", ""}, {"data", {{">enabled", EXPECTED_VALUE}, {">new_data", true}}}}; - wpi::print("***** Input JSON: {}\n", msg.dump()); + wpi::util::print("***** Input JSON: {}\n", msg.dump()); m_webserverClient->SendMessage(msg); done = true; } diff --git a/simulation/halsim_ws_server/src/test/native/include/WebServerClientTest.hpp b/simulation/halsim_ws_server/src/test/native/include/WebServerClientTest.hpp index fec11d9234..c5d07ce630 100644 --- a/simulation/halsim_ws_server/src/test/native/include/WebServerClientTest.hpp +++ b/simulation/halsim_ws_server/src/test/native/include/WebServerClientTest.hpp @@ -21,19 +21,19 @@ namespace wpilibws { class WebServerClientTest { public: - using BufferPool = wpi::uv::SimpleBufferPool<4>; + using BufferPool = wpi::net::uv::SimpleBufferPool<4>; using LoopFunc = std::function; - using UvExecFunc = wpi::uv::AsyncFunction; + using UvExecFunc = wpi::net::uv::AsyncFunction; - explicit WebServerClientTest(wpi::uv::Loop& loop) : m_loop(loop) {} + explicit WebServerClientTest(wpi::net::uv::Loop& loop) : m_loop(loop) {} WebServerClientTest(const WebServerClientTest&) = delete; WebServerClientTest& operator=(const WebServerClientTest&) = delete; bool Initialize(); void AttemptConnect(); - void SendMessage(const wpi::json& msg); - const wpi::json& GetLastMessage(); + void SendMessage(const wpi::util::json& msg); + const wpi::util::json& GetLastMessage(); bool IsConnectedWS() { return m_ws_connected; } private: @@ -41,14 +41,14 @@ class WebServerClientTest { const std::string& uri); bool m_tcp_connected = false; - std::shared_ptr m_connect_timer; + std::shared_ptr m_connect_timer; int m_connect_attempts = 0; - wpi::uv::Loop& m_loop; - std::shared_ptr m_tcp_client; - wpi::json m_json; + wpi::net::uv::Loop& m_loop; + std::shared_ptr m_tcp_client; + wpi::util::json m_json; bool m_ws_connected = false; - std::shared_ptr m_websocket; + std::shared_ptr m_websocket; std::shared_ptr m_exec; std::unique_ptr m_buffers; std::mutex m_buffers_mutex; diff --git a/simulation/halsim_xrp/src/main/native/cpp/HALSimXRP.cpp b/simulation/halsim_xrp/src/main/native/cpp/HALSimXRP.cpp index 2d73c9aa2f..54a5118ce6 100644 --- a/simulation/halsim_xrp/src/main/native/cpp/HALSimXRP.cpp +++ b/simulation/halsim_xrp/src/main/native/cpp/HALSimXRP.cpp @@ -14,18 +14,18 @@ #include "wpi/util/SmallString.hpp" #include "wpi/util/print.hpp" -namespace uv = wpi::uv; +namespace uv = wpi::net::uv; using namespace wpilibxrp; -HALSimXRP::HALSimXRP(wpi::uv::Loop& loop, +HALSimXRP::HALSimXRP(wpi::net::uv::Loop& loop, wpilibws::ProviderContainer& providers, wpilibws::HALSimWSProviderSimDevices& simDevicesProvider) : m_loop(loop), m_providers(providers), m_simDevicesProvider(simDevicesProvider) { m_loop.error.connect([](uv::Error err) { - wpi::print(stderr, "HALSim XRP Client libuv Error: {}\n", err.str()); + wpi::util::print(stderr, "HALSim XRP Client libuv Error: {}\n", err.str()); }); m_udp_client = uv::Udp::Create(m_loop); @@ -52,14 +52,14 @@ bool HALSimXRP::Initialize() { try { m_port = std::stoi(port); } catch (const std::invalid_argument& err) { - wpi::print(stderr, "Error decoding HALSIMXRP_PORT ({})\n", err.what()); + wpi::util::print(stderr, "Error decoding HALSIMXRP_PORT ({})\n", err.what()); return false; } } else { m_port = 3540; } - wpilibxrp::WPILibUpdateFunc func = [&](const wpi::json& data) { + wpilibxrp::WPILibUpdateFunc func = [&](const wpi::util::json& data) { OnNetValueChanged(data); }; @@ -80,7 +80,7 @@ void HALSimXRP::Start() { ParsePacket({reinterpret_cast(data.base), len}); }); - m_udp_client->closed.connect([]() { wpi::print("Socket Closed\n"); }); + m_udp_client->closed.connect([]() { wpi::util::print("Socket Closed\n"); }); // Fake the OnNetworkConnected call auto hws = shared_from_this(); @@ -104,12 +104,12 @@ void HALSimXRP::ParsePacket(std::span packet) { m_xrp.HandleXRPUpdate(packet); } -void HALSimXRP::OnNetValueChanged(const wpi::json& msg) { +void HALSimXRP::OnNetValueChanged(const wpi::util::json& msg) { try { auto& type = msg.at("type").get_ref(); auto& device = msg.at("device").get_ref(); - wpi::SmallString<64> key; + wpi::util::SmallString<64> key; key.append(type); if (!device.empty()) { key.append("/"); @@ -120,12 +120,12 @@ void HALSimXRP::OnNetValueChanged(const wpi::json& msg) { if (provider) { provider->OnNetValueChanged(msg.at("data")); } - } catch (wpi::json::exception& e) { - wpi::print(stderr, "Error with incoming message: {}\n", e.what()); + } catch (wpi::util::json::exception& e) { + wpi::util::print(stderr, "Error with incoming message: {}\n", e.what()); } } -void HALSimXRP::OnSimValueChanged(const wpi::json& simData) { +void HALSimXRP::OnSimValueChanged(const wpi::util::json& simData) { // We'll use a signal from robot code to send all the data if (simData["type"] == "HAL") { auto halData = simData["data"]; @@ -143,8 +143,8 @@ uv::SimpleBufferPool<4>& HALSimXRP::GetBufferPool() { } void HALSimXRP::SendStateToXRP() { - wpi::SmallVector sendBufs; - wpi::raw_uv_ostream stream{sendBufs, [&] { + wpi::util::SmallVector sendBufs; + wpi::net::raw_uv_ostream stream{sendBufs, [&] { std::lock_guard lock(m_buffer_mutex); return GetBufferPool().Allocate(); }}; diff --git a/simulation/halsim_xrp/src/main/native/cpp/HALSimXRPClient.cpp b/simulation/halsim_xrp/src/main/native/cpp/HALSimXRPClient.cpp index cd66d7a6a2..856e30e1d8 100644 --- a/simulation/halsim_xrp/src/main/native/cpp/HALSimXRPClient.cpp +++ b/simulation/halsim_xrp/src/main/native/cpp/HALSimXRPClient.cpp @@ -20,7 +20,7 @@ using namespace wpilibws; bool HALSimXRPClient::Initialize() { bool result = true; - runner.ExecSync([&](wpi::uv::Loop& loop) { + runner.ExecSync([&](wpi::net::uv::Loop& loop) { simxrp = std::make_shared(loop, providers, simDevices); if (!simxrp->Initialize()) { diff --git a/simulation/halsim_xrp/src/main/native/cpp/XRP.cpp b/simulation/halsim_xrp/src/main/native/cpp/XRP.cpp index 9f7c0d148d..7757d62a1c 100644 --- a/simulation/halsim_xrp/src/main/native/cpp/XRP.cpp +++ b/simulation/halsim_xrp/src/main/native/cpp/XRP.cpp @@ -15,7 +15,7 @@ using namespace wpilibxrp; XRP::XRP() - : m_gyro_name{"XRPGyro"}, m_wpilib_update_func([](const wpi::json&) {}) { + : m_gyro_name{"XRPGyro"}, m_wpilib_update_func([](const wpi::util::json&) {}) { // Set up the inputs and outputs m_motor_outputs.emplace(0, 0.0f); m_motor_outputs.emplace(1, 0.0f); @@ -31,7 +31,7 @@ XRP::XRP() m_encoder_inputs.emplace(3, 0); } -void XRP::HandleWPILibUpdate(const wpi::json& data) { +void XRP::HandleWPILibUpdate(const wpi::util::json& data) { if (data.count("type") == 0) { return; } @@ -97,7 +97,7 @@ void XRP::HandleXRPUpdate(std::span packet) { } } -void XRP::SetupXRPSendBuffer(wpi::raw_uv_ostream& buf) { +void XRP::SetupXRPSendBuffer(wpi::net::raw_uv_ostream& buf) { SetupSendHeader(buf); SetupMotorTag(buf); SetupServoTag(buf); @@ -106,14 +106,14 @@ void XRP::SetupXRPSendBuffer(wpi::raw_uv_ostream& buf) { } // WPILib Sim Handlers -void XRP::HandleDriverStationSimValueChanged(const wpi::json& data) { +void XRP::HandleDriverStationSimValueChanged(const wpi::util::json& data) { auto dsData = data["data"]; if (dsData.find(">enabled") != dsData.end()) { m_robot_enabled = dsData[">enabled"]; } } -void XRP::HandleMotorSimValueChanged(const wpi::json& data) { +void XRP::HandleMotorSimValueChanged(const wpi::util::json& data) { int deviceId = -1; auto motorData = data["data"]; @@ -132,7 +132,7 @@ void XRP::HandleMotorSimValueChanged(const wpi::json& data) { } } -void XRP::HandleServoSimValueChanged(const wpi::json& data) { +void XRP::HandleServoSimValueChanged(const wpi::util::json& data) { int deviceId = -1; auto servoData = data["data"]; @@ -151,7 +151,7 @@ void XRP::HandleServoSimValueChanged(const wpi::json& data) { } } -void XRP::HandleDIOSimValueChanged(const wpi::json& data) { +void XRP::HandleDIOSimValueChanged(const wpi::util::json& data) { int deviceId = -1; auto dioData = data["data"]; @@ -184,11 +184,11 @@ void XRP::HandleDIOSimValueChanged(const wpi::json& data) { } } -void XRP::HandleGyroSimValueChanged(const wpi::json& data) { +void XRP::HandleGyroSimValueChanged(const wpi::util::json& data) { m_gyro_name = data["device"].get(); } -void XRP::HandleEncoderSimValueChanged(const wpi::json& data) { +void XRP::HandleEncoderSimValueChanged(const wpi::util::json& data) { // We need to handle the various encoder cases // 4/5 -> Encoder 0 // 6/7 -> Encoder 1 @@ -228,15 +228,15 @@ void XRP::HandleEncoderSimValueChanged(const wpi::json& data) { // XRP Buffer Generation/Read Methods // ================================== -void XRP::SetupSendHeader(wpi::raw_uv_ostream& buf) { +void XRP::SetupSendHeader(wpi::net::raw_uv_ostream& buf) { uint8_t pktSeq[2]; - wpi::support::endian::write16be(pktSeq, m_xrp_bound_seq); + wpi::util::support::endian::write16be(pktSeq, m_xrp_bound_seq); buf << pktSeq[0] << pktSeq[1] << static_cast(m_robot_enabled ? 1 : 0); } -void XRP::SetupMotorTag(wpi::raw_uv_ostream& buf) { +void XRP::SetupMotorTag(wpi::net::raw_uv_ostream& buf) { uint8_t value[4]; for (auto motor : m_motor_outputs) { @@ -246,13 +246,13 @@ void XRP::SetupMotorTag(wpi::raw_uv_ostream& buf) { << static_cast(motor.first); // Channel // Convert the value - wpi::support::endian::write32be(value, + wpi::util::support::endian::write32be(value, std::bit_cast(motor.second)); buf << value[0] << value[1] << value[2] << value[3]; } } -void XRP::SetupServoTag(wpi::raw_uv_ostream& buf) { +void XRP::SetupServoTag(wpi::net::raw_uv_ostream& buf) { uint8_t value[4]; for (auto servo : m_servo_outputs) { @@ -262,13 +262,13 @@ void XRP::SetupServoTag(wpi::raw_uv_ostream& buf) { << static_cast(servo.first); // Channel // Convert the value - wpi::support::endian::write32be(value, + wpi::util::support::endian::write32be(value, std::bit_cast(servo.second)); buf << value[0] << value[1] << value[2] << value[3]; } } -void XRP::SetupDigitalOutTag(wpi::raw_uv_ostream& buf) { +void XRP::SetupDigitalOutTag(wpi::net::raw_uv_ostream& buf) { for (auto digitalOut : m_digital_outputs) { // DIO payload is 3 bytes buf << static_cast(3) // Size @@ -285,20 +285,20 @@ void XRP::ReadGyroTag(std::span packet) { packet = packet.subspan(2); // Skip past the size and tag float rate_x = - std::bit_cast(wpi::support::endian::read32be(&packet[0])); + std::bit_cast(wpi::util::support::endian::read32be(&packet[0])); float rate_y = - std::bit_cast(wpi::support::endian::read32be(&packet[4])); + std::bit_cast(wpi::util::support::endian::read32be(&packet[4])); float rate_z = - std::bit_cast(wpi::support::endian::read32be(&packet[8])); + std::bit_cast(wpi::util::support::endian::read32be(&packet[8])); float angle_x = - std::bit_cast(wpi::support::endian::read32be(&packet[12])); + std::bit_cast(wpi::util::support::endian::read32be(&packet[12])); float angle_y = - std::bit_cast(wpi::support::endian::read32be(&packet[16])); + std::bit_cast(wpi::util::support::endian::read32be(&packet[16])); float angle_z = - std::bit_cast(wpi::support::endian::read32be(&packet[20])); + std::bit_cast(wpi::util::support::endian::read32be(&packet[20])); // Make the json object - wpi::json gyroJson; + wpi::util::json gyroJson; gyroJson["type"] = "Gyro"; gyroJson["device"] = m_gyro_name; gyroJson["data"] = {{">rate_x", rate_x}, {">rate_y", rate_y}, @@ -314,7 +314,7 @@ void XRP::ReadDIOTag(std::span packet) { return; // size(1) + tag(1) + id(1) + value(1) } - wpi::json dioJson; + wpi::util::json dioJson; dioJson["type"] = "DIO"; dioJson["device"] = std::to_string(packet[2]); dioJson["data"] = {{"<>value", packet[3] == 1}}; @@ -335,7 +335,7 @@ void XRP::ReadEncoderTag(std::span packet) { packet = packet.subspan(3); // Skip past the size and tag and ID int32_t count = - static_cast(wpi::support::endian::read32be(&packet[0])); + static_cast(wpi::util::support::endian::read32be(&packet[0])); // Look up the registered encoders if (m_encoder_channel_map.count(encoderId) == 0) { @@ -344,7 +344,7 @@ void XRP::ReadEncoderTag(std::span packet) { uint8_t wpilibEncoderChannel = m_encoder_channel_map[encoderId]; - wpi::json encJson; + wpi::util::json encJson; encJson["type"] = "Encoder"; encJson["device"] = std::to_string(wpilibEncoderChannel); encJson["data"] = {{">count", count}}; @@ -360,11 +360,11 @@ void XRP::ReadEncoderTag(std::span packet) { size_t i = sizeof(count); uint32_t period_numerator = - static_cast(wpi::support::endian::read32be(&packet[i])); + static_cast(wpi::util::support::endian::read32be(&packet[i])); i += sizeof(period_numerator); uint32_t period_denominator = - static_cast(wpi::support::endian::read32be(&packet[i])); + static_cast(wpi::util::support::endian::read32be(&packet[i])); double period = static_cast(period_numerator >> 1) / period_denominator; @@ -374,7 +374,7 @@ void XRP::ReadEncoderTag(std::span packet) { period = -period; } - encJson["data"].push_back({wpi::json(">period"), wpi::json(period)}); + encJson["data"].push_back({wpi::util::json(">period"), wpi::util::json(period)}); } m_wpilib_update_func(encJson); @@ -389,9 +389,9 @@ void XRP::ReadAnalogTag(std::span packet) { packet = packet.subspan(3); float voltage = - std::bit_cast(wpi::support::endian::read32be(&packet[0])); + std::bit_cast(wpi::util::support::endian::read32be(&packet[0])); - wpi::json analogJson; + wpi::util::json analogJson; analogJson["type"] = "AI"; analogJson["device"] = std::to_string(analogId); analogJson["data"] = {{">voltage", voltage}}; diff --git a/simulation/halsim_xrp/src/main/native/include/wpi/halsim/xrp/HALSimXRP.hpp b/simulation/halsim_xrp/src/main/native/include/wpi/halsim/xrp/HALSimXRP.hpp index 0a59aa4270..2c234ac004 100644 --- a/simulation/halsim_xrp/src/main/native/include/wpi/halsim/xrp/HALSimXRP.hpp +++ b/simulation/halsim_xrp/src/main/native/include/wpi/halsim/xrp/HALSimXRP.hpp @@ -28,9 +28,9 @@ class HALSimXRP : public wpilibws::HALSimBaseWebSocketConnection, public std::enable_shared_from_this { public: using LoopFunc = std::function; - using UvExecFunc = wpi::uv::Async; + using UvExecFunc = wpi::net::uv::Async; - HALSimXRP(wpi::uv::Loop& loop, wpilibws::ProviderContainer& providers, + HALSimXRP(wpi::net::uv::Loop& loop, wpilibws::ProviderContainer& providers, wpilibws::HALSimWSProviderSimDevices& simDevicesProvider); HALSimXRP(const HALSimXRP&) = delete; HALSimXRP& operator=(const HALSimXRP&) = delete; @@ -39,20 +39,20 @@ class HALSimXRP : public wpilibws::HALSimBaseWebSocketConnection, void Start(); void ParsePacket(std::span packet); - void OnNetValueChanged(const wpi::json& msg); - void OnSimValueChanged(const wpi::json& simData) override; + void OnNetValueChanged(const wpi::util::json& msg); + void OnSimValueChanged(const wpi::util::json& simData) override; const std::string& GetTargetHost() const { return m_host; } int GetTargetPort() const { return m_port; } - wpi::uv::Loop& GetLoop() { return m_loop; } + wpi::net::uv::Loop& GetLoop() { return m_loop; } UvExecFunc& GetExec() { return *m_exec; } private: XRP m_xrp; - wpi::uv::Loop& m_loop; - std::shared_ptr m_udp_client; + wpi::net::uv::Loop& m_loop; + std::shared_ptr m_udp_client; std::shared_ptr m_exec; wpilibws::ProviderContainer& m_providers; @@ -62,7 +62,7 @@ class HALSimXRP : public wpilibws::HALSimBaseWebSocketConnection, int m_port; void SendStateToXRP(); - wpi::uv::SimpleBufferPool<4>& GetBufferPool(); + wpi::net::uv::SimpleBufferPool<4>& GetBufferPool(); std::mutex m_buffer_mutex; struct sockaddr_in m_dest; diff --git a/simulation/halsim_xrp/src/main/native/include/wpi/halsim/xrp/HALSimXRPClient.hpp b/simulation/halsim_xrp/src/main/native/include/wpi/halsim/xrp/HALSimXRPClient.hpp index 2126001da8..bb678e578d 100644 --- a/simulation/halsim_xrp/src/main/native/include/wpi/halsim/xrp/HALSimXRPClient.hpp +++ b/simulation/halsim_xrp/src/main/native/include/wpi/halsim/xrp/HALSimXRPClient.hpp @@ -23,7 +23,7 @@ class HALSimXRPClient { wpilibws::ProviderContainer providers; wpilibws::HALSimWSProviderSimDevices simDevices{providers}; - wpi::EventLoopRunner runner; + wpi::net::EventLoopRunner runner; std::shared_ptr simxrp; }; diff --git a/simulation/halsim_xrp/src/main/native/include/wpi/halsim/xrp/XRP.hpp b/simulation/halsim_xrp/src/main/native/include/wpi/halsim/xrp/XRP.hpp index 29969d8db5..2cb0af2e93 100644 --- a/simulation/halsim_xrp/src/main/native/include/wpi/halsim/xrp/XRP.hpp +++ b/simulation/halsim_xrp/src/main/native/include/wpi/halsim/xrp/XRP.hpp @@ -22,7 +22,7 @@ namespace wpilibxrp { -using WPILibUpdateFunc = std::function; +using WPILibUpdateFunc = std::function; class XRP { public: @@ -32,25 +32,25 @@ class XRP { m_wpilib_update_func = func; } - void HandleWPILibUpdate(const wpi::json& data); + void HandleWPILibUpdate(const wpi::util::json& data); void HandleXRPUpdate(std::span packet); - void SetupXRPSendBuffer(wpi::raw_uv_ostream& buf); + void SetupXRPSendBuffer(wpi::net::raw_uv_ostream& buf); private: // To XRP Methods - void SetupSendHeader(wpi::raw_uv_ostream& buf); - void SetupMotorTag(wpi::raw_uv_ostream& buf); - void SetupServoTag(wpi::raw_uv_ostream& buf); - void SetupDigitalOutTag(wpi::raw_uv_ostream& buf); + void SetupSendHeader(wpi::net::raw_uv_ostream& buf); + void SetupMotorTag(wpi::net::raw_uv_ostream& buf); + void SetupServoTag(wpi::net::raw_uv_ostream& buf); + void SetupDigitalOutTag(wpi::net::raw_uv_ostream& buf); // WPILib Sim Update Handlers - void HandleDriverStationSimValueChanged(const wpi::json& data); - void HandleMotorSimValueChanged(const wpi::json& data); - void HandleServoSimValueChanged(const wpi::json& data); - void HandleDIOSimValueChanged(const wpi::json& data); - void HandleGyroSimValueChanged(const wpi::json& data); - void HandleEncoderSimValueChanged(const wpi::json& data); + void HandleDriverStationSimValueChanged(const wpi::util::json& data); + void HandleMotorSimValueChanged(const wpi::util::json& data); + void HandleServoSimValueChanged(const wpi::util::json& data); + void HandleDIOSimValueChanged(const wpi::util::json& data); + void HandleGyroSimValueChanged(const wpi::util::json& data); + void HandleEncoderSimValueChanged(const wpi::util::json& data); // XRP Packet Update Handlers void ReadGyroTag(std::span packet); diff --git a/tools/datalogtool/src/main/native/cpp/App.cpp b/tools/datalogtool/src/main/native/cpp/App.cpp index 0b7285e628..47e8dd4427 100644 --- a/tools/datalogtool/src/main/native/cpp/App.cpp +++ b/tools/datalogtool/src/main/native/cpp/App.cpp @@ -64,7 +64,7 @@ static void DisplayDownload() { if (ImGui::Begin("Download", gDownloadVisible)) { if (!gDownloader) { gDownloader = std::make_unique( - glass::GetStorageRoot().GetChild("download")); + wpi::glass::GetStorageRoot().GetChild("download")); } gDownloader->Display(); } @@ -74,7 +74,7 @@ static void DisplayDownload() { static void DisplayMainMenu() { ImGui::BeginMainMenuBar(); - static glass::MainMenuBar mainMenu; + static wpi::glass::MainMenuBar mainMenu; mainMenu.WorkspaceMenu(); gui::EmitViewMenu(); @@ -110,7 +110,7 @@ static void DisplayMainMenu() { ImGui::Separator(); ImGui::Text("v%s", GetWPILibVersion()); ImGui::Separator(); - ImGui::Text("Save location: %s", glass::GetStorageDir().c_str()); + ImGui::Text("Save location: %s", wpi::glass::GetStorageDir().c_str()); ImGui::Text("%.3f ms/frame (%.1f FPS)", 1000.0f / ImGui::GetIO().Framerate, ImGui::GetIO().Framerate); if (ImGui::Button("Close")) { @@ -124,7 +124,7 @@ static void DisplayGui() { DisplayMainMenu(); DisplayInputFiles(); DisplayEntries(); - DisplayOutput(glass::GetStorageRoot().GetChild("output")); + DisplayOutput(wpi::glass::GetStorageRoot().GetChild("output")); DisplayDownload(); } @@ -132,7 +132,7 @@ void Application(std::string_view saveDir) { ssh_init(); gui::CreateContext(); - glass::CreateContext(); + wpi::glass::CreateContext(); // Add icons gui::AddIcon(dlt::GetResource_dlt_16_png()); @@ -143,8 +143,8 @@ void Application(std::string_view saveDir) { gui::AddIcon(dlt::GetResource_dlt_256_png()); gui::AddIcon(dlt::GetResource_dlt_512_png()); - glass::SetStorageName("datalogtool"); - glass::SetStorageDir(saveDir.empty() ? gui::GetPlatformSaveFileDir() + wpi::glass::SetStorageName("datalogtool"); + wpi::glass::SetStorageDir(saveDir.empty() ? gui::GetPlatformSaveFileDir() : saveDir); gui::AddWindowScaler([](float scale) { gDefaultScale = scale; }); @@ -152,12 +152,12 @@ void Application(std::string_view saveDir) { gui::Initialize("Datalog Tool", 925, 510); gDownloadVisible = - &glass::GetStorageRoot().GetChild("download").GetBool("visible", true); + &wpi::glass::GetStorageRoot().GetChild("download").GetBool("visible", true); gui::Main(); gShutdown = true; - glass::DestroyContext(); + wpi::glass::DestroyContext(); gui::DestroyContext(); gDownloader.reset(); diff --git a/tools/datalogtool/src/main/native/cpp/Downloader.cpp b/tools/datalogtool/src/main/native/cpp/Downloader.cpp index dc76cd80f0..3839c149a2 100644 --- a/tools/datalogtool/src/main/native/cpp/Downloader.cpp +++ b/tools/datalogtool/src/main/native/cpp/Downloader.cpp @@ -28,7 +28,7 @@ #include "wpi/util/StringExtras.hpp" #include "wpi/util/fs.hpp" -Downloader::Downloader(glass::Storage& storage) +Downloader::Downloader(wpi::glass::Storage& storage) : m_serverTeam{storage.GetString("serverTeam")}, m_remoteDir{storage.GetString("remoteDir", "/home/systemcore/logs")}, m_username{storage.GetString("username", "systemcore")}, @@ -104,15 +104,15 @@ void Downloader::DisplayRemoteDirSelector() { for (auto&& dir : m_dirList) { if (ImGui::Selectable(dir.c_str())) { if (dir == "..") { - if (wpi::ends_with(m_remoteDir, '/')) { + if (wpi::util::ends_with(m_remoteDir, '/')) { m_remoteDir.resize(m_remoteDir.size() - 1); } - m_remoteDir = wpi::rsplit(m_remoteDir, '/').first; + m_remoteDir = wpi::util::rsplit(m_remoteDir, '/').first; if (m_remoteDir.empty()) { m_remoteDir = "/"; } } else { - if (!wpi::ends_with(m_remoteDir, '/')) { + if (!wpi::util::ends_with(m_remoteDir, '/')) { m_remoteDir += '/'; } m_remoteDir += dir; @@ -286,7 +286,7 @@ void Downloader::ThreadMain() { try { switch (m_state) { case kConnecting: - if (auto team = wpi::parse_integer(m_serverTeam, 10)) { + if (auto team = wpi::util::parse_integer(m_serverTeam, 10)) { // team number session = std::make_unique( fmt::format("roborio-{}-frc.local", team.value()), 22, @@ -335,7 +335,7 @@ void Downloader::ThreadMain() { } } else if (attr.type == SSH_FILEXFER_TYPE_REGULAR && (attr.flags & SSH_FILEXFER_ATTR_SIZE) != 0 && - wpi::ends_with(attr.name, ".wpilog")) { + wpi::util::ends_with(attr.name, ".wpilog")) { m_fileList.emplace_back(attr.name, attr.size); } } @@ -359,7 +359,7 @@ void Downloader::ThreadMain() { auto remoteFilename = fmt::format( "{}{}{}", m_remoteDir, - wpi::ends_with(m_remoteDir, '/') ? "" : "/", file.name); + wpi::util::ends_with(m_remoteDir, '/') ? "" : "/", file.name); auto localFilename = fs::path{m_localDir} / file.name; uint64_t fileSize = file.size; @@ -450,7 +450,7 @@ void Downloader::ThreadMain() { auto remoteFilename = fmt::format( "{}{}{}", m_remoteDir, - wpi::ends_with(m_remoteDir, '/') ? "" : "/", file.name); + wpi::util::ends_with(m_remoteDir, '/') ? "" : "/", file.name); lock.unlock(); try { diff --git a/tools/datalogtool/src/main/native/cpp/Downloader.hpp b/tools/datalogtool/src/main/native/cpp/Downloader.hpp index 2054382ef4..94410a03fb 100644 --- a/tools/datalogtool/src/main/native/cpp/Downloader.hpp +++ b/tools/datalogtool/src/main/native/cpp/Downloader.hpp @@ -12,7 +12,7 @@ #include "wpi/util/condition_variable.hpp" #include "wpi/util/mutex.hpp" -namespace glass { +namespace wpi::glass { class Storage; } // namespace glass @@ -22,7 +22,7 @@ class select_folder; class Downloader { public: - explicit Downloader(glass::Storage& storage); + explicit Downloader(wpi::glass::Storage& storage); ~Downloader(); void Display(); @@ -36,7 +36,7 @@ class Downloader { void ThreadMain(); - wpi::mutex m_mutex; + wpi::util::mutex m_mutex; enum State { kDisconnected, kConnecting, diff --git a/tools/datalogtool/src/main/native/cpp/Exporter.cpp b/tools/datalogtool/src/main/native/cpp/Exporter.cpp index 76fbd4df9a..0b28733fe2 100644 --- a/tools/datalogtool/src/main/native/cpp/Exporter.cpp +++ b/tools/datalogtool/src/main/native/cpp/Exporter.cpp @@ -84,7 +84,7 @@ struct EntryTreeNode { static std::map, std::less<>> gInputFiles; -static wpi::mutex gEntriesMutex; +static wpi::util::mutex gEntriesMutex; static std::map, std::less<>> gEntries; static std::vector gEntryTree; std::atomic_int gExportCount{0}; @@ -92,17 +92,17 @@ std::atomic_int gExportCount{0}; // must be called with gEntriesMutex held static void RebuildEntryTree() { gEntryTree.clear(); - wpi::SmallVector parts; + wpi::util::SmallVector parts; for (auto& kv : gEntries) { parts.clear(); // split on first : if one is present - auto [prefix, mainpart] = wpi::split(kv.first, ':'); - if (mainpart.empty() || wpi::contains(prefix, '/')) { + auto [prefix, mainpart] = wpi::util::split(kv.first, ':'); + if (mainpart.empty() || wpi::util::contains(prefix, '/')) { mainpart = kv.first; } else { parts.emplace_back(prefix); } - wpi::split(mainpart, '/', -1, false, + wpi::util::split(mainpart, '/', -1, false, [&](auto part) { parts.emplace_back(part); }); // ignore a raw "/" key @@ -112,7 +112,7 @@ static void RebuildEntryTree() { // get to leaf auto nodes = &gEntryTree; - for (auto part : wpi::drop_back(std::span{parts.begin(), parts.end()})) { + for (auto part : wpi::util::drop_back(std::span{parts.begin(), parts.end()})) { auto it = std::find_if(nodes->begin(), nodes->end(), [&](const auto& node) { return node.name == part; }); @@ -183,7 +183,7 @@ InputFile::~InputFile() { } static std::unique_ptr LoadDataLog(std::string_view filename) { - auto fileBuffer = wpi::MemoryBuffer::GetFile(filename); + auto fileBuffer = wpi::util::MemoryBuffer::GetFile(filename); if (!fileBuffer) { return std::make_unique( filename, @@ -436,46 +436,46 @@ void DisplayEntries() { ImGui::End(); } -static wpi::mutex gExportMutex; +static wpi::util::mutex gExportMutex; static std::vector gExportErrors; -static void PrintEscapedCsvString(wpi::raw_ostream& os, std::string_view str) { +static void PrintEscapedCsvString(wpi::util::raw_ostream& os, std::string_view str) { auto s = str; while (!s.empty()) { std::string_view fragment; - std::tie(fragment, s) = wpi::split(s, '"'); + std::tie(fragment, s) = wpi::util::split(s, '"'); os << fragment; if (!s.empty()) { os << '"' << '"'; } } - if (wpi::ends_with(str, '"')) { + if (wpi::util::ends_with(str, '"')) { os << '"' << '"'; } } -static void ValueToCsv(wpi::raw_ostream& os, const Entry& entry, +static void ValueToCsv(wpi::util::raw_ostream& os, const Entry& entry, const wpi::log::DataLogRecord& record) { // handle systemTime specially if (entry.name == "systemTime" && entry.type == "int64") { int64_t val; if (record.GetInteger(&val)) { std::time_t timeval = val / 1000000; - wpi::print(os, "{:%Y-%m-%d %H:%M:%S}.{:06}", *std::localtime(&timeval), + wpi::util::print(os, "{:%Y-%m-%d %H:%M:%S}.{:06}", *std::localtime(&timeval), val % 1000000); return; } } else if (entry.type == "double") { double val; if (record.GetDouble(&val)) { - wpi::print(os, "{}", val); + wpi::util::print(os, "{}", val); return; } } else if (entry.type == "int64" || entry.type == "int") { // support "int" for compatibility with old NT4 datalogs int64_t val; if (record.GetInteger(&val)) { - wpi::print(os, "{}", val); + wpi::util::print(os, "{}", val); return; } } else if (entry.type == "string" || entry.type == "json") { @@ -488,31 +488,31 @@ static void ValueToCsv(wpi::raw_ostream& os, const Entry& entry, } else if (entry.type == "boolean") { bool val; if (record.GetBoolean(&val)) { - wpi::print(os, "{}", val); + wpi::util::print(os, "{}", val); return; } } else if (entry.type == "boolean[]") { std::vector val; if (record.GetBooleanArray(&val)) { - wpi::print(os, "{}", fmt::join(val, ";")); + wpi::util::print(os, "{}", fmt::join(val, ";")); return; } } else if (entry.type == "double[]") { std::vector val; if (record.GetDoubleArray(&val)) { - wpi::print(os, "{}", fmt::join(val, ";")); + wpi::util::print(os, "{}", fmt::join(val, ";")); return; } } else if (entry.type == "float[]") { std::vector val; if (record.GetFloatArray(&val)) { - wpi::print(os, "{}", fmt::join(val, ";")); + wpi::util::print(os, "{}", fmt::join(val, ";")); return; } } else if (entry.type == "int64[]") { std::vector val; if (record.GetIntegerArray(&val)) { - wpi::print(os, "{}", fmt::join(val, ";")); + wpi::util::print(os, "{}", fmt::join(val, ";")); return; } } else if (entry.type == "string[]") { @@ -531,10 +531,10 @@ static void ValueToCsv(wpi::raw_ostream& os, const Entry& entry, return; } } - wpi::print(os, ""); + wpi::util::print(os, ""); } -static void ExportCsvFile(InputFile& f, wpi::raw_ostream& os, int style) { +static void ExportCsvFile(InputFile& f, wpi::util::raw_ostream& os, int style) { // header if (style == 0) { os << "Timestamp,Name,Value\n"; @@ -556,7 +556,7 @@ static void ExportCsvFile(InputFile& f, wpi::raw_ostream& os, int style) { os << '\n'; } - wpi::DenseMap nameMap; + wpi::util::DenseMap nameMap; for (auto&& record : f.datalog->GetReader()) { if (record.IsStart()) { wpi::log::StartRecordData data; @@ -579,13 +579,13 @@ static void ExportCsvFile(InputFile& f, wpi::raw_ostream& os, int style) { Entry* entry = entryIt->second; if (style == 0) { - wpi::print(os, "{},\"", record.GetTimestamp() / 1000000.0); + wpi::util::print(os, "{},\"", record.GetTimestamp() / 1000000.0); PrintEscapedCsvString(os, entry->name); os << '"' << ','; ValueToCsv(os, *entry, record); os << '\n'; } else if (style == 1 && entry->column != -1) { - wpi::print(os, "{},", record.GetTimestamp() / 1000000.0); + wpi::util::print(os, "{},", record.GetTimestamp() / 1000000.0); for (int i = 0; i < entry->column; ++i) { os << ','; } @@ -611,14 +611,14 @@ static void ExportCsv(std::string_view outputFolder, int style) { ++gExportCount; continue; } - wpi::raw_fd_ostream os{fs::FileToFd(of, ec, fs::OF_Text), true}; + wpi::util::raw_fd_ostream os{fs::FileToFd(of, ec, fs::OF_Text), true}; ExportCsvFile(*f.second, os, style); } ++gExportCount; } } -void DisplayOutput(glass::Storage& storage) { +void DisplayOutput(wpi::glass::Storage& storage) { static std::string& outputFolder = storage.GetString("outputFolder"); static std::unique_ptr outputFolderSelector; diff --git a/tools/datalogtool/src/main/native/cpp/Exporter.hpp b/tools/datalogtool/src/main/native/cpp/Exporter.hpp index 8078243bb7..a0ca032a18 100644 --- a/tools/datalogtool/src/main/native/cpp/Exporter.hpp +++ b/tools/datalogtool/src/main/native/cpp/Exporter.hpp @@ -4,12 +4,12 @@ #pragma once -namespace glass { +namespace wpi::glass { class Storage; } // namespace glass void DisplayInputFiles(); void DisplayEntries(); -void DisplayOutput(glass::Storage& storage); +void DisplayOutput(wpi::glass::Storage& storage); extern bool gShutdown; diff --git a/tools/outlineviewer/src/main/native/cpp/main.cpp b/tools/outlineviewer/src/main/native/cpp/main.cpp index 74b1008947..8b2048e22d 100644 --- a/tools/outlineviewer/src/main/native/cpp/main.cpp +++ b/tools/outlineviewer/src/main/native/cpp/main.cpp @@ -34,21 +34,21 @@ std::string_view GetResource_ov_256_png(); std::string_view GetResource_ov_512_png(); } // namespace ov -static std::unique_ptr gModel; -static std::unique_ptr gSettings; -static glass::LogData gLog; -static glass::NetworkTablesFlagsSettings gFlagsSettings; -static glass::MainMenuBar gMainMenu; +static std::unique_ptr gModel; +static std::unique_ptr gSettings; +static wpi::glass::LogData gLog; +static wpi::glass::NetworkTablesFlagsSettings gFlagsSettings; +static wpi::glass::MainMenuBar gMainMenu; static unsigned int gPrevMode = NT_NET_MODE_NONE; /** * Generates the proper title bar title based on current instance state and * event. */ -static std::string MakeTitle(NT_Inst inst, nt::Event event) { - auto mode = nt::GetNetworkMode(inst); +static std::string MakeTitle(NT_Inst inst, wpi::nt::Event event) { + auto mode = wpi::nt::GetNetworkMode(inst); if (mode & NT_NET_MODE_SERVER) { - auto numClients = nt::GetConnections(inst).size(); + auto numClients = wpi::nt::GetConnections(inst).size(); return fmt::format("OutlineViewer - {} Client{} Connected", numClients, (numClients == 1 ? "" : "s")); } else if (mode & NT_NET_MODE_CLIENT) { @@ -61,22 +61,22 @@ static std::string MakeTitle(NT_Inst inst, nt::Event event) { } static void NtInitialize() { - auto inst = nt::GetDefaultInstance(); - auto poller = nt::CreateListenerPoller(inst); - nt::AddPolledListener(poller, inst, NT_EVENT_CONNECTION | NT_EVENT_IMMEDIATE); - nt::AddPolledLogger(poller, NT_LOG_INFO, 100); + auto inst = wpi::nt::GetDefaultInstance(); + auto poller = wpi::nt::CreateListenerPoller(inst); + wpi::nt::AddPolledListener(poller, inst, NT_EVENT_CONNECTION | NT_EVENT_IMMEDIATE); + wpi::nt::AddPolledLogger(poller, NT_LOG_INFO, 100); gui::AddEarlyExecute([inst, poller] { auto win = gui::GetSystemWindow(); if (!win) { return; } bool updateTitle = false; - nt::Event connectionEvent; - if (nt::GetNetworkMode(inst) != gPrevMode) { - gPrevMode = nt::GetNetworkMode(inst); + wpi::nt::Event connectionEvent; + if (wpi::nt::GetNetworkMode(inst) != gPrevMode) { + gPrevMode = wpi::nt::GetNetworkMode(inst); updateTitle = true; } - for (auto&& event : nt::ReadListenerQueue(poller)) { + for (auto&& event : wpi::nt::ReadListenerQueue(poller)) { if (event.Is(NT_EVENT_CONNECTION)) { updateTitle = true; connectionEvent = event; @@ -101,13 +101,13 @@ static void NtInitialize() { }); // NetworkTables table window - gModel = std::make_unique(); + gModel = std::make_unique(); gui::AddEarlyExecute([] { gModel->Update(); }); // NetworkTables settings window - gSettings = std::make_unique( + gSettings = std::make_unique( "outlineviewer", - glass::GetStorageRoot().GetChild("NetworkTables Settings")); + wpi::glass::GetStorageRoot().GetChild("NetworkTables Settings")); gui::AddEarlyExecute([] { gSettings->Update(); }); } @@ -139,7 +139,7 @@ static void DisplayGui() { gui::EmitViewMenu(); if (ImGui::BeginMenu("View")) { gFlagsSettings.DisplayMenu(); - glass::DisplayNetworkTablesAddMenu(gModel.get()); + wpi::glass::DisplayNetworkTablesAddMenu(gModel.get()); ImGui::EndMenu(); } @@ -197,7 +197,7 @@ static void DisplayGui() { ImGui::CloseCurrentPopup(); } ImGui::BeginChild("Lines", ImVec2(width * 0.75f, height * 0.75f)); - glass::DisplayLog(&gLog, true); + wpi::glass::DisplayLog(&gLog, true); ImGui::EndChild(); ImGui::EndPopup(); } @@ -212,7 +212,7 @@ static void DisplayGui() { ImGui::Separator(); ImGui::Text("v%s", GetWPILibVersion()); ImGui::Separator(); - ImGui::Text("Save location: %s", glass::GetStorageDir().c_str()); + ImGui::Text("Save location: %s", wpi::glass::GetStorageDir().c_str()); ImGui::Text("%.3f ms/frame (%.1f FPS)", 1000.0f / ImGui::GetIO().Framerate, ImGui::GetIO().Framerate); if (ImGui::Button("Close")) { @@ -222,9 +222,9 @@ static void DisplayGui() { } // display table view - glass::DisplayNetworkTablesInfo(gModel.get()); + wpi::glass::DisplayNetworkTablesInfo(gModel.get()); ImGui::Separator(); - glass::DisplayNetworkTables(gModel.get(), gFlagsSettings.GetFlags()); + wpi::glass::DisplayNetworkTables(gModel.get(), gFlagsSettings.GetFlags()); ImGui::End(); } @@ -243,7 +243,7 @@ int main(int argc, char** argv) { } gui::CreateContext(); - glass::CreateContext(); + wpi::glass::CreateContext(); gui::AddIcon(ov::GetResource_ov_16_png()); gui::AddIcon(ov::GetResource_ov_32_png()); @@ -253,8 +253,8 @@ int main(int argc, char** argv) { gui::AddIcon(ov::GetResource_ov_256_png()); gui::AddIcon(ov::GetResource_ov_512_png()); - glass::SetStorageName("outlineviewer"); - glass::SetStorageDir(saveDir.empty() ? gui::GetPlatformSaveFileDir() + wpi::glass::SetStorageName("outlineviewer"); + wpi::glass::SetStorageDir(saveDir.empty() ? gui::GetPlatformSaveFileDir() : saveDir); gui::AddInit(NtInitialize); @@ -267,7 +267,7 @@ int main(int argc, char** argv) { gModel.reset(); gSettings.reset(); - glass::DestroyContext(); + wpi::glass::DestroyContext(); gui::DestroyContext(); return 0; diff --git a/tools/sysid/src/main/native/cpp/App.cpp b/tools/sysid/src/main/native/cpp/App.cpp index 89b63d9e1a..6ee8e6a576 100644 --- a/tools/sysid/src/main/native/cpp/App.cpp +++ b/tools/sysid/src/main/native/cpp/App.cpp @@ -31,16 +31,16 @@ namespace gui = wpi::gui; -static std::unique_ptr gWindowManager; +static std::unique_ptr gWindowManager; -glass::Window* gLogLoaderWindow; -glass::Window* gDataSelectorWindow; -glass::Window* gAnalyzerWindow; -glass::Window* gProgramLogWindow; -static glass::MainMenuBar gMainMenu; +wpi::glass::Window* gLogLoaderWindow; +wpi::glass::Window* gDataSelectorWindow; +wpi::glass::Window* gAnalyzerWindow; +wpi::glass::Window* gProgramLogWindow; +static wpi::glass::MainMenuBar gMainMenu; -glass::LogData gLog; -wpi::Logger gLogger; +wpi::glass::LogData gLog; +wpi::util::Logger gLogger; const char* GetWPILibVersion(); @@ -57,7 +57,7 @@ std::string_view GetResource_sysid_512_png(); void Application(std::string_view saveDir) { // Create the wpigui (along with Dear ImGui) and Glass contexts. gui::CreateContext(); - glass::CreateContext(); + wpi::glass::CreateContext(); // Add icons gui::AddIcon(sysid::GetResource_sysid_16_png()); @@ -68,37 +68,37 @@ void Application(std::string_view saveDir) { gui::AddIcon(sysid::GetResource_sysid_256_png()); gui::AddIcon(sysid::GetResource_sysid_512_png()); - glass::SetStorageName("sysid"); - glass::SetStorageDir(saveDir.empty() ? gui::GetPlatformSaveFileDir() + wpi::glass::SetStorageName("sysid"); + wpi::glass::SetStorageDir(saveDir.empty() ? gui::GetPlatformSaveFileDir() : saveDir); // Add messages from the global sysid logger into the Log window. gLogger.SetLogger([](unsigned int level, const char* file, unsigned int line, const char* msg) { const char* lvl = ""; - if (level >= wpi::WPI_LOG_CRITICAL) { + if (level >= wpi::util::WPI_LOG_CRITICAL) { lvl = "CRITICAL: "; - } else if (level >= wpi::WPI_LOG_ERROR) { + } else if (level >= wpi::util::WPI_LOG_ERROR) { lvl = "ERROR: "; - } else if (level >= wpi::WPI_LOG_WARNING) { + } else if (level >= wpi::util::WPI_LOG_WARNING) { lvl = "WARNING: "; - } else if (level >= wpi::WPI_LOG_INFO) { + } else if (level >= wpi::util::WPI_LOG_INFO) { lvl = "INFO: "; - } else if (level >= wpi::WPI_LOG_DEBUG) { + } else if (level >= wpi::util::WPI_LOG_DEBUG) { lvl = "DEBUG: "; } std::string filename = std::filesystem::path{file}.filename().string(); gLog.Append(fmt::format("{}{} ({}:{})\n", lvl, msg, filename, line)); #ifndef NDEBUG - wpi::print(stderr, "{}{} ({}:{})\n", lvl, msg, filename, line); + wpi::util::print(stderr, "{}{} ({}:{})\n", lvl, msg, filename, line); #endif }); - gLogger.set_min_level(wpi::WPI_LOG_DEBUG); + gLogger.set_min_level(wpi::util::WPI_LOG_DEBUG); // Initialize window manager and add views. - auto& storage = glass::GetStorageRoot().GetChild("SysId"); - gWindowManager = std::make_unique(storage); + auto& storage = wpi::glass::GetStorageRoot().GetChild("SysId"); + gWindowManager = std::make_unique(storage); gWindowManager->GlobalInit(); auto logLoader = std::make_unique(storage, gLogger); @@ -122,7 +122,7 @@ void Application(std::string_view saveDir) { gAnalyzerWindow = gWindowManager->AddWindow("Analyzer", std::move(analyzer)); gProgramLogWindow = gWindowManager->AddWindow( - "Program Log", std::make_unique(&gLog)); + "Program Log", std::make_unique(&gLog)); // Set default positions and sizes for windows. @@ -194,7 +194,7 @@ void Application(std::string_view saveDir) { ImGui::Separator(); ImGui::Text("v%s", GetWPILibVersion()); ImGui::Separator(); - ImGui::Text("Save location: %s", glass::GetStorageDir().c_str()); + ImGui::Text("Save location: %s", wpi::glass::GetStorageDir().c_str()); if (ImGui::Button("Close")) { ImGui::CloseCurrentPopup(); } @@ -206,7 +206,7 @@ void Application(std::string_view saveDir) { sysid::kAppWindowSize.y); gui::Main(); - glass::DestroyContext(); + wpi::glass::DestroyContext(); gui::DestroyContext(); } diff --git a/tools/sysid/src/main/native/cpp/Util.cpp b/tools/sysid/src/main/native/cpp/Util.cpp index 95296c8627..f1173f3ee3 100644 --- a/tools/sysid/src/main/native/cpp/Util.cpp +++ b/tools/sysid/src/main/native/cpp/Util.cpp @@ -67,7 +67,7 @@ void sysid::SaveFile(std::string_view contents, // Open a fd_ostream to write to file. std::error_code ec; // NOLINTNEXTLINE(build/include_what_you_use) - wpi::raw_fd_ostream ostream{path.string(), ec}; + wpi::util::raw_fd_ostream ostream{path.string(), ec}; // Check error code. if (ec) { diff --git a/tools/sysid/src/main/native/cpp/analysis/AnalysisManager.cpp b/tools/sysid/src/main/native/cpp/analysis/AnalysisManager.cpp index 7aa9ac2cbd..c4143009a3 100644 --- a/tools/sysid/src/main/native/cpp/analysis/AnalysisManager.cpp +++ b/tools/sysid/src/main/native/cpp/analysis/AnalysisManager.cpp @@ -20,7 +20,7 @@ using namespace sysid; -static double Lerp(units::second_t time, +static double Lerp(wpi::units::second_t time, std::vector>& data) { auto next = std::find_if(data.begin(), data.end(), [&](const auto& entry) { return entry.time > time; @@ -36,7 +36,7 @@ static double Lerp(units::second_t time, const auto prev = next - 1; - return wpi::Lerp(prev->measurement, next->measurement, + return wpi::util::Lerp(prev->measurement, next->measurement, (time - prev->time) / (next->time - prev->time)); } @@ -79,21 +79,21 @@ static std::vector ConvertToPrepared(const MotorData& data) { /** * To preserve a raw copy of the data, this method saves a raw version - * in the dataset StringMap where the key of the raw data starts with "raw-" + * in the dataset wpi::util::StringMap where the key of the raw data starts with "raw-" * before the name of the original data. * * @tparam S The size of the array data that's being used * * @param dataset A reference to the dataset being used */ -static void CopyRawData(wpi::StringMap* dataset) { +static void CopyRawData(wpi::util::StringMap* dataset) { auto& data = *dataset; // Loads the Raw Data for (auto& it : data) { auto& key = it.first; auto& motorData = it.second; - if (!wpi::contains(key, "raw")) { + if (!wpi::util::contains(key, "raw")) { data[fmt::format("raw-{}", key)] = motorData; data[fmt::format("original-raw-{}", key)] = motorData; } @@ -116,7 +116,7 @@ static Storage CombineDatasets(const std::vector& slowForward, } void AnalysisManager::PrepareGeneralData() { - wpi::StringMap> preparedData; + wpi::util::StringMap> preparedData; WPI_INFO(m_logger, "{}", "Preprocessing raw data."); @@ -167,11 +167,11 @@ void AnalysisManager::PrepareGeneralData() { preparedData["raw-dynamic-reverse"][0].timestamp}; } -AnalysisManager::AnalysisManager(Settings& settings, wpi::Logger& logger) +AnalysisManager::AnalysisManager(Settings& settings, wpi::util::Logger& logger) : m_logger{logger}, m_settings{settings} {} AnalysisManager::AnalysisManager(TestData data, Settings& settings, - wpi::Logger& logger) + wpi::util::Logger& logger) : m_data{std::move(data)}, m_logger{logger}, m_settings{settings} { // Reset settings for Dynamic Test Limits m_settings.stepTestDuration = 0_s; diff --git a/tools/sysid/src/main/native/cpp/analysis/ArmSim.cpp b/tools/sysid/src/main/native/cpp/analysis/ArmSim.cpp index 7fa8358763..38eec15f1e 100644 --- a/tools/sysid/src/main/native/cpp/analysis/ArmSim.cpp +++ b/tools/sysid/src/main/native/cpp/analysis/ArmSim.cpp @@ -27,13 +27,13 @@ ArmSim::ArmSim(double Ks, double Kv, double Ka, double Kg, double offset, Reset(initialPosition, initialVelocity); } -void ArmSim::Update(units::volt_t voltage, units::second_t dt) { +void ArmSim::Update(wpi::units::volt_t voltage, wpi::units::second_t dt) { // Returns arm acceleration under gravity auto f = [=, this]( const Eigen::Vector& x, const Eigen::Vector& u) -> Eigen::Vector { return Eigen::Vector{ - x(1), (m_A * x.block<1, 1>(1, 0) + m_B * u + m_c * wpi::sgn(x(1)) + + x(1), (m_A * x.block<1, 1>(1, 0) + m_B * u + m_c * wpi::util::sgn(x(1)) + m_d * std::cos(x(0) + m_offset))(0)}; }; @@ -42,7 +42,7 @@ void ArmSim::Update(units::volt_t voltage, units::second_t dt) { // small for ill-conditioned data (e.g., high velocities with sharp spikes in // acceleration). Eigen::Vector u{voltage.value()}; - m_x = frc::RKDP(f, m_x, u, dt, 0.25); + m_x = wpi::math::RKDP(f, m_x, u, dt, 0.25); } double ArmSim::GetPosition() const { @@ -53,10 +53,10 @@ double ArmSim::GetVelocity() const { return m_x(1); } -double ArmSim::GetAcceleration(units::volt_t voltage) const { +double ArmSim::GetAcceleration(wpi::units::volt_t voltage) const { Eigen::Vector u{voltage.value()}; return (m_A * m_x.block<1, 1>(1, 0) + m_B * u + - m_c * wpi::sgn(GetVelocity()) + m_d * std::cos(m_x(0) + m_offset))(0); + m_c * wpi::util::sgn(GetVelocity()) + m_d * std::cos(m_x(0) + m_offset))(0); } void ArmSim::Reset(double position, double velocity) { diff --git a/tools/sysid/src/main/native/cpp/analysis/ElevatorSim.cpp b/tools/sysid/src/main/native/cpp/analysis/ElevatorSim.cpp index 545a05ea2e..f58d7d8fd2 100644 --- a/tools/sysid/src/main/native/cpp/analysis/ElevatorSim.cpp +++ b/tools/sysid/src/main/native/cpp/analysis/ElevatorSim.cpp @@ -20,16 +20,16 @@ ElevatorSim::ElevatorSim(double Ks, double Kv, double Ka, double Kg, Reset(initialPosition, initialVelocity); } -void ElevatorSim::Update(units::volt_t voltage, units::second_t dt) { +void ElevatorSim::Update(wpi::units::volt_t voltage, wpi::units::second_t dt) { Eigen::Vector u{voltage.value()}; // Given dx/dt = Ax + Bu + c sgn(x) + d, // x_k+1 = e^(AT) x_k + A^-1 (e^(AT) - 1) (Bu + c sgn(x) + d) Eigen::Matrix Ad; Eigen::Matrix Bd; - frc::DiscretizeAB<2, 1>(m_A, m_B, dt, &Ad, &Bd); + wpi::math::DiscretizeAB<2, 1>(m_A, m_B, dt, &Ad, &Bd); m_x = Ad * m_x + Bd * u + - Bd * m_B.householderQr().solve(m_c * wpi::sgn(GetVelocity()) + m_d); + Bd * m_B.householderQr().solve(m_c * wpi::util::sgn(GetVelocity()) + m_d); } double ElevatorSim::GetPosition() const { @@ -40,9 +40,9 @@ double ElevatorSim::GetVelocity() const { return m_x(1); } -double ElevatorSim::GetAcceleration(units::volt_t voltage) const { +double ElevatorSim::GetAcceleration(wpi::units::volt_t voltage) const { Eigen::Vector u{voltage.value()}; - return (m_A * m_x + m_B * u + m_c * wpi::sgn(GetVelocity()) + m_d)(1); + return (m_A * m_x + m_B * u + m_c * wpi::util::sgn(GetVelocity()) + m_d)(1); } void ElevatorSim::Reset(double position, double velocity) { diff --git a/tools/sysid/src/main/native/cpp/analysis/FeedbackAnalysis.cpp b/tools/sysid/src/main/native/cpp/analysis/FeedbackAnalysis.cpp index ec1a9f19ca..6dc5edbf4d 100644 --- a/tools/sysid/src/main/native/cpp/analysis/FeedbackAnalysis.cpp +++ b/tools/sysid/src/main/native/cpp/analysis/FeedbackAnalysis.cpp @@ -32,10 +32,10 @@ FeedbackGains sysid::CalculatePositionFeedbackGains( // instabilities in the LQR. if (std::abs(Ka) < 1e-7) { // System has position state and velocity input - frc::LinearSystem<1, 1, 1> system{Matrix1d{0.0}, Matrix1d{1.0}, + wpi::math::LinearSystem<1, 1, 1> system{Matrix1d{0.0}, Matrix1d{1.0}, Matrix1d{1.0}, Matrix1d{0.0}}; - frc::LinearQuadraticRegulator<1, 1> controller{ + wpi::math::LinearQuadraticRegulator<1, 1> controller{ system, {params.qp}, {params.r}, preset.period}; controller.LatencyCompensate(system, preset.period, preset.measurementDelay); @@ -43,16 +43,16 @@ FeedbackGains sysid::CalculatePositionFeedbackGains( return {Kv * controller.K(0, 0) * preset.outputConversionFactor, 0.0}; } - auto system = frc::LinearSystemId::IdentifyPositionSystem( + auto system = wpi::math::LinearSystemId::IdentifyPositionSystem( Kv_t{Kv}, Ka_t{Ka}); - frc::LinearQuadraticRegulator<2, 1> controller{ + wpi::math::LinearQuadraticRegulator<2, 1> controller{ system, {params.qp, params.qv}, {params.r}, preset.period}; controller.LatencyCompensate(system, preset.period, preset.measurementDelay); return {controller.K(0, 0) * preset.outputConversionFactor, controller.K(0, 1) * preset.outputConversionFactor / - (preset.normalized ? 1 : units::second_t{preset.period}.value())}; + (preset.normalized ? 1 : wpi::units::second_t{preset.period}.value())}; } FeedbackGains sysid::CalculateVelocityFeedbackGains( @@ -69,9 +69,9 @@ FeedbackGains sysid::CalculateVelocityFeedbackGains( return {0.0, 0.0}; } - auto system = frc::LinearSystemId::IdentifyVelocitySystem( + auto system = wpi::math::LinearSystemId::IdentifyVelocitySystem( Kv_t{Kv}, Ka_t{Ka}); - frc::LinearQuadraticRegulator<1, 1> controller{ + wpi::math::LinearQuadraticRegulator<1, 1> controller{ system, {params.qv}, {params.r}, preset.period}; controller.LatencyCompensate(system, preset.period, preset.measurementDelay); diff --git a/tools/sysid/src/main/native/cpp/analysis/FilteringUtils.cpp b/tools/sysid/src/main/native/cpp/analysis/FilteringUtils.cpp index c9457689de..c0d73662b2 100644 --- a/tools/sysid/src/main/native/cpp/analysis/FilteringUtils.cpp +++ b/tools/sysid/src/main/native/cpp/analysis/FilteringUtils.cpp @@ -49,7 +49,7 @@ static void CheckSize(const std::vector& data, size_t window, * @return True, if the key corresponds to a raw dataset. */ static bool IsRaw(std::string_view key) { - return wpi::contains(key, "raw") && !wpi::contains(key, "original"); + return wpi::util::contains(key, "raw") && !wpi::util::contains(key, "original"); } /** @@ -60,7 +60,7 @@ static bool IsRaw(std::string_view key) { * @return True, if the key corresponds to a filtered dataset. */ static bool IsFiltered(std::string_view key) { - return !wpi::contains(key, "raw") && !wpi::contains(key, "original"); + return !wpi::util::contains(key, "raw") && !wpi::util::contains(key, "original"); } /** @@ -116,16 +116,16 @@ static void PrepareMechData(std::vector* data, } } -std::tuple +std::tuple sysid::TrimStepVoltageData(std::vector* data, AnalysisManager::Settings* settings, - units::second_t minStepTime, - units::second_t maxStepTime) { + wpi::units::second_t minStepTime, + wpi::units::second_t maxStepTime) { auto voltageBegins = std::find_if(data->begin(), data->end(), [](auto& datum) { return std::abs(datum.voltage) > 0; }); - units::second_t firstTimestamp = voltageBegins->timestamp; + wpi::units::second_t firstTimestamp = voltageBegins->timestamp; double firstPosition = voltageBegins->position; auto motionBegins = std::find_if( @@ -134,7 +134,7 @@ sysid::TrimStepVoltageData(std::vector* data, (settings->velocityThreshold * datum.dt.value()); }); - units::second_t positionDelay; + wpi::units::second_t positionDelay; if (motionBegins != data->end()) { positionDelay = motionBegins->timestamp - firstTimestamp; } else { @@ -146,8 +146,8 @@ sysid::TrimStepVoltageData(std::vector* data, // Since we don't know if its a forward or backwards test here, we use // the sign of each point's velocity to determine how to compare their // accelerations. - return wpi::sgn(a.velocity) * a.acceleration < - wpi::sgn(b.velocity) * b.acceleration; + return wpi::util::sgn(a.velocity) * a.acceleration < + wpi::util::sgn(b.velocity) * b.acceleration; }); // Current limiting can delay onset of the peak acceleration, so we need to @@ -155,11 +155,11 @@ sysid::TrimStepVoltageData(std::vector* data, // because this whole file is tech debt already auto accelBegins = std::find_if( data->begin(), data->end(), [&maxAccel](const auto& measurement) { - return wpi::sgn(measurement.velocity) * measurement.acceleration > - 0.8 * wpi::sgn(maxAccel->velocity) * maxAccel->acceleration; + return wpi::util::sgn(measurement.velocity) * measurement.acceleration > + 0.8 * wpi::util::sgn(maxAccel->velocity) * maxAccel->acceleration; }); - units::second_t velocityDelay; + wpi::units::second_t velocityDelay; if (accelBegins != data->end()) { velocityDelay = accelBegins->timestamp - firstTimestamp; @@ -209,7 +209,7 @@ double sysid::GetNoiseFloor( std::function accessorFunction) { double sum = 0.0; size_t step = window / 2; - auto averageFilter = frc::LinearFilter::MovingAverage(window); + auto averageFilter = wpi::math::LinearFilter::MovingAverage(window); for (size_t i = 0; i < data.size(); i++) { double mean = averageFilter.Calculate(accessorFunction(data[i])); if (i >= step) { @@ -229,8 +229,8 @@ double sysid::GetMaxSpeed( return max; } -units::second_t sysid::GetMeanTimeDelta(const std::vector& data) { - std::vector dts; +wpi::units::second_t sysid::GetMeanTimeDelta(const std::vector& data) { + std::vector dts; for (const auto& pt : data) { if (pt.dt > 0_s && pt.dt < 500_ms) { @@ -241,8 +241,8 @@ units::second_t sysid::GetMeanTimeDelta(const std::vector& data) { return std::accumulate(dts.begin(), dts.end(), 0_s) / dts.size(); } -units::second_t sysid::GetMeanTimeDelta(const Storage& data) { - std::vector dts; +wpi::units::second_t sysid::GetMeanTimeDelta(const Storage& data) { + std::vector dts; for (const auto& pt : data.slowForward) { if (pt.dt > 0_s && pt.dt < 500_ms) { @@ -274,7 +274,7 @@ units::second_t sysid::GetMeanTimeDelta(const Storage& data) { void sysid::ApplyMedianFilter(std::vector* data, int window) { CheckSize(*data, window, "Median Filter"); - frc::MedianFilter medianFilter(window); + wpi::math::MedianFilter medianFilter(window); // Load the median filter with the first value for accurate initial behavior for (int i = 0; i < window; i++) { @@ -319,14 +319,14 @@ static std::string RemoveStr(std::string_view str, std::string_view removeStr) { * * @return The maximum duration of the Dynamic Tests */ -static units::second_t GetMaxStepTime( - wpi::StringMap>& data) { +static wpi::units::second_t GetMaxStepTime( + wpi::util::StringMap>& data) { auto maxStepTime = 0_s; for (auto& it : data) { auto& key = it.first; auto& dataset = it.second; - if (IsRaw(key) && wpi::contains(key, "dynamic")) { + if (IsRaw(key) && wpi::util::contains(key, "dynamic")) { if (!dataset.empty()) { auto duration = dataset.back().timestamp - dataset.front().timestamp; if (duration > maxStepTime) { @@ -339,11 +339,11 @@ static units::second_t GetMaxStepTime( } void sysid::InitialTrimAndFilter( - wpi::StringMap>* data, + wpi::util::StringMap>* data, AnalysisManager::Settings* settings, - std::vector& positionDelays, - std::vector& velocityDelays, units::second_t& minStepTime, - units::second_t& maxStepTime, std::string_view unit) { + std::vector& positionDelays, + std::vector& velocityDelays, wpi::units::second_t& minStepTime, + wpi::units::second_t& maxStepTime, std::string_view unit) { auto& preparedData = *data; // Find the maximum Step Test Duration of the dynamic tests @@ -354,7 +354,7 @@ void sysid::InitialTrimAndFilter( for (auto& it : preparedData) { auto& key = it.first; auto& dataset = it.second; - if (wpi::contains(key, "quasistatic")) { + if (wpi::util::contains(key, "quasistatic")) { settings->velocityThreshold = std::min(settings->velocityThreshold, GetNoiseFloor(dataset, kNoiseMeanWindow, @@ -369,7 +369,7 @@ void sysid::InitialTrimAndFilter( // Trim quasistatic test data to remove all points where voltage is zero or // velocity < velocity threshold. - if (wpi::contains(key, "quasistatic")) { + if (wpi::util::contains(key, "quasistatic")) { dataset.erase(std::remove_if(dataset.begin(), dataset.end(), [&](const auto& pt) { return std::abs(pt.voltage) <= 0 || @@ -393,7 +393,7 @@ void sysid::InitialTrimAndFilter( PrepareMechData(&dataset, unit); // Trims filtered Dynamic Test Data - if (IsFiltered(key) && wpi::contains(key, "dynamic")) { + if (IsFiltered(key) && wpi::util::contains(key, "dynamic")) { // Get the filtered dataset name auto filteredKey = RemoveStr(key, "raw-"); @@ -420,7 +420,7 @@ void sysid::InitialTrimAndFilter( } } -void sysid::AccelFilter(wpi::StringMap>* data) { +void sysid::AccelFilter(wpi::util::StringMap>* data) { auto& preparedData = *data; // Remove points with acceleration = 0 diff --git a/tools/sysid/src/main/native/cpp/analysis/SimpleMotorSim.cpp b/tools/sysid/src/main/native/cpp/analysis/SimpleMotorSim.cpp index 49c4411fe7..3265cea5cc 100644 --- a/tools/sysid/src/main/native/cpp/analysis/SimpleMotorSim.cpp +++ b/tools/sysid/src/main/native/cpp/analysis/SimpleMotorSim.cpp @@ -17,16 +17,16 @@ SimpleMotorSim::SimpleMotorSim(double Ks, double Kv, double Ka, Reset(initialPosition, initialVelocity); } -void SimpleMotorSim::Update(units::volt_t voltage, units::second_t dt) { +void SimpleMotorSim::Update(wpi::units::volt_t voltage, wpi::units::second_t dt) { Eigen::Vector u{voltage.value()}; // Given dx/dt = Ax + Bu + c sgn(x), // x_k+1 = e^(AT) x_k + A^-1 (e^(AT) - 1) (Bu + c sgn(x)) Eigen::Matrix Ad; Eigen::Matrix Bd; - frc::DiscretizeAB<2, 1>(m_A, m_B, dt, &Ad, &Bd); + wpi::math::DiscretizeAB<2, 1>(m_A, m_B, dt, &Ad, &Bd); m_x = Ad * m_x + Bd * u + - Bd * m_B.householderQr().solve(m_c * wpi::sgn(GetVelocity())); + Bd * m_B.householderQr().solve(m_c * wpi::util::sgn(GetVelocity())); } double SimpleMotorSim::GetPosition() const { @@ -37,9 +37,9 @@ double SimpleMotorSim::GetVelocity() const { return m_x(1); } -double SimpleMotorSim::GetAcceleration(units::volt_t voltage) const { +double SimpleMotorSim::GetAcceleration(wpi::units::volt_t voltage) const { Eigen::Vector u{voltage.value()}; - return (m_A * m_x + m_B * u + m_c * wpi::sgn(GetVelocity()))(1); + return (m_A * m_x + m_B * u + m_c * wpi::util::sgn(GetVelocity()))(1); } void SimpleMotorSim::Reset(double position, double velocity) { diff --git a/tools/sysid/src/main/native/cpp/view/Analyzer.cpp b/tools/sysid/src/main/native/cpp/view/Analyzer.cpp index b0542a2e28..cc39f90c15 100644 --- a/tools/sysid/src/main/native/cpp/view/Analyzer.cpp +++ b/tools/sysid/src/main/native/cpp/view/Analyzer.cpp @@ -29,9 +29,9 @@ using namespace sysid; -Analyzer::Analyzer(glass::Storage& storage, wpi::Logger& logger) +Analyzer::Analyzer(wpi::glass::Storage& storage, wpi::util::Logger& logger) : m_logger(logger) { - // Fill the StringMap with preset values. + // Fill the wpi::util::StringMap with preset values. m_presets["Default"] = presets::kDefault; m_presets["WPILib"] = presets::kWPILib; m_presets["CTRE Phoenix 5"] = presets::kCTREv5; @@ -55,8 +55,8 @@ void Analyzer::UpdateFeedforwardGains() { m_settings.preset.measurementDelay = m_settings.type == FeedbackControllerLoopType::kPosition // Clamp feedback measurement delay to ≥ 0 - ? units::math::max(0_s, m_manager->GetPositionDelay()) - : units::math::max(0_s, m_manager->GetVelocityDelay()); + ? wpi::units::math::max(0_s, m_manager->GetPositionDelay()) + : wpi::units::math::max(0_s, m_manager->GetVelocityDelay()); PrepareGraphs(); } catch (const sysid::InvalidDataError& e) { m_state = AnalyzerState::kGeneralDataError; @@ -70,7 +70,7 @@ void Analyzer::UpdateFeedforwardGains() { } catch (const AnalysisManager::FileReadingError& e) { m_state = AnalyzerState::kFileError; HandleError(e.what()); - } catch (const wpi::json::exception& e) { + } catch (const wpi::util::json::exception& e) { m_state = AnalyzerState::kFileError; HandleError(e.what()); } catch (const std::exception& e) { @@ -86,7 +86,7 @@ void Analyzer::UpdateFeedbackGains() { const auto& Ka = m_feedforwardGains.Ka; if (Kv.isValidGain && Ka.isValidGain) { const auto& fb = m_manager->CalculateFeedback(Kv, Ka); - m_timescale = units::second_t{Ka.gain / Kv.gain}; + m_timescale = wpi::units::second_t{Ka.gain / Kv.gain}; m_timescaleValid = true; m_Kp = fb.Kp; m_Kd = fb.Kd; @@ -298,7 +298,7 @@ void Analyzer::PrepareData() { } catch (const AnalysisManager::FileReadingError& e) { m_state = AnalyzerState::kFileError; HandleError(e.what()); - } catch (const wpi::json::exception& e) { + } catch (const wpi::util::json::exception& e) { m_state = AnalyzerState::kFileError; HandleError(e.what()); } catch (const std::exception& e) { @@ -475,7 +475,7 @@ void Analyzer::DisplayFeedforwardParameters(float beginX, float beginY) { if (ImGui::SliderFloat("Test Duration", &m_stepTestDuration, m_manager->GetMinStepTime().value(), m_manager->GetMaxStepTime().value(), "%.2f")) { - m_settings.stepTestDuration = units::second_t{m_stepTestDuration}; + m_settings.stepTestDuration = wpi::units::second_t{m_stepTestDuration}; PrepareData(); } } @@ -612,9 +612,9 @@ void Analyzer::DisplayFeedbackGains() { sysid::CreateTooltip( "Gain presets represent how feedback gains are calculated for your " "specific feedback controller:\n\n" - "Default, WPILib (2020-): For use with the new WPILib PIDController " + "Default, WPILib (2020-): For use with the new WPILib wpi::math::PIDController " "class.\n" - "WPILib (Pre-2020): For use with the old WPILib PIDController class.\n" + "WPILib (Pre-2020): For use with the old WPILib wpi::math::PIDController class.\n" "CTRE: For use with CTRE units. These are the default units that ship " "with CTRE motor controllers.\n" "REV (Brushless): For use with NEO and NEO 550 motors on a SPARK MAX.\n" diff --git a/tools/sysid/src/main/native/cpp/view/AnalyzerPlot.cpp b/tools/sysid/src/main/native/cpp/view/AnalyzerPlot.cpp index d9a370adbe..1f5adcef6b 100644 --- a/tools/sysid/src/main/native/cpp/view/AnalyzerPlot.cpp +++ b/tools/sysid/src/main/native/cpp/view/AnalyzerPlot.cpp @@ -30,7 +30,7 @@ static ImPlotPoint Getter(int idx, void* data) { template static std::vector> PopulateTimeDomainSim( const std::vector& data, - const std::array& startTimes, size_t step, Model model, + const std::array& startTimes, size_t step, Model model, double* simSquaredErrorSum, double* squaredVariationSum, int* timeSeriesPoints) { // Create the vector of ImPlotPoints that will contain our simulated data. @@ -42,7 +42,7 @@ static std::vector> PopulateTimeDomainSim( tmp.emplace_back(startTime.value(), data[0].velocity); model.Reset(data[0].position, data[0].velocity); - units::second_t t = 0_s; + wpi::units::second_t t = 0_s; for (size_t i = 1; i < data.size(); ++i) { const auto& now = data[i]; @@ -60,7 +60,7 @@ static std::vector> PopulateTimeDomainSim( continue; } - model.Update(units::volt_t{pre.voltage}, now.timestamp - pre.timestamp); + model.Update(wpi::units::volt_t{pre.voltage}, now.timestamp - pre.timestamp); tmp.emplace_back((startTime + t).value(), model.GetVelocity()); *simSquaredErrorSum += std::pow(now.velocity - model.GetVelocity(), 2); *squaredVariationSum += std::pow(now.velocity, 2); @@ -71,7 +71,7 @@ static std::vector> PopulateTimeDomainSim( return pts; } -AnalyzerPlot::AnalyzerPlot(wpi::Logger& logger) : m_logger(logger) {} +AnalyzerPlot::AnalyzerPlot(wpi::util::Logger& logger) : m_logger(logger) {} void AnalyzerPlot::SetRawTimeData(const std::vector& rawSlow, const std::vector& rawFast, @@ -131,7 +131,7 @@ void AnalyzerPlot::SetRawData(const Storage& data, std::string_view unit, void AnalyzerPlot::SetData(const Storage& rawData, const Storage& filteredData, std::string_view unit, const AnalysisManager::FeedforwardGains& ffGains, - const std::array& startTimes, + const std::array& startTimes, AnalysisType type, std::atomic& abort) { double simSquaredErrorSum = 0; double squaredVariationSum = 0; @@ -163,7 +163,7 @@ void AnalyzerPlot::SetData(const Storage& rawData, const Storage& filteredData, auto slowStep = std::ceil(slow.size() * 1.0 / kMaxSize * 4); auto fastStep = std::ceil(fast.size() * 1.0 / kMaxSize * 4); - units::second_t dtMean = GetMeanTimeDelta(filteredData); + wpi::units::second_t dtMean = GetMeanTimeDelta(filteredData); // Velocity-vs-time plots { @@ -192,7 +192,7 @@ void AnalyzerPlot::SetData(const Storage& rawData, const Storage& filteredData, slow[i].timestamp) == startTimes.end()) { m_timestepData.data.emplace_back( (slow[i].timestamp).value(), - units::millisecond_t{slow[i].dt}.value()); + wpi::units::millisecond_t{slow[i].dt}.value()); } } } @@ -217,7 +217,7 @@ void AnalyzerPlot::SetData(const Storage& rawData, const Storage& filteredData, fast[i].timestamp) == startTimes.end()) { m_timestepData.data.emplace_back( (fast[i].timestamp).value(), - units::millisecond_t{fast[i].dt}.value()); + wpi::units::millisecond_t{fast[i].dt}.value()); } } } @@ -334,7 +334,7 @@ void AnalyzerPlot::SetData(const Storage& rawData, const Storage& filteredData, startTimes.end()) { m_timestepData.data.emplace_back( (slow[i].timestamp).value(), - units::millisecond_t{slow[i].dt}.value()); + wpi::units::millisecond_t{slow[i].dt}.value()); } } } @@ -351,19 +351,19 @@ void AnalyzerPlot::SetData(const Storage& rawData, const Storage& filteredData, startTimes.end()) { m_timestepData.data.emplace_back( (fast[i].timestamp).value(), - units::millisecond_t{fast[i].dt}.value()); + wpi::units::millisecond_t{fast[i].dt}.value()); } } } auto minTime = - units::math::min(slow.front().timestamp, fast.front().timestamp); + wpi::units::math::min(slow.front().timestamp, fast.front().timestamp); m_timestepData.fitLine[0] = - ImPlotPoint{minTime.value(), units::millisecond_t{dtMean}.value()}; + ImPlotPoint{minTime.value(), wpi::units::millisecond_t{dtMean}.value()}; - auto maxTime = units::math::max(slow.back().timestamp, fast.back().timestamp); + auto maxTime = wpi::units::math::max(slow.back().timestamp, fast.back().timestamp); m_timestepData.fitLine[1] = - ImPlotPoint{maxTime.value(), units::millisecond_t{dtMean}.value()}; + ImPlotPoint{maxTime.value(), wpi::units::millisecond_t{dtMean}.value()}; // RMSE = std::sqrt(sum((x_i - x^_i)^2) / N) where sum represents the sum of // all time series points, x_i represents the velocity at a timestep, x^_i diff --git a/tools/sysid/src/main/native/cpp/view/DataSelector.cpp b/tools/sysid/src/main/native/cpp/view/DataSelector.cpp index d3f52651ad..c422bf26bb 100644 --- a/tools/sysid/src/main/native/cpp/view/DataSelector.cpp +++ b/tools/sysid/src/main/native/cpp/view/DataSelector.cpp @@ -105,7 +105,7 @@ void DataSelector::Display() { continue; } for (auto it2 = it->second.begin(); it2 != it->second.end();) { - auto direction = wpi::rsplit(it2->first, '-').second; + auto direction = wpi::util::rsplit(it2->first, '-').second; if (direction != "forward" && direction != "reverse") { WPI_WARNING(m_logger, "Unrecognized direction {}, removing", direction); @@ -220,7 +220,7 @@ DataSelector::Tests DataSelector::LoadTests( continue; } - auto [testName, direction] = wpi::rsplit(testState, '-'); + auto [testName, direction] = wpi::util::rsplit(testState, '-'); auto testIt = tests.find(testName); if (testIt == tests.end()) { testIt = tests.emplace(std::string{testName}, State{}).first; @@ -252,7 +252,7 @@ static void AddSamples(std::vector>& samples, [](const auto& datapoint, double val) { return datapoint.first < val; }); for (auto it = begin; it != end; ++it) { - samples.emplace_back(units::second_t{it->first * 1.0e-6}, T{it->second}); + samples.emplace_back(wpi::units::second_t{it->first * 1.0e-6}, T{it->second}); } } diff --git a/tools/sysid/src/main/native/cpp/view/LogLoader.cpp b/tools/sysid/src/main/native/cpp/view/LogLoader.cpp index 12df0cf9ff..bbe3f35b09 100644 --- a/tools/sysid/src/main/native/cpp/view/LogLoader.cpp +++ b/tools/sysid/src/main/native/cpp/view/LogLoader.cpp @@ -24,7 +24,7 @@ using namespace sysid; -LogLoader::LogLoader(glass::Storage& storage, wpi::Logger& logger) {} +LogLoader::LogLoader(wpi::glass::Storage& storage, wpi::util::Logger& logger) {} LogLoader::~LogLoader() = default; @@ -40,7 +40,7 @@ void LogLoader::Display() { if (!m_opener->result().empty()) { m_filename = m_opener->result()[0]; - auto fileBuffer = wpi::MemoryBuffer::GetFile(m_filename); + auto fileBuffer = wpi::util::MemoryBuffer::GetFile(m_filename); if (!fileBuffer) { ImGui::OpenPopup("Error"); m_error = fmt::format("Could not open file: {}", @@ -108,7 +108,7 @@ void LogLoader::Display() { void LogLoader::RebuildEntryTree() { m_entryTree.clear(); - wpi::SmallVector parts; + wpi::util::SmallVector parts; m_reader->ForEachEntryName([&](const wpi::log::DataLogReaderEntry& entry) { // only show double/float/string entries (TODO: support struct/protobuf) if (entry.type != "double" && entry.type != "float" && @@ -117,19 +117,19 @@ void LogLoader::RebuildEntryTree() { } // filter on name - if (!m_filter.empty() && !wpi::contains_lower(entry.name, m_filter)) { + if (!m_filter.empty() && !wpi::util::contains_lower(entry.name, m_filter)) { return; } parts.clear(); // split on first : if one is present - auto [prefix, mainpart] = wpi::split(entry.name, ':'); - if (mainpart.empty() || wpi::contains(prefix, '/')) { + auto [prefix, mainpart] = wpi::util::split(entry.name, ':'); + if (mainpart.empty() || wpi::util::contains(prefix, '/')) { mainpart = entry.name; } else { parts.emplace_back(prefix); } - wpi::split(mainpart, '/', -1, false, + wpi::util::split(mainpart, '/', -1, false, [&](auto part) { parts.emplace_back(part); }); // ignore a raw "/" key @@ -139,7 +139,7 @@ void LogLoader::RebuildEntryTree() { // get to leaf auto nodes = &m_entryTree; - for (auto part : wpi::drop_back(std::span{parts.begin(), parts.end()})) { + for (auto part : wpi::util::drop_back(std::span{parts.begin(), parts.end()})) { auto it = std::find_if(nodes->begin(), nodes->end(), [&](const auto& node) { return node.name == part; }); diff --git a/tools/sysid/src/main/native/include/wpi/sysid/analysis/AnalysisManager.hpp b/tools/sysid/src/main/native/include/wpi/sysid/analysis/AnalysisManager.hpp index c57de76efc..dabfc624d9 100644 --- a/tools/sysid/src/main/native/include/wpi/sysid/analysis/AnalysisManager.hpp +++ b/tools/sysid/src/main/native/include/wpi/sysid/analysis/AnalysisManager.hpp @@ -70,7 +70,7 @@ class AnalysisManager { * The duration of the dynamic test that should be considered. A value of * zero indicates it needs to be set to the default. */ - units::second_t stepTestDuration = 0_s; + wpi::units::second_t stepTestDuration = 0_s; }; struct FeedforwardGain { @@ -189,7 +189,7 @@ class AnalysisManager { * @param settings The settings for this instance of the analysis manager. * @param logger The logger instance to use for log data. */ - AnalysisManager(Settings& settings, wpi::Logger& logger); + AnalysisManager(Settings& settings, wpi::util::Logger& logger); /** * Constructs an instance of the analysis manager with the given path (to the @@ -199,7 +199,7 @@ class AnalysisManager { * @param settings The settings for this instance of the analysis manager. * @param logger The logger instance to use for log data. */ - AnalysisManager(TestData data, Settings& settings, wpi::Logger& logger); + AnalysisManager(TestData data, Settings& settings, wpi::util::Logger& logger); /** * Prepares data from the JSON and stores the output in Storage member @@ -281,7 +281,7 @@ class AnalysisManager { * * @return The minimum step test duration. */ - units::second_t GetMinStepTime() const { return m_minStepTime; } + wpi::units::second_t GetMinStepTime() const { return m_minStepTime; } /** * Returns the maximum duration of the Step Voltage Test of the currently @@ -289,7 +289,7 @@ class AnalysisManager { * * @return Maximum step test duration */ - units::second_t GetMaxStepTime() const { return m_maxStepTime; } + wpi::units::second_t GetMaxStepTime() const { return m_maxStepTime; } /** * Returns the estimated time delay of the measured position, including @@ -297,7 +297,7 @@ class AnalysisManager { * * @return Position delay in milliseconds */ - units::millisecond_t GetPositionDelay() const { + wpi::units::millisecond_t GetPositionDelay() const { return std::accumulate(m_positionDelays.begin(), m_positionDelays.end(), 0_s) / m_positionDelays.size(); @@ -309,7 +309,7 @@ class AnalysisManager { * * @return Velocity delay in milliseconds */ - units::millisecond_t GetVelocityDelay() const { + wpi::units::millisecond_t GetVelocityDelay() const { return std::accumulate(m_velocityDelays.begin(), m_velocityDelays.end(), 0_s) / m_positionDelays.size(); @@ -320,30 +320,30 @@ class AnalysisManager { * * @return The start times for each test */ - const std::array& GetStartTimes() const { + const std::array& GetStartTimes() const { return m_startTimes; } bool HasData() const { return !m_originalDataset.empty(); } private: - wpi::Logger& m_logger; + wpi::util::Logger& m_logger; Storage m_originalDataset; Storage m_rawDataset; Storage m_filteredDataset; // Stores the various start times of the different tests. - std::array m_startTimes; + std::array m_startTimes; // The settings for this instance. This contains pointers to the feedback // controller preset, LQR parameters, acceleration window size, etc. Settings& m_settings; - units::second_t m_minStepTime{0}; - units::second_t m_maxStepTime{std::numeric_limits::infinity()}; - std::vector m_positionDelays; - std::vector m_velocityDelays; + wpi::units::second_t m_minStepTime{0}; + wpi::units::second_t m_maxStepTime{std::numeric_limits::infinity()}; + std::vector m_positionDelays; + std::vector m_velocityDelays; void PrepareGeneralData(); }; diff --git a/tools/sysid/src/main/native/include/wpi/sysid/analysis/ArmSim.hpp b/tools/sysid/src/main/native/include/wpi/sysid/analysis/ArmSim.hpp index 51a615ec6c..e3f7e38834 100644 --- a/tools/sysid/src/main/native/include/wpi/sysid/analysis/ArmSim.hpp +++ b/tools/sysid/src/main/native/include/wpi/sysid/analysis/ArmSim.hpp @@ -36,7 +36,7 @@ class ArmSim { * @param voltage Voltage to apply over the timestep. * @param dt Sample period. */ - void Update(units::volt_t voltage, units::second_t dt); + void Update(wpi::units::volt_t voltage, wpi::units::second_t dt); /** * Returns the position. @@ -58,7 +58,7 @@ class ArmSim { * @param voltage The voltage that is being applied to the mechanism / input * @return The acceleration given the state and input */ - double GetAcceleration(units::volt_t voltage) const; + double GetAcceleration(wpi::units::volt_t voltage) const; /** * Resets model position and velocity. diff --git a/tools/sysid/src/main/native/include/wpi/sysid/analysis/ElevatorSim.hpp b/tools/sysid/src/main/native/include/wpi/sysid/analysis/ElevatorSim.hpp index 8d82928d66..622e88d43a 100644 --- a/tools/sysid/src/main/native/include/wpi/sysid/analysis/ElevatorSim.hpp +++ b/tools/sysid/src/main/native/include/wpi/sysid/analysis/ElevatorSim.hpp @@ -34,7 +34,7 @@ class ElevatorSim { * @param voltage Voltage to apply over the timestep. * @param dt Sample period. */ - void Update(units::volt_t voltage, units::second_t dt); + void Update(wpi::units::volt_t voltage, wpi::units::second_t dt); /** * Returns the position. @@ -56,7 +56,7 @@ class ElevatorSim { * @param voltage The voltage that is being applied to the mechanism / input * @return The acceleration given the state and input */ - double GetAcceleration(units::volt_t voltage) const; + double GetAcceleration(wpi::units::volt_t voltage) const; /** * Resets model position and velocity. diff --git a/tools/sysid/src/main/native/include/wpi/sysid/analysis/FeedbackControllerPreset.hpp b/tools/sysid/src/main/native/include/wpi/sysid/analysis/FeedbackControllerPreset.hpp index 440d5e3433..04dc7fca09 100644 --- a/tools/sysid/src/main/native/include/wpi/sysid/analysis/FeedbackControllerPreset.hpp +++ b/tools/sysid/src/main/native/include/wpi/sysid/analysis/FeedbackControllerPreset.hpp @@ -29,7 +29,7 @@ struct FeedbackControllerPreset { /** * The period at which the controller runs. */ - units::millisecond_t period; + wpi::units::millisecond_t period; /** * Whether the controller gains are time-normalized. @@ -39,7 +39,7 @@ struct FeedbackControllerPreset { /** * The measurement delay in the encoder measurements. */ - units::millisecond_t measurementDelay; + wpi::units::millisecond_t measurementDelay; /** * Checks equality between two feedback controller presets. diff --git a/tools/sysid/src/main/native/include/wpi/sysid/analysis/FilteringUtils.hpp b/tools/sysid/src/main/native/include/wpi/sysid/analysis/FilteringUtils.hpp index 847d824d4d..a3ba5fa728 100644 --- a/tools/sysid/src/main/native/include/wpi/sysid/analysis/FilteringUtils.hpp +++ b/tools/sysid/src/main/native/include/wpi/sysid/analysis/FilteringUtils.hpp @@ -145,10 +145,10 @@ void ApplyMedianFilter(std::vector* data, int window); * @param maxStepTime The maximum step test duration. * @return The updated minimum step test duration. */ -std::tuple +std::tuple TrimStepVoltageData(std::vector* data, AnalysisManager::Settings* settings, - units::second_t minStepTime, units::second_t maxStepTime); + wpi::units::second_t minStepTime, wpi::units::second_t maxStepTime); /** * Compute the mean time delta of the given data. @@ -156,7 +156,7 @@ TrimStepVoltageData(std::vector* data, * @param data A reference to all of the collected PreparedData * @return The mean time delta for all the data points */ -units::second_t GetMeanTimeDelta(const std::vector& data); +wpi::units::second_t GetMeanTimeDelta(const std::vector& data); /** * Compute the mean time delta of the given data. @@ -164,7 +164,7 @@ units::second_t GetMeanTimeDelta(const std::vector& data); * @param data A reference to all of the collected PreparedData * @return The mean time delta for all the data points */ -units::second_t GetMeanTimeDelta(const Storage& data); +wpi::units::second_t GetMeanTimeDelta(const Storage& data); /** * Creates a central finite difference filter that computes the nth @@ -187,16 +187,16 @@ units::second_t GetMeanTimeDelta(const Storage& data); * @param period The period in seconds between samples taken by the user. */ template -frc::LinearFilter CentralFiniteDifference(units::second_t period) { +wpi::math::LinearFilter CentralFiniteDifference(wpi::units::second_t period) { static_assert(Samples % 2 != 0, "Number of samples must be odd."); // Generate stencil points from -(samples - 1)/2 to (samples - 1)/2 - wpi::array stencil{wpi::empty_array}; + wpi::util::array stencil{wpi::util::empty_array}; for (int i = 0; i < Samples; ++i) { stencil[i] = -(Samples - 1) / 2 + i; } - return frc::LinearFilter::FiniteDifference( + return wpi::math::LinearFilter::FiniteDifference( stencil, period); } @@ -219,12 +219,12 @@ frc::LinearFilter CentralFiniteDifference(units::second_t period) { * @param unit The angular unit that the arm test is in (only for calculating * cosine data) */ -void InitialTrimAndFilter(wpi::StringMap>* data, +void InitialTrimAndFilter(wpi::util::StringMap>* data, AnalysisManager::Settings* settings, - std::vector& positionDelays, - std::vector& velocityDelays, - units::second_t& minStepTime, - units::second_t& maxStepTime, + std::vector& positionDelays, + std::vector& velocityDelays, + wpi::units::second_t& minStepTime, + wpi::units::second_t& maxStepTime, std::string_view unit = ""); /** @@ -232,6 +232,6 @@ void InitialTrimAndFilter(wpi::StringMap>* data, * * @param data A pointer to a PreparedData vector */ -void AccelFilter(wpi::StringMap>* data); +void AccelFilter(wpi::util::StringMap>* data); } // namespace sysid diff --git a/tools/sysid/src/main/native/include/wpi/sysid/analysis/SimpleMotorSim.hpp b/tools/sysid/src/main/native/include/wpi/sysid/analysis/SimpleMotorSim.hpp index d78f66bf08..ff749b8743 100644 --- a/tools/sysid/src/main/native/include/wpi/sysid/analysis/SimpleMotorSim.hpp +++ b/tools/sysid/src/main/native/include/wpi/sysid/analysis/SimpleMotorSim.hpp @@ -34,7 +34,7 @@ class SimpleMotorSim { * @param voltage Voltage to apply over the timestep. * @param dt Sample period. */ - void Update(units::volt_t voltage, units::second_t dt); + void Update(wpi::units::volt_t voltage, wpi::units::second_t dt); /** * Returns the position. @@ -56,7 +56,7 @@ class SimpleMotorSim { * @param voltage The voltage that is being applied to the mechanism / input * @return The acceleration given the state and input */ - double GetAcceleration(units::volt_t voltage) const; + double GetAcceleration(wpi::units::volt_t voltage) const; /** * Resets model position and velocity. diff --git a/tools/sysid/src/main/native/include/wpi/sysid/analysis/Storage.hpp b/tools/sysid/src/main/native/include/wpi/sysid/analysis/Storage.hpp index 4ce6cde226..ae17192ecd 100644 --- a/tools/sysid/src/main/native/include/wpi/sysid/analysis/Storage.hpp +++ b/tools/sysid/src/main/native/include/wpi/sysid/analysis/Storage.hpp @@ -22,14 +22,14 @@ struct MotorData { // Timestamps are not necessarily aligned! struct Run { template - requires std::is_arithmetic_v || units::traits::is_unit_t_v + requires std::is_arithmetic_v || wpi::units::traits::is_unit_t_v struct Sample { - Sample(units::second_t time, T measurement) + Sample(wpi::units::second_t time, T measurement) : time{time}, measurement{measurement} {} - units::second_t time; + wpi::units::second_t time; T measurement; }; - std::vector> voltage; + std::vector> voltage; std::vector> position; std::vector> velocity; }; @@ -40,7 +40,7 @@ struct MotorData { struct TestData { std::string distanceUnit; AnalysisType mechanismType; - wpi::StringMap motorData; + wpi::util::StringMap motorData; }; /** @@ -51,7 +51,7 @@ struct PreparedData { /** * The timestamp of the data point. */ - units::second_t timestamp; + wpi::units::second_t timestamp; /** * The voltage of the data point. @@ -71,7 +71,7 @@ struct PreparedData { /** * The difference in timestamps between this point and the next point. */ - units::second_t dt = 0_s; + wpi::units::second_t dt = 0_s; /** * The acceleration of the data point diff --git a/tools/sysid/src/main/native/include/wpi/sysid/analysis/TrackwidthAnalysis.hpp b/tools/sysid/src/main/native/include/wpi/sysid/analysis/TrackwidthAnalysis.hpp index 219758d36e..ad8454f707 100644 --- a/tools/sysid/src/main/native/include/wpi/sysid/analysis/TrackwidthAnalysis.hpp +++ b/tools/sysid/src/main/native/include/wpi/sysid/analysis/TrackwidthAnalysis.hpp @@ -19,7 +19,7 @@ namespace sysid { * @param accum The accumulated gyro angle. */ constexpr double CalculateTrackwidth(double l, double r, - units::radian_t accum) { + wpi::units::radian_t accum) { // The below comes from solving ω = (vr − vl) / 2r for 2r. return (gcem::abs(r) + gcem::abs(l)) / gcem::abs(accum.value()); } diff --git a/tools/sysid/src/main/native/include/wpi/sysid/view/Analyzer.hpp b/tools/sysid/src/main/native/include/wpi/sysid/view/Analyzer.hpp index d218e48d6e..3f7676ed87 100644 --- a/tools/sysid/src/main/native/include/wpi/sysid/view/Analyzer.hpp +++ b/tools/sysid/src/main/native/include/wpi/sysid/view/Analyzer.hpp @@ -25,7 +25,7 @@ struct ImPlotPoint; -namespace glass { +namespace wpi::glass { class Storage; } // namespace glass @@ -35,7 +35,7 @@ namespace sysid { * load their data, visualize the data, adjust certain variables, and then view * the calculated gains. */ -class Analyzer : public glass::View { +class Analyzer : public wpi::glass::View { public: TestData m_data; /** @@ -78,7 +78,7 @@ class Analyzer : public glass::View { * @param storage Glass Storage * @param logger The program logger */ - Analyzer(glass::Storage& storage, wpi::Logger& logger); + Analyzer(wpi::glass::Storage& storage, wpi::util::Logger& logger); /** * Displays the analyzer widget @@ -212,7 +212,7 @@ class Analyzer : public glass::View { // Everything related to feedback controller calculations. AnalysisManager::Settings m_settings; - wpi::StringMap m_presets; + wpi::util::StringMap m_presets; int m_selectedLoopType = 1; int m_selectedPreset = 0; @@ -223,7 +223,7 @@ class Analyzer : public glass::View { double m_accelRMSE; double m_Kp; double m_Kd; - units::millisecond_t m_timescale; + wpi::units::millisecond_t m_timescale; bool m_timescaleValid = false; // Units @@ -235,7 +235,7 @@ class Analyzer : public glass::View { float m_stepTestDuration = 0; // Logger - wpi::Logger& m_logger; + wpi::util::Logger& m_logger; // Plot AnalyzerPlot m_plot{m_logger}; diff --git a/tools/sysid/src/main/native/include/wpi/sysid/view/AnalyzerPlot.hpp b/tools/sysid/src/main/native/include/wpi/sysid/view/AnalyzerPlot.hpp index 396bedcf63..51a51cbc92 100644 --- a/tools/sysid/src/main/native/include/wpi/sysid/view/AnalyzerPlot.hpp +++ b/tools/sysid/src/main/native/include/wpi/sysid/view/AnalyzerPlot.hpp @@ -37,7 +37,7 @@ class AnalyzerPlot { * * @param logger The program logger */ - explicit AnalyzerPlot(wpi::Logger& logger); + explicit AnalyzerPlot(wpi::util::Logger& logger); /** * Sets the data to be displayed on the plots. @@ -55,7 +55,7 @@ class AnalyzerPlot { void SetData(const Storage& rawData, const Storage& filteredData, std::string_view unit, const AnalysisManager::FeedforwardGains& ff, - const std::array& startTimes, + const std::array& startTimes, AnalysisType type, std::atomic& abort); /** @@ -189,10 +189,10 @@ class AnalyzerPlot { std::string m_velPortionAccelLabel; // Thread safety - wpi::spinlock m_mutex; + wpi::util::spinlock m_mutex; // Logger - wpi::Logger& m_logger; + wpi::util::Logger& m_logger; FilteredDataVsTimePlot m_quasistaticData; FilteredDataVsTimePlot m_dynamicData; diff --git a/tools/sysid/src/main/native/include/wpi/sysid/view/DataSelector.hpp b/tools/sysid/src/main/native/include/wpi/sysid/view/DataSelector.hpp index 0059675462..6f8f39d984 100644 --- a/tools/sysid/src/main/native/include/wpi/sysid/view/DataSelector.hpp +++ b/tools/sysid/src/main/native/include/wpi/sysid/view/DataSelector.hpp @@ -17,7 +17,7 @@ #include "wpi/sysid/analysis/Storage.hpp" #include "wpi/util/StringMap.hpp" -namespace glass { +namespace wpi::glass { class Storage; } // namespace glass @@ -25,21 +25,21 @@ namespace wpi { namespace log { class DataLogReaderEntry; } // namespace log -class Logger; +class wpi::util::Logger; } // namespace wpi namespace sysid { /** * Helps with loading datalog files. */ -class DataSelector : public glass::View { +class DataSelector : public wpi::glass::View { public: /** * Creates a data selector widget * * @param logger The program logger */ - explicit DataSelector(glass::Storage& storage, wpi::Logger& logger) + explicit DataSelector(wpi::glass::Storage& storage, wpi::util::Logger& logger) : m_logger{logger} {} /** @@ -60,7 +60,7 @@ class DataSelector : public glass::View { std::vector m_missingTests; private: - wpi::Logger& m_logger; + wpi::util::Logger& m_logger; using Runs = std::vector>; using State = std::map>; // full name using Tests = std::map>; // e.g. "dynamic" diff --git a/tools/sysid/src/main/native/include/wpi/sysid/view/LogLoader.hpp b/tools/sysid/src/main/native/include/wpi/sysid/view/LogLoader.hpp index ed59906b0e..0f5edec62d 100644 --- a/tools/sysid/src/main/native/include/wpi/sysid/view/LogLoader.hpp +++ b/tools/sysid/src/main/native/include/wpi/sysid/view/LogLoader.hpp @@ -12,7 +12,7 @@ #include "wpi/glass/View.hpp" #include "wpi/util/Signal.h" -namespace glass { +namespace wpi::glass { class Storage; } // namespace glass @@ -25,21 +25,21 @@ namespace log { class DataLogReaderEntry; class DataLogReaderThread; } // namespace log -class Logger; +class wpi::util::Logger; } // namespace wpi namespace sysid { /** * Helps with loading datalog files. */ -class LogLoader : public glass::View { +class LogLoader : public wpi::glass::View { public: /** * Creates a log loader widget * * @param logger The program logger */ - explicit LogLoader(glass::Storage& storage, wpi::Logger& logger); + explicit LogLoader(wpi::glass::Storage& storage, wpi::util::Logger& logger); ~LogLoader() override; @@ -52,10 +52,10 @@ class LogLoader : public glass::View { * Signal called when the current file is unloaded (invalidates any * LogEntry*). */ - wpi::sig::Signal<> unload; + wpi::util::sig::Signal<> unload; private: - // wpi::Logger& m_logger; + // Logger& m_logger; std::string m_filename; std::unique_ptr m_opener; diff --git a/tools/sysid/src/test/native/cpp/analysis/FeedforwardAnalysisTest.cpp b/tools/sysid/src/test/native/cpp/analysis/FeedforwardAnalysisTest.cpp index 6f9094b433..163ac7aa92 100644 --- a/tools/sysid/src/test/native/cpp/analysis/FeedforwardAnalysisTest.cpp +++ b/tools/sysid/src/test/native/cpp/analysis/FeedforwardAnalysisTest.cpp @@ -40,9 +40,9 @@ inline constexpr int kMovementCombinations = 16; template sysid::Storage CollectData(Model& model, std::bitset<4> movements) { constexpr auto kUstep = 0.25_V / 1_s; - constexpr units::volt_t kUmax = 7_V; - constexpr units::second_t T = 5_ms; - constexpr units::second_t kTestDuration = 5_s; + constexpr wpi::units::volt_t kUmax = 7_V; + constexpr wpi::units::second_t T = 5_ms; + constexpr wpi::units::second_t kTestDuration = 5_s; sysid::Storage storage; auto& [slowForward, slowBackward, fastForward, fastBackward] = storage; diff --git a/tools/sysid/src/test/native/cpp/analysis/FilterTest.cpp b/tools/sysid/src/test/native/cpp/analysis/FilterTest.cpp index 672d97be68..e446cc2a5c 100644 --- a/tools/sysid/src/test/native/cpp/analysis/FilterTest.cpp +++ b/tools/sysid/src/test/native/cpp/analysis/FilterTest.cpp @@ -13,7 +13,7 @@ #include "wpi/sysid/analysis/FilteringUtils.hpp" #include "wpi/sysid/analysis/Storage.hpp" -TEST(FilterTest, MedianFilter) { +TEST(FilterTest, wpi::math::MedianFilter) { std::vector testData{ sysid::PreparedData{0_s, 0, 0, 0}, sysid::PreparedData{0_s, 0, 0, 1}, sysid::PreparedData{0_s, 0, 0, 10}, sysid::PreparedData{0_s, 0, 0, 5}, @@ -49,7 +49,7 @@ void FillStepVoltageData(std::vector& data) { auto& datum = data.at(i); datum.timestamp = previousDatum.timestamp + previousDatum.dt; datum.position = 0.5 * previousDatum.acceleration * - units::math::pow<2>(previousDatum.dt).value() + + wpi::units::math::pow<2>(previousDatum.dt).value() + previousDatum.velocity * previousDatum.dt.value() + previousDatum.position; datum.velocity = previousDatum.velocity + @@ -136,7 +136,7 @@ TEST(FilterTest, StepTrim) { } template -void AssertCentralResults(F&& f, DfDx&& dfdx, units::second_t h, double min, +void AssertCentralResults(F&& f, DfDx&& dfdx, wpi::units::second_t h, double min, double max) { static_assert(Samples % 2 != 0, "Number of samples must be odd."); diff --git a/tools/wpical/src/main/native/cpp/WPIcal.cpp b/tools/wpical/src/main/native/cpp/WPIcal.cpp index ba9205bd31..76763d4613 100644 --- a/tools/wpical/src/main/native/cpp/WPIcal.cpp +++ b/tools/wpical/src/main/native/cpp/WPIcal.cpp @@ -148,7 +148,7 @@ static bool EmitEntryTarget(int tag_id, std::string& file) { return rv; } -void saveCalibration(wpi::json& field, std::string& output_directory, +void saveCalibration(wpi::util::json& field, std::string& output_directory, std::string output_name, bool& isCalibrating) { if (!field.empty() && !output_directory.empty()) { std::cout << "Saving calibration to " << output_directory << std::endl; @@ -198,8 +198,8 @@ static void DisplayGui() { field_calibration_directory_selector; static std::unique_ptr download_directory_selector; - static wpi::json field_calibration_json; - static wpi::json field_combination_json; + static wpi::util::json field_calibration_json; + static wpi::util::json field_combination_json; static std::string selected_camera_intrinsics; static std::string selected_field_map; @@ -534,8 +534,8 @@ static void DisplayGui() { std::ifstream calJson(output_calibration_json_path); std::ifstream refJson(selected_field_map); - currentCalibrationMap = Fieldmap(wpi::json::parse(calJson)); - currentReferenceMap = Fieldmap(wpi::json::parse(refJson)); + currentCalibrationMap = Fieldmap(wpi::util::json::parse(calJson)); + currentReferenceMap = Fieldmap(wpi::util::json::parse(refJson)); if (currentCalibrationMap.getNumTags() != currentReferenceMap.getNumTags()) { @@ -616,7 +616,7 @@ static void DisplayGui() { if (!selected_field_map.empty()) { drawCheck(); std::ifstream json(selected_field_map); - currentReferenceMap = Fieldmap(wpi::json::parse(json)); + currentReferenceMap = Fieldmap(wpi::util::json::parse(json)); currentCombinerMap = currentReferenceMap; } openFilesButton("Select Field Calibrations", @@ -660,7 +660,7 @@ static void DisplayGui() { if (ImGui::Button("Download", ImVec2(0, 0))) { for (auto& [key, val] : combiner_map) { std::ifstream json(val); - Fieldmap map(wpi::json::parse(json)); + Fieldmap map(wpi::util::json::parse(json)); currentCombinerMap.replaceTag(key, map.getTag(key)); } field_combination_json = currentCombinerMap.toJson(); diff --git a/tools/wpical/src/main/native/cpp/fieldcalibration.cpp b/tools/wpical/src/main/native/cpp/fieldcalibration.cpp index 4f1aa749ce..38e00c6b7e 100644 --- a/tools/wpical/src/main/native/cpp/fieldcalibration.cpp +++ b/tools/wpical/src/main/native/cpp/fieldcalibration.cpp @@ -96,11 +96,11 @@ inline cameracalibration::CameraModel load_camera_model(std::string path) { std::ifstream file(path); - wpi::json json_data; + wpi::util::json json_data; try { - json_data = wpi::json::parse(file); - } catch (const wpi::json::parse_error& e) { + json_data = wpi::util::json::parse(file); + } catch (const wpi::util::json::parse_error& e) { std::cout << e.what() << std::endl; } @@ -150,7 +150,7 @@ inline cameracalibration::CameraModel load_camera_model(std::string path) { return camera_model; } -inline cameracalibration::CameraModel load_camera_model(wpi::json json_data) { +inline cameracalibration::CameraModel load_camera_model(wpi::util::json json_data) { // Camera matrix Eigen::Matrix camera_matrix; @@ -176,10 +176,10 @@ inline cameracalibration::CameraModel load_camera_model(wpi::json json_data) { return camera_model; } -inline std::map load_ideal_map(std::string path) { +inline std::map load_ideal_map(std::string path) { std::ifstream file(path); - wpi::json json_data = wpi::json::parse(file); - std::map ideal_map; + wpi::util::json json_data = wpi::util::json::parse(file); + std::map ideal_map; for (const auto& element : json_data["tags"]) { ideal_map[element["ID"]] = element; @@ -189,7 +189,7 @@ inline std::map load_ideal_map(std::string path) { } Eigen::Matrix get_tag_transform( - std::map& ideal_map, int tag_id) { + std::map& ideal_map, int tag_id) { Eigen::Matrix transform = Eigen::Matrix::Identity(); @@ -432,7 +432,7 @@ inline bool process_video_file( } int fieldcalibration::calibrate(std::string input_dir_path, - wpi::json& output_json, + wpi::util::json& output_json, std::string camera_model_path, std::string ideal_map_path, int pinned_tag_id, bool show_debug_window) { @@ -452,13 +452,13 @@ int fieldcalibration::calibrate(std::string input_dir_path, return 1; } - wpi::json json = wpi::json::parse(std::ifstream(ideal_map_path)); + wpi::util::json json = wpi::util::json::parse(std::ifstream(ideal_map_path)); if (!json.contains("tags")) { return 1; } // Load ideal field map - std::map ideal_map; + std::map ideal_map; try { ideal_map = load_ideal_map(ideal_map_path); } catch (...) { @@ -552,7 +552,7 @@ int fieldcalibration::calibrate(std::string input_dir_path, std::cout << summary.BriefReport() << std::endl; // Output - std::map observed_map = ideal_map; + std::map observed_map = ideal_map; Eigen::Matrix correction_a; correction_a << 0, 0, -1, 0, 1, 0, 0, 0, 0, -1, 0, 0, 0, 0, 0, 1; @@ -594,7 +594,7 @@ int fieldcalibration::calibrate(std::string input_dir_path, corrected_transform_q.w(); } - wpi::json observed_map_json; + wpi::util::json observed_map_json; for (const auto& [tag_id, tag_json] : observed_map) { observed_map_json["tags"].push_back(tag_json); diff --git a/tools/wpical/src/main/native/cpp/fmap.cpp b/tools/wpical/src/main/native/cpp/fmap.cpp index 82db1f956b..6ed9944afa 100644 --- a/tools/wpical/src/main/native/cpp/fmap.cpp +++ b/tools/wpical/src/main/native/cpp/fmap.cpp @@ -7,7 +7,7 @@ #include #include -wpi::json fmap::singleTag(int tag, const tag::Pose& tagpose) { +wpi::util::json fmap::singleTag(int tag, const tag::Pose& tagpose) { std::vector transform = {}; for (int i = 0; i < 4; i++) { for (int j = 0; j < 4; j++) { @@ -22,7 +22,7 @@ wpi::json fmap::singleTag(int tag, const tag::Pose& tagpose) { {"unique", true}}; } -wpi::json fmap::convertfmap(const wpi::json& json) { +wpi::util::json fmap::convertfmap(const wpi::util::json& json) { std::string fmapstart = "{\"fiducials\":["; std::string fmapend = "],\"type\":\"frc\"}"; @@ -36,5 +36,5 @@ wpi::json fmap::convertfmap(const wpi::json& json) { } } - return wpi::json::parse(fmapstart.append(fmapend)); + return wpi::util::json::parse(fmapstart.append(fmapend)); } diff --git a/tools/wpical/src/main/native/cpp/tagpose.cpp b/tools/wpical/src/main/native/cpp/tagpose.cpp index 5208ad6244..8137679996 100644 --- a/tools/wpical/src/main/native/cpp/tagpose.cpp +++ b/tools/wpical/src/main/native/cpp/tagpose.cpp @@ -32,7 +32,7 @@ Pose::Pose(int tag_id, double xpos, double ypos, double zpos, double w, yawRot = eulerAngles[2]; } -wpi::json Pose::toJson() { +wpi::util::json Pose::toJson() { return {{"ID", tagId}, {"pose", {{"translation", {{"x", xPos}, {"y", yPos}, {"z", zPos}}}, diff --git a/tools/wpical/src/main/native/include/cameracalibration.hpp b/tools/wpical/src/main/native/include/cameracalibration.hpp index 3e728ac1ae..c1210270b4 100644 --- a/tools/wpical/src/main/native/include/cameracalibration.hpp +++ b/tools/wpical/src/main/native/include/cameracalibration.hpp @@ -40,7 +40,7 @@ static void dumpJson(CameraModel& camera_model, camera_model.distortion_coefficients.data() + camera_model.distortion_coefficients.size()); - wpi::json result = { + wpi::util::json result = { {"camera_matrix", camera_matrix}, {"distortion_coefficients", distortion_coefficients}, {"avg_reprojection_error", camera_model.avg_reprojection_error}}; diff --git a/tools/wpical/src/main/native/include/fieldcalibration.hpp b/tools/wpical/src/main/native/include/fieldcalibration.hpp index 673b6a236f..582e19cb8c 100644 --- a/tools/wpical/src/main/native/include/fieldcalibration.hpp +++ b/tools/wpical/src/main/native/include/fieldcalibration.hpp @@ -10,7 +10,7 @@ #include "wpi/util/json.hpp" namespace fieldcalibration { -int calibrate(std::string input_dir_path, wpi::json& output_json, +int calibrate(std::string input_dir_path, wpi::util::json& output_json, std::string camera_model_path, std::string ideal_map_path, int pinned_tag_id, bool show_debug_window); } // namespace fieldcalibration diff --git a/tools/wpical/src/main/native/include/fieldmap.hpp b/tools/wpical/src/main/native/include/fieldmap.hpp index c3fb241927..352d4ab5d2 100644 --- a/tools/wpical/src/main/native/include/fieldmap.hpp +++ b/tools/wpical/src/main/native/include/fieldmap.hpp @@ -13,7 +13,7 @@ class Fieldmap { public: Fieldmap() = default; - explicit Fieldmap(const wpi::json& json) { + explicit Fieldmap(const wpi::util::json& json) { double field_length_meters = static_cast(json.at("field").at("length")); double field_width_meters = @@ -50,8 +50,8 @@ class Fieldmap { bool hasTag(int tag) { return tagMap.find(tag) != tagMap.end(); } - wpi::json toJson() { - wpi::json json; + wpi::util::json toJson() { + wpi::util::json json; for (auto& [key, val] : tagMap) { json["tags"].push_back(val.toJson()); } diff --git a/tools/wpical/src/main/native/include/fmap.hpp b/tools/wpical/src/main/native/include/fmap.hpp index 6975e8a3ee..d63b3190d2 100644 --- a/tools/wpical/src/main/native/include/fmap.hpp +++ b/tools/wpical/src/main/native/include/fmap.hpp @@ -9,6 +9,6 @@ #include "wpi/util/json.hpp" namespace fmap { -wpi::json singleTag(int tag, const tag::Pose& tagpose); -wpi::json convertfmap(const wpi::json& json); +wpi::util::json singleTag(int tag, const tag::Pose& tagpose); +wpi::util::json convertfmap(const wpi::util::json& json); } // namespace fmap diff --git a/tools/wpical/src/main/native/include/tagpose.hpp b/tools/wpical/src/main/native/include/tagpose.hpp index 6c9f37247a..596ed3c5c6 100644 --- a/tools/wpical/src/main/native/include/tagpose.hpp +++ b/tools/wpical/src/main/native/include/tagpose.hpp @@ -20,6 +20,6 @@ class Pose { Eigen::Quaterniond quaternion; Eigen::Matrix3d rotationMatrix; Eigen::Matrix4d transformMatrixFmap; - wpi::json toJson(); + wpi::util::json toJson(); }; } // namespace tag diff --git a/tools/wpical/src/main/native/thirdparty/mrcal/src/poseutils-uses-autodiff.cpp b/tools/wpical/src/main/native/thirdparty/mrcal/src/poseutils-uses-autodiff.cpp index deb4670887..39b31408a8 100644 --- a/tools/wpical/src/main/native/thirdparty/mrcal/src/poseutils-uses-autodiff.cpp +++ b/tools/wpical/src/main/native/thirdparty/mrcal/src/poseutils-uses-autodiff.cpp @@ -288,7 +288,7 @@ compose_r_core(// output Described here: - Altmann, Simon L. "Hamilton, Rodrigues, and the Quaternion Scandal." + Altmann, Simon L. "Hamilton, Rodrigues, and the wpi::math::Quaternion Scandal." Mathematics Magazine, vol. 62, no. 5, 1989, pp. 291–308 Available here: diff --git a/tools/wpical/src/test/native/cpp/test_calibrate.cpp b/tools/wpical/src/test/native/cpp/test_calibrate.cpp index 5e298f7a6d..3979d2a835 100644 --- a/tools/wpical/src/test/native/cpp/test_calibrate.cpp +++ b/tools/wpical/src/test/native/cpp/test_calibrate.cpp @@ -26,7 +26,7 @@ cameracalibration::CameraModel cameraModel = { .distortion_coefficients = Eigen::Matrix::Zero(), .avg_reprojection_error = 0.0}; -wpi::json output_json; +wpi::util::json output_json; #ifdef __linux__ const std::string fileSuffix = ".avi"; diff --git a/wpilibc/src/dev/native/cpp/main.cpp b/wpilibc/src/dev/native/cpp/main.cpp index 9fb77f5ade..af572151af 100644 --- a/wpilibc/src/dev/native/cpp/main.cpp +++ b/wpilibc/src/dev/native/cpp/main.cpp @@ -7,7 +7,7 @@ #include "wpi/util/print.hpp" int main() { - wpi::print("Hello World\n"); - wpi::print("{}\n", static_cast(HAL_GetRuntimeType())); - wpi::print("{}\n", GetWPILibVersion()); + wpi::util::print("Hello World\n"); + wpi::util::print("{}\n", static_cast(HAL_GetRuntimeType())); + wpi::util::print("{}\n", GetWPILibVersion()); } diff --git a/wpilibc/src/generate/main/native/cpp/driverstation/hid.cpp.jinja b/wpilibc/src/generate/main/native/cpp/driverstation/hid.cpp.jinja index 9ac2bca451..a59dc80e9e 100644 --- a/wpilibc/src/generate/main/native/cpp/driverstation/hid.cpp.jinja +++ b/wpilibc/src/generate/main/native/cpp/driverstation/hid.cpp.jinja @@ -13,7 +13,7 @@ #include "wpi/event/BooleanEvent.hpp" -using namespace frc; +using namespace wpi; {{ ConsoleName }}Controller::{{ ConsoleName }}Controller(int port) : GenericHID(port) { HAL_ReportUsage("HID", port, "{{ ConsoleName }}Controller"); @@ -92,7 +92,7 @@ bool {{ ConsoleName }}Controller::GetTouchpadReleased() { } {%- endif %} -void {{ ConsoleName }}Controller::InitSendable(wpi::SendableBuilder& builder) { +void {{ ConsoleName }}Controller::InitSendable(wpi::util::SendableBuilder& builder) { builder.SetSmartDashboardType("HID"); builder.PublishConstString("ControllerType", "{{ ConsoleName }}"); {%- for trigger in triggers %} diff --git a/wpilibc/src/generate/main/native/cpp/hardware/motor/pwm_motor_controller.cpp.jinja b/wpilibc/src/generate/main/native/cpp/hardware/motor/pwm_motor_controller.cpp.jinja index 0c0909176f..d6e79633b4 100644 --- a/wpilibc/src/generate/main/native/cpp/hardware/motor/pwm_motor_controller.cpp.jinja +++ b/wpilibc/src/generate/main/native/cpp/hardware/motor/pwm_motor_controller.cpp.jinja @@ -8,7 +8,7 @@ #include "wpi/hal/UsageReporting.h" -using namespace frc; +using namespace wpi; {{ name }}::{{ name }}(int channel) : PWMMotorController("{{ name }}", channel) { SetBounds({{ pulse_width_ms.max }}_ms, {{ pulse_width_ms.deadbandMax }}_ms, {{ pulse_width_ms.center }}_ms, {{ pulse_width_ms.deadbandMin }}_ms, {{ pulse_width_ms.min }}_ms); diff --git a/wpilibc/src/generate/main/native/cpp/simulation/hidsim.cpp.jinja b/wpilibc/src/generate/main/native/cpp/simulation/hidsim.cpp.jinja index 3a99eafbd1..e3a39046a8 100644 --- a/wpilibc/src/generate/main/native/cpp/simulation/hidsim.cpp.jinja +++ b/wpilibc/src/generate/main/native/cpp/simulation/hidsim.cpp.jinja @@ -10,8 +10,8 @@ #include "wpi/driverstation/{{ ConsoleName }}Controller.hpp" -using namespace frc; -using namespace frc::sim; +using namespace wpi; +using namespace wpi::sim; {{ ConsoleName }}ControllerSim::{{ ConsoleName }}ControllerSim(const {{ ConsoleName }}Controller& joystick) : GenericHIDSim{joystick} { diff --git a/wpilibc/src/generate/main/native/include/wpi/driverstation/hid.hpp.jinja b/wpilibc/src/generate/main/native/include/wpi/driverstation/hid.hpp.jinja index f7350e50ea..9e29eeb760 100644 --- a/wpilibc/src/generate/main/native/include/wpi/driverstation/hid.hpp.jinja +++ b/wpilibc/src/generate/main/native/include/wpi/driverstation/hid.hpp.jinja @@ -13,7 +13,7 @@ #include "wpi/driverstation/GenericHID.hpp" -namespace frc { +namespace wpi { /** * Handle input from {{ ConsoleName }} controllers connected to the Driver Station. @@ -28,8 +28,8 @@ namespace frc { * to have the same mapping, as well as any 3rd party controllers. */ class {{ ConsoleName }}Controller : public GenericHID, - public wpi::Sendable, - public wpi::SendableHelper<{{ ConsoleName }}Controller> { + public wpi::util::Sendable, + public wpi::util::SendableHelper<{{ ConsoleName }}Controller> { public: /** * Construct an instance of a controller. @@ -236,7 +236,7 @@ class {{ ConsoleName }}Controller : public GenericHID, {%- endfor %} }; - void InitSendable(wpi::SendableBuilder& builder) override; + void InitSendable(wpi::util::SendableBuilder& builder) override; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/generate/main/native/include/wpi/hardware/motor/pwm_motor_controller.hpp.jinja b/wpilibc/src/generate/main/native/include/wpi/hardware/motor/pwm_motor_controller.hpp.jinja index 251d2e49ce..5eab39dfa6 100644 --- a/wpilibc/src/generate/main/native/include/wpi/hardware/motor/pwm_motor_controller.hpp.jinja +++ b/wpilibc/src/generate/main/native/include/wpi/hardware/motor/pwm_motor_controller.hpp.jinja @@ -8,7 +8,7 @@ #include "wpi/hardware/motor/PWMMotorController.hpp" -namespace frc { +namespace wpi { /** * {{ Manufacturer }} {{ DisplayName }} Motor Controller with PWM control. @@ -40,4 +40,4 @@ class {{ name }} : public PWMMotorController { {{ name }}& operator=({{ name }}&&) = default; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/generate/main/native/include/wpi/simulation/hidsim.hpp.jinja b/wpilibc/src/generate/main/native/include/wpi/simulation/hidsim.hpp.jinja index e29724a06a..94d8064244 100644 --- a/wpilibc/src/generate/main/native/include/wpi/simulation/hidsim.hpp.jinja +++ b/wpilibc/src/generate/main/native/include/wpi/simulation/hidsim.hpp.jinja @@ -10,7 +10,7 @@ #include "wpi/simulation/GenericHIDSim.hpp" -namespace frc { +namespace wpi { class {{ ConsoleName }}Controller; @@ -95,4 +95,4 @@ class {{ ConsoleName }}ControllerSim : public GenericHIDSim { }; } // namespace sim -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/generated/main/native/cpp/driverstation/PS4Controller.cpp b/wpilibc/src/generated/main/native/cpp/driverstation/PS4Controller.cpp index 306652ca19..3c215e997c 100644 --- a/wpilibc/src/generated/main/native/cpp/driverstation/PS4Controller.cpp +++ b/wpilibc/src/generated/main/native/cpp/driverstation/PS4Controller.cpp @@ -11,7 +11,7 @@ #include "wpi/event/BooleanEvent.hpp" -using namespace frc; +using namespace wpi; PS4Controller::PS4Controller(int port) : GenericHID(port) { HAL_ReportUsage("HID", port, "PS4Controller"); @@ -277,7 +277,7 @@ bool PS4Controller::GetTouchpadReleased() { return GetRawButtonReleased(Button::kTouchpad); } -void PS4Controller::InitSendable(wpi::SendableBuilder& builder) { +void PS4Controller::InitSendable(wpi::util::SendableBuilder& builder) { builder.SetSmartDashboardType("HID"); builder.PublishConstString("ControllerType", "PS4"); builder.AddDoubleProperty("L2 Axis", [this] { return GetL2Axis(); }, nullptr); diff --git a/wpilibc/src/generated/main/native/cpp/driverstation/PS5Controller.cpp b/wpilibc/src/generated/main/native/cpp/driverstation/PS5Controller.cpp index fee3efc689..5ead2a666a 100644 --- a/wpilibc/src/generated/main/native/cpp/driverstation/PS5Controller.cpp +++ b/wpilibc/src/generated/main/native/cpp/driverstation/PS5Controller.cpp @@ -11,7 +11,7 @@ #include "wpi/event/BooleanEvent.hpp" -using namespace frc; +using namespace wpi; PS5Controller::PS5Controller(int port) : GenericHID(port) { HAL_ReportUsage("HID", port, "PS5Controller"); @@ -277,7 +277,7 @@ bool PS5Controller::GetTouchpadReleased() { return GetRawButtonReleased(Button::kTouchpad); } -void PS5Controller::InitSendable(wpi::SendableBuilder& builder) { +void PS5Controller::InitSendable(wpi::util::SendableBuilder& builder) { builder.SetSmartDashboardType("HID"); builder.PublishConstString("ControllerType", "PS5"); builder.AddDoubleProperty("L2 Axis", [this] { return GetL2Axis(); }, nullptr); diff --git a/wpilibc/src/generated/main/native/cpp/driverstation/StadiaController.cpp b/wpilibc/src/generated/main/native/cpp/driverstation/StadiaController.cpp index d4cafa249a..8f500c6874 100644 --- a/wpilibc/src/generated/main/native/cpp/driverstation/StadiaController.cpp +++ b/wpilibc/src/generated/main/native/cpp/driverstation/StadiaController.cpp @@ -11,7 +11,7 @@ #include "wpi/event/BooleanEvent.hpp" -using namespace frc; +using namespace wpi; StadiaController::StadiaController(int port) : GenericHID(port) { HAL_ReportUsage("HID", port, "StadiaController"); @@ -297,7 +297,7 @@ bool StadiaController::GetRightBumperReleased() { return GetRawButtonReleased(Button::kRightBumper); } -void StadiaController::InitSendable(wpi::SendableBuilder& builder) { +void StadiaController::InitSendable(wpi::util::SendableBuilder& builder) { builder.SetSmartDashboardType("HID"); builder.PublishConstString("ControllerType", "Stadia"); builder.AddDoubleProperty("LeftX", [this] { return GetLeftX(); }, nullptr); diff --git a/wpilibc/src/generated/main/native/cpp/driverstation/XboxController.cpp b/wpilibc/src/generated/main/native/cpp/driverstation/XboxController.cpp index c529a70b44..8def6d8b45 100644 --- a/wpilibc/src/generated/main/native/cpp/driverstation/XboxController.cpp +++ b/wpilibc/src/generated/main/native/cpp/driverstation/XboxController.cpp @@ -11,7 +11,7 @@ #include "wpi/event/BooleanEvent.hpp" -using namespace frc; +using namespace wpi; XboxController::XboxController(int port) : GenericHID(port) { HAL_ReportUsage("HID", port, "XboxController"); @@ -241,7 +241,7 @@ bool XboxController::GetRightBumperReleased() { return GetRawButtonReleased(Button::kRightBumper); } -void XboxController::InitSendable(wpi::SendableBuilder& builder) { +void XboxController::InitSendable(wpi::util::SendableBuilder& builder) { builder.SetSmartDashboardType("HID"); builder.PublishConstString("ControllerType", "Xbox"); builder.AddDoubleProperty("LeftTrigger Axis", [this] { return GetLeftTriggerAxis(); }, nullptr); diff --git a/wpilibc/src/generated/main/native/cpp/hardware/motor/Koors40.cpp b/wpilibc/src/generated/main/native/cpp/hardware/motor/Koors40.cpp index ab643aaccc..9c84583187 100644 --- a/wpilibc/src/generated/main/native/cpp/hardware/motor/Koors40.cpp +++ b/wpilibc/src/generated/main/native/cpp/hardware/motor/Koors40.cpp @@ -8,7 +8,7 @@ #include "wpi/hal/UsageReporting.h" -using namespace frc; +using namespace wpi; Koors40::Koors40(int channel) : PWMMotorController("Koors40", channel) { SetBounds(2.004_ms, 1.52_ms, 1.5_ms, 1.48_ms, 0.997_ms); diff --git a/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMSparkFlex.cpp b/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMSparkFlex.cpp index a7d23e7a99..ccac0bb37d 100644 --- a/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMSparkFlex.cpp +++ b/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMSparkFlex.cpp @@ -8,7 +8,7 @@ #include "wpi/hal/UsageReporting.h" -using namespace frc; +using namespace wpi; PWMSparkFlex::PWMSparkFlex(int channel) : PWMMotorController("PWMSparkFlex", channel) { SetBounds(2.003_ms, 1.55_ms, 1.5_ms, 1.46_ms, 0.999_ms); diff --git a/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMSparkMax.cpp b/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMSparkMax.cpp index 1958e078d0..bf915255f1 100644 --- a/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMSparkMax.cpp +++ b/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMSparkMax.cpp @@ -8,7 +8,7 @@ #include "wpi/hal/UsageReporting.h" -using namespace frc; +using namespace wpi; PWMSparkMax::PWMSparkMax(int channel) : PWMMotorController("PWMSparkMax", channel) { SetBounds(2.003_ms, 1.55_ms, 1.5_ms, 1.46_ms, 0.999_ms); diff --git a/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMTalonFX.cpp b/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMTalonFX.cpp index 23557bc9bf..24d0fdcf42 100644 --- a/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMTalonFX.cpp +++ b/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMTalonFX.cpp @@ -8,7 +8,7 @@ #include "wpi/hal/UsageReporting.h" -using namespace frc; +using namespace wpi; PWMTalonFX::PWMTalonFX(int channel) : PWMMotorController("PWMTalonFX", channel) { SetBounds(2.004_ms, 1.52_ms, 1.5_ms, 1.48_ms, 0.997_ms); diff --git a/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMTalonSRX.cpp b/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMTalonSRX.cpp index b0b6821bad..35bd165d58 100644 --- a/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMTalonSRX.cpp +++ b/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMTalonSRX.cpp @@ -8,7 +8,7 @@ #include "wpi/hal/UsageReporting.h" -using namespace frc; +using namespace wpi; PWMTalonSRX::PWMTalonSRX(int channel) : PWMMotorController("PWMTalonSRX", channel) { SetBounds(2.004_ms, 1.52_ms, 1.5_ms, 1.48_ms, 0.997_ms); diff --git a/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMVenom.cpp b/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMVenom.cpp index df931ca0f6..28b182a1b7 100644 --- a/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMVenom.cpp +++ b/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMVenom.cpp @@ -8,7 +8,7 @@ #include "wpi/hal/UsageReporting.h" -using namespace frc; +using namespace wpi; PWMVenom::PWMVenom(int channel) : PWMMotorController("PWMVenom", channel) { SetBounds(2.004_ms, 1.52_ms, 1.5_ms, 1.48_ms, 0.997_ms); diff --git a/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMVictorSPX.cpp b/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMVictorSPX.cpp index d2328ef142..7585ae5d31 100644 --- a/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMVictorSPX.cpp +++ b/wpilibc/src/generated/main/native/cpp/hardware/motor/PWMVictorSPX.cpp @@ -8,7 +8,7 @@ #include "wpi/hal/UsageReporting.h" -using namespace frc; +using namespace wpi; PWMVictorSPX::PWMVictorSPX(int channel) : PWMMotorController("PWMVictorSPX", channel) { SetBounds(2.004_ms, 1.52_ms, 1.5_ms, 1.48_ms, 0.997_ms); diff --git a/wpilibc/src/generated/main/native/cpp/hardware/motor/Spark.cpp b/wpilibc/src/generated/main/native/cpp/hardware/motor/Spark.cpp index 20783d33dd..a77800b755 100644 --- a/wpilibc/src/generated/main/native/cpp/hardware/motor/Spark.cpp +++ b/wpilibc/src/generated/main/native/cpp/hardware/motor/Spark.cpp @@ -8,7 +8,7 @@ #include "wpi/hal/UsageReporting.h" -using namespace frc; +using namespace wpi; Spark::Spark(int channel) : PWMMotorController("Spark", channel) { SetBounds(2.003_ms, 1.55_ms, 1.5_ms, 1.46_ms, 0.999_ms); diff --git a/wpilibc/src/generated/main/native/cpp/hardware/motor/SparkMini.cpp b/wpilibc/src/generated/main/native/cpp/hardware/motor/SparkMini.cpp index a61314f7ca..38ddcb3801 100644 --- a/wpilibc/src/generated/main/native/cpp/hardware/motor/SparkMini.cpp +++ b/wpilibc/src/generated/main/native/cpp/hardware/motor/SparkMini.cpp @@ -8,7 +8,7 @@ #include "wpi/hal/UsageReporting.h" -using namespace frc; +using namespace wpi; SparkMini::SparkMini(int channel) : PWMMotorController("SparkMini", channel) { SetBounds(2.5_ms, 1.51_ms, 1.5_ms, 1.49_ms, 0.5_ms); diff --git a/wpilibc/src/generated/main/native/cpp/hardware/motor/Talon.cpp b/wpilibc/src/generated/main/native/cpp/hardware/motor/Talon.cpp index ca83bb34c8..bfc03a7a19 100644 --- a/wpilibc/src/generated/main/native/cpp/hardware/motor/Talon.cpp +++ b/wpilibc/src/generated/main/native/cpp/hardware/motor/Talon.cpp @@ -8,7 +8,7 @@ #include "wpi/hal/UsageReporting.h" -using namespace frc; +using namespace wpi; Talon::Talon(int channel) : PWMMotorController("Talon", channel) { SetBounds(2.037_ms, 1.539_ms, 1.513_ms, 1.487_ms, 0.989_ms); diff --git a/wpilibc/src/generated/main/native/cpp/hardware/motor/VictorSP.cpp b/wpilibc/src/generated/main/native/cpp/hardware/motor/VictorSP.cpp index 9d96bee5cc..c15abe7243 100644 --- a/wpilibc/src/generated/main/native/cpp/hardware/motor/VictorSP.cpp +++ b/wpilibc/src/generated/main/native/cpp/hardware/motor/VictorSP.cpp @@ -8,7 +8,7 @@ #include "wpi/hal/UsageReporting.h" -using namespace frc; +using namespace wpi; VictorSP::VictorSP(int channel) : PWMMotorController("VictorSP", channel) { SetBounds(2.004_ms, 1.52_ms, 1.5_ms, 1.48_ms, 0.997_ms); diff --git a/wpilibc/src/generated/main/native/cpp/simulation/PS4ControllerSim.cpp b/wpilibc/src/generated/main/native/cpp/simulation/PS4ControllerSim.cpp index 8ddcaafb85..0b21c90d0e 100644 --- a/wpilibc/src/generated/main/native/cpp/simulation/PS4ControllerSim.cpp +++ b/wpilibc/src/generated/main/native/cpp/simulation/PS4ControllerSim.cpp @@ -8,8 +8,8 @@ #include "wpi/driverstation/PS4Controller.hpp" -using namespace frc; -using namespace frc::sim; +using namespace wpi; +using namespace wpi::sim; PS4ControllerSim::PS4ControllerSim(const PS4Controller& joystick) : GenericHIDSim{joystick} { diff --git a/wpilibc/src/generated/main/native/cpp/simulation/PS5ControllerSim.cpp b/wpilibc/src/generated/main/native/cpp/simulation/PS5ControllerSim.cpp index 833ae3be6d..717c60e966 100644 --- a/wpilibc/src/generated/main/native/cpp/simulation/PS5ControllerSim.cpp +++ b/wpilibc/src/generated/main/native/cpp/simulation/PS5ControllerSim.cpp @@ -8,8 +8,8 @@ #include "wpi/driverstation/PS5Controller.hpp" -using namespace frc; -using namespace frc::sim; +using namespace wpi; +using namespace wpi::sim; PS5ControllerSim::PS5ControllerSim(const PS5Controller& joystick) : GenericHIDSim{joystick} { diff --git a/wpilibc/src/generated/main/native/cpp/simulation/StadiaControllerSim.cpp b/wpilibc/src/generated/main/native/cpp/simulation/StadiaControllerSim.cpp index 64051708a4..4b70aad36d 100644 --- a/wpilibc/src/generated/main/native/cpp/simulation/StadiaControllerSim.cpp +++ b/wpilibc/src/generated/main/native/cpp/simulation/StadiaControllerSim.cpp @@ -8,8 +8,8 @@ #include "wpi/driverstation/StadiaController.hpp" -using namespace frc; -using namespace frc::sim; +using namespace wpi; +using namespace wpi::sim; StadiaControllerSim::StadiaControllerSim(const StadiaController& joystick) : GenericHIDSim{joystick} { diff --git a/wpilibc/src/generated/main/native/cpp/simulation/XboxControllerSim.cpp b/wpilibc/src/generated/main/native/cpp/simulation/XboxControllerSim.cpp index 10448c42d9..1f54ef6f3a 100644 --- a/wpilibc/src/generated/main/native/cpp/simulation/XboxControllerSim.cpp +++ b/wpilibc/src/generated/main/native/cpp/simulation/XboxControllerSim.cpp @@ -8,8 +8,8 @@ #include "wpi/driverstation/XboxController.hpp" -using namespace frc; -using namespace frc::sim; +using namespace wpi; +using namespace wpi::sim; XboxControllerSim::XboxControllerSim(const XboxController& joystick) : GenericHIDSim{joystick} { diff --git a/wpilibc/src/generated/main/native/include/wpi/driverstation/PS4Controller.hpp b/wpilibc/src/generated/main/native/include/wpi/driverstation/PS4Controller.hpp index 370a20c42e..b3b512699e 100644 --- a/wpilibc/src/generated/main/native/include/wpi/driverstation/PS4Controller.hpp +++ b/wpilibc/src/generated/main/native/include/wpi/driverstation/PS4Controller.hpp @@ -11,7 +11,7 @@ #include "wpi/driverstation/GenericHID.hpp" -namespace frc { +namespace wpi { /** * Handle input from PS4 controllers connected to the Driver Station. @@ -26,8 +26,8 @@ namespace frc { * to have the same mapping, as well as any 3rd party controllers. */ class PS4Controller : public GenericHID, - public wpi::Sendable, - public wpi::SendableHelper { + public wpi::util::Sendable, + public wpi::util::SendableHelper { public: /** * Construct an instance of a controller. @@ -602,7 +602,7 @@ class PS4Controller : public GenericHID, static constexpr int kR2 = 4; }; - void InitSendable(wpi::SendableBuilder& builder) override; + void InitSendable(wpi::util::SendableBuilder& builder) override; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/generated/main/native/include/wpi/driverstation/PS5Controller.hpp b/wpilibc/src/generated/main/native/include/wpi/driverstation/PS5Controller.hpp index ac1bdda0f3..dd80e2f5ab 100644 --- a/wpilibc/src/generated/main/native/include/wpi/driverstation/PS5Controller.hpp +++ b/wpilibc/src/generated/main/native/include/wpi/driverstation/PS5Controller.hpp @@ -11,7 +11,7 @@ #include "wpi/driverstation/GenericHID.hpp" -namespace frc { +namespace wpi { /** * Handle input from PS5 controllers connected to the Driver Station. @@ -26,8 +26,8 @@ namespace frc { * to have the same mapping, as well as any 3rd party controllers. */ class PS5Controller : public GenericHID, - public wpi::Sendable, - public wpi::SendableHelper { + public wpi::util::Sendable, + public wpi::util::SendableHelper { public: /** * Construct an instance of a controller. @@ -602,7 +602,7 @@ class PS5Controller : public GenericHID, static constexpr int kR2 = 4; }; - void InitSendable(wpi::SendableBuilder& builder) override; + void InitSendable(wpi::util::SendableBuilder& builder) override; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/generated/main/native/include/wpi/driverstation/StadiaController.hpp b/wpilibc/src/generated/main/native/include/wpi/driverstation/StadiaController.hpp index 7dbcf6593f..26402a5d42 100644 --- a/wpilibc/src/generated/main/native/include/wpi/driverstation/StadiaController.hpp +++ b/wpilibc/src/generated/main/native/include/wpi/driverstation/StadiaController.hpp @@ -11,7 +11,7 @@ #include "wpi/driverstation/GenericHID.hpp" -namespace frc { +namespace wpi { /** * Handle input from Stadia controllers connected to the Driver Station. @@ -26,8 +26,8 @@ namespace frc { * to have the same mapping, as well as any 3rd party controllers. */ class StadiaController : public GenericHID, - public wpi::Sendable, - public wpi::SendableHelper { + public wpi::util::Sendable, + public wpi::util::SendableHelper { public: /** * Construct an instance of a controller. @@ -649,7 +649,7 @@ class StadiaController : public GenericHID, static constexpr int kRightY = 4; }; - void InitSendable(wpi::SendableBuilder& builder) override; + void InitSendable(wpi::util::SendableBuilder& builder) override; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/generated/main/native/include/wpi/driverstation/XboxController.hpp b/wpilibc/src/generated/main/native/include/wpi/driverstation/XboxController.hpp index c7bb8575cd..9d66898937 100644 --- a/wpilibc/src/generated/main/native/include/wpi/driverstation/XboxController.hpp +++ b/wpilibc/src/generated/main/native/include/wpi/driverstation/XboxController.hpp @@ -11,7 +11,7 @@ #include "wpi/driverstation/GenericHID.hpp" -namespace frc { +namespace wpi { /** * Handle input from Xbox controllers connected to the Driver Station. @@ -26,8 +26,8 @@ namespace frc { * to have the same mapping, as well as any 3rd party controllers. */ class XboxController : public GenericHID, - public wpi::Sendable, - public wpi::SendableHelper { + public wpi::util::Sendable, + public wpi::util::SendableHelper { public: /** * Construct an instance of a controller. @@ -548,7 +548,7 @@ class XboxController : public GenericHID, static constexpr int kRightTrigger = 3; }; - void InitSendable(wpi::SendableBuilder& builder) override; + void InitSendable(wpi::util::SendableBuilder& builder) override; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/generated/main/native/include/wpi/hardware/motor/Koors40.hpp b/wpilibc/src/generated/main/native/include/wpi/hardware/motor/Koors40.hpp index 40dced4cf7..bf3b861163 100644 --- a/wpilibc/src/generated/main/native/include/wpi/hardware/motor/Koors40.hpp +++ b/wpilibc/src/generated/main/native/include/wpi/hardware/motor/Koors40.hpp @@ -8,7 +8,7 @@ #include "wpi/hardware/motor/PWMMotorController.hpp" -namespace frc { +namespace wpi { /** * AndyMark Koors40 Motor Controller with PWM control. @@ -40,4 +40,4 @@ class Koors40 : public PWMMotorController { Koors40& operator=(Koors40&&) = default; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/generated/main/native/include/wpi/hardware/motor/PWMSparkFlex.hpp b/wpilibc/src/generated/main/native/include/wpi/hardware/motor/PWMSparkFlex.hpp index 4842546131..ebd9eae6a0 100644 --- a/wpilibc/src/generated/main/native/include/wpi/hardware/motor/PWMSparkFlex.hpp +++ b/wpilibc/src/generated/main/native/include/wpi/hardware/motor/PWMSparkFlex.hpp @@ -8,7 +8,7 @@ #include "wpi/hardware/motor/PWMMotorController.hpp" -namespace frc { +namespace wpi { /** * REV Robotics SPARK Flex Motor Controller with PWM control. @@ -40,4 +40,4 @@ class PWMSparkFlex : public PWMMotorController { PWMSparkFlex& operator=(PWMSparkFlex&&) = default; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/generated/main/native/include/wpi/hardware/motor/PWMSparkMax.hpp b/wpilibc/src/generated/main/native/include/wpi/hardware/motor/PWMSparkMax.hpp index 2c0c08c045..54102a6e6b 100644 --- a/wpilibc/src/generated/main/native/include/wpi/hardware/motor/PWMSparkMax.hpp +++ b/wpilibc/src/generated/main/native/include/wpi/hardware/motor/PWMSparkMax.hpp @@ -8,7 +8,7 @@ #include "wpi/hardware/motor/PWMMotorController.hpp" -namespace frc { +namespace wpi { /** * REV Robotics SPARK MAX Motor Controller with PWM control. @@ -40,4 +40,4 @@ class PWMSparkMax : public PWMMotorController { PWMSparkMax& operator=(PWMSparkMax&&) = default; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/generated/main/native/include/wpi/hardware/motor/PWMTalonFX.hpp b/wpilibc/src/generated/main/native/include/wpi/hardware/motor/PWMTalonFX.hpp index 6cbab7df1f..2b1e56932d 100644 --- a/wpilibc/src/generated/main/native/include/wpi/hardware/motor/PWMTalonFX.hpp +++ b/wpilibc/src/generated/main/native/include/wpi/hardware/motor/PWMTalonFX.hpp @@ -8,7 +8,7 @@ #include "wpi/hardware/motor/PWMMotorController.hpp" -namespace frc { +namespace wpi { /** * Cross the Road Electronics (CTRE) Talon FX Motor Controller with PWM control. @@ -40,4 +40,4 @@ class PWMTalonFX : public PWMMotorController { PWMTalonFX& operator=(PWMTalonFX&&) = default; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/generated/main/native/include/wpi/hardware/motor/PWMTalonSRX.hpp b/wpilibc/src/generated/main/native/include/wpi/hardware/motor/PWMTalonSRX.hpp index 4e22ed39ec..412b5a9de5 100644 --- a/wpilibc/src/generated/main/native/include/wpi/hardware/motor/PWMTalonSRX.hpp +++ b/wpilibc/src/generated/main/native/include/wpi/hardware/motor/PWMTalonSRX.hpp @@ -8,7 +8,7 @@ #include "wpi/hardware/motor/PWMMotorController.hpp" -namespace frc { +namespace wpi { /** * Cross the Road Electronics (CTRE) Talon SRX Motor Controller with PWM control. @@ -40,4 +40,4 @@ class PWMTalonSRX : public PWMMotorController { PWMTalonSRX& operator=(PWMTalonSRX&&) = default; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/generated/main/native/include/wpi/hardware/motor/PWMVenom.hpp b/wpilibc/src/generated/main/native/include/wpi/hardware/motor/PWMVenom.hpp index b50ecd3797..156b94e6d5 100644 --- a/wpilibc/src/generated/main/native/include/wpi/hardware/motor/PWMVenom.hpp +++ b/wpilibc/src/generated/main/native/include/wpi/hardware/motor/PWMVenom.hpp @@ -8,7 +8,7 @@ #include "wpi/hardware/motor/PWMMotorController.hpp" -namespace frc { +namespace wpi { /** * Playing with Fusion Venom Motor Controller with PWM control. @@ -40,4 +40,4 @@ class PWMVenom : public PWMMotorController { PWMVenom& operator=(PWMVenom&&) = default; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/generated/main/native/include/wpi/hardware/motor/PWMVictorSPX.hpp b/wpilibc/src/generated/main/native/include/wpi/hardware/motor/PWMVictorSPX.hpp index 8ae5be3950..35435176a8 100644 --- a/wpilibc/src/generated/main/native/include/wpi/hardware/motor/PWMVictorSPX.hpp +++ b/wpilibc/src/generated/main/native/include/wpi/hardware/motor/PWMVictorSPX.hpp @@ -8,7 +8,7 @@ #include "wpi/hardware/motor/PWMMotorController.hpp" -namespace frc { +namespace wpi { /** * Cross the Road Electronics (CTRE) Victor SPX Motor Controller with PWM control. @@ -40,4 +40,4 @@ class PWMVictorSPX : public PWMMotorController { PWMVictorSPX& operator=(PWMVictorSPX&&) = default; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/generated/main/native/include/wpi/hardware/motor/Spark.hpp b/wpilibc/src/generated/main/native/include/wpi/hardware/motor/Spark.hpp index 85933346b9..052ec7e9d5 100644 --- a/wpilibc/src/generated/main/native/include/wpi/hardware/motor/Spark.hpp +++ b/wpilibc/src/generated/main/native/include/wpi/hardware/motor/Spark.hpp @@ -8,7 +8,7 @@ #include "wpi/hardware/motor/PWMMotorController.hpp" -namespace frc { +namespace wpi { /** * REV Robotics SPARK Motor Controller with PWM control. @@ -40,4 +40,4 @@ class Spark : public PWMMotorController { Spark& operator=(Spark&&) = default; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/generated/main/native/include/wpi/hardware/motor/SparkMini.hpp b/wpilibc/src/generated/main/native/include/wpi/hardware/motor/SparkMini.hpp index ca3db6e28e..d49faef4a1 100644 --- a/wpilibc/src/generated/main/native/include/wpi/hardware/motor/SparkMini.hpp +++ b/wpilibc/src/generated/main/native/include/wpi/hardware/motor/SparkMini.hpp @@ -8,7 +8,7 @@ #include "wpi/hardware/motor/PWMMotorController.hpp" -namespace frc { +namespace wpi { /** * REV Robotics SPARKMini Motor Controller with PWM control. @@ -40,4 +40,4 @@ class SparkMini : public PWMMotorController { SparkMini& operator=(SparkMini&&) = default; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/generated/main/native/include/wpi/hardware/motor/Talon.hpp b/wpilibc/src/generated/main/native/include/wpi/hardware/motor/Talon.hpp index 22f365cc27..c104b64fd8 100644 --- a/wpilibc/src/generated/main/native/include/wpi/hardware/motor/Talon.hpp +++ b/wpilibc/src/generated/main/native/include/wpi/hardware/motor/Talon.hpp @@ -8,7 +8,7 @@ #include "wpi/hardware/motor/PWMMotorController.hpp" -namespace frc { +namespace wpi { /** * Cross the Road Electronics (CTRE) Talon Motor Controller with PWM control. @@ -40,4 +40,4 @@ class Talon : public PWMMotorController { Talon& operator=(Talon&&) = default; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/generated/main/native/include/wpi/hardware/motor/VictorSP.hpp b/wpilibc/src/generated/main/native/include/wpi/hardware/motor/VictorSP.hpp index d532dfade5..ea711c15ad 100644 --- a/wpilibc/src/generated/main/native/include/wpi/hardware/motor/VictorSP.hpp +++ b/wpilibc/src/generated/main/native/include/wpi/hardware/motor/VictorSP.hpp @@ -8,7 +8,7 @@ #include "wpi/hardware/motor/PWMMotorController.hpp" -namespace frc { +namespace wpi { /** * Vex Robotics Victor SP Motor Controller with PWM control. @@ -40,4 +40,4 @@ class VictorSP : public PWMMotorController { VictorSP& operator=(VictorSP&&) = default; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/generated/main/native/include/wpi/simulation/PS4ControllerSim.hpp b/wpilibc/src/generated/main/native/include/wpi/simulation/PS4ControllerSim.hpp index 46359ca83a..238c907dbf 100644 --- a/wpilibc/src/generated/main/native/include/wpi/simulation/PS4ControllerSim.hpp +++ b/wpilibc/src/generated/main/native/include/wpi/simulation/PS4ControllerSim.hpp @@ -8,7 +8,7 @@ #include "wpi/simulation/GenericHIDSim.hpp" -namespace frc { +namespace wpi { class PS4Controller; @@ -187,4 +187,4 @@ class PS4ControllerSim : public GenericHIDSim { }; } // namespace sim -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/generated/main/native/include/wpi/simulation/PS5ControllerSim.hpp b/wpilibc/src/generated/main/native/include/wpi/simulation/PS5ControllerSim.hpp index ed8313f68b..aa8ba5562f 100644 --- a/wpilibc/src/generated/main/native/include/wpi/simulation/PS5ControllerSim.hpp +++ b/wpilibc/src/generated/main/native/include/wpi/simulation/PS5ControllerSim.hpp @@ -8,7 +8,7 @@ #include "wpi/simulation/GenericHIDSim.hpp" -namespace frc { +namespace wpi { class PS5Controller; @@ -187,4 +187,4 @@ class PS5ControllerSim : public GenericHIDSim { }; } // namespace sim -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/generated/main/native/include/wpi/simulation/StadiaControllerSim.hpp b/wpilibc/src/generated/main/native/include/wpi/simulation/StadiaControllerSim.hpp index 4a135cd946..2e3961bacb 100644 --- a/wpilibc/src/generated/main/native/include/wpi/simulation/StadiaControllerSim.hpp +++ b/wpilibc/src/generated/main/native/include/wpi/simulation/StadiaControllerSim.hpp @@ -8,7 +8,7 @@ #include "wpi/simulation/GenericHIDSim.hpp" -namespace frc { +namespace wpi { class StadiaController; @@ -169,4 +169,4 @@ class StadiaControllerSim : public GenericHIDSim { }; } // namespace sim -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/generated/main/native/include/wpi/simulation/XboxControllerSim.hpp b/wpilibc/src/generated/main/native/include/wpi/simulation/XboxControllerSim.hpp index 42f7222204..d2745a519d 100644 --- a/wpilibc/src/generated/main/native/include/wpi/simulation/XboxControllerSim.hpp +++ b/wpilibc/src/generated/main/native/include/wpi/simulation/XboxControllerSim.hpp @@ -8,7 +8,7 @@ #include "wpi/simulation/GenericHIDSim.hpp" -namespace frc { +namespace wpi { class XboxController; @@ -170,4 +170,4 @@ class XboxControllerSim : public GenericHIDSim { }; } // namespace sim -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/cpp/ExpansionHub.cpp b/wpilibc/src/main/native/cpp/ExpansionHub.cpp index 2c3be13a19..57a189e713 100644 --- a/wpilibc/src/main/native/cpp/ExpansionHub.cpp +++ b/wpilibc/src/main/native/cpp/ExpansionHub.cpp @@ -13,9 +13,9 @@ #include "wpi/system/Errors.hpp" #include "wpi/system/SystemServer.hpp" -using namespace frc; +using namespace wpi; -wpi::mutex ExpansionHub::m_handleLock; +wpi::util::mutex ExpansionHub::m_handleLock; std::weak_ptr ExpansionHub::m_storeMap[4]; class ExpansionHub::DataStore { @@ -33,11 +33,11 @@ class ExpansionHub::DataStore { DataStore& operator=(DataStore&) = delete; DataStore& operator=(DataStore&&) = delete; - nt::BooleanSubscriber m_hubConnectedSubscriber; + wpi::nt::BooleanSubscriber m_hubConnectedSubscriber; uint32_t m_reservedMotorMask{0}; uint32_t m_reservedServoMask{0}; - wpi::mutex m_reservedLock; + wpi::util::mutex m_reservedLock; int m_usbId; }; diff --git a/wpilibc/src/main/native/cpp/ExpansionHubMotor.cpp b/wpilibc/src/main/native/cpp/ExpansionHubMotor.cpp index 29223ce295..de81506a75 100644 --- a/wpilibc/src/main/native/cpp/ExpansionHubMotor.cpp +++ b/wpilibc/src/main/native/cpp/ExpansionHubMotor.cpp @@ -13,7 +13,7 @@ static constexpr int kPositionMode = 2; static constexpr int kVelocityMode = 3; static constexpr int kFollowerMode = 4; -using namespace frc; +using namespace wpi; ExpansionHubMotor::ExpansionHubMotor(int usbId, int channel) : m_hub{usbId}, @@ -31,7 +31,7 @@ ExpansionHubMotor::ExpansionHubMotor(int usbId, int channel) auto systemServer = SystemServer::GetSystemServer(); - nt::PubSubOptions options; + wpi::nt::PubSubOptions options; options.sendAll = true; options.keepDuplicates = true; options.periodic = 0.005; @@ -96,7 +96,7 @@ void ExpansionHubMotor::SetPercentagePower(double power) { m_setpointPublisher.Set(power); } -void ExpansionHubMotor::SetVoltage(units::volt_t voltage) { +void ExpansionHubMotor::SetVoltage(wpi::units::volt_t voltage) { m_modePublisher.Set(kVoltageMode); m_setpointPublisher.Set(voltage.to()); } @@ -119,8 +119,8 @@ void ExpansionHubMotor::SetFloatOn0(bool floatOn0) { m_floatOn0Publisher.Set(floatOn0); } -units::ampere_t ExpansionHubMotor::GetCurrent() const { - return units::ampere_t{m_currentSubscriber.Get(0)}; +wpi::units::ampere_t ExpansionHubMotor::GetCurrent() const { + return wpi::units::ampere_t{m_currentSubscriber.Get(0)}; } void ExpansionHubMotor::SetDistancePerCount(double perCount) { diff --git a/wpilibc/src/main/native/cpp/ExpansionHubPidConstants.cpp b/wpilibc/src/main/native/cpp/ExpansionHubPidConstants.cpp index 15d91f4758..94a30b6b6f 100644 --- a/wpilibc/src/main/native/cpp/ExpansionHubPidConstants.cpp +++ b/wpilibc/src/main/native/cpp/ExpansionHubPidConstants.cpp @@ -9,13 +9,13 @@ #include "wpi/system/Errors.hpp" #include "wpi/system/SystemServer.hpp" -using namespace frc; +using namespace wpi; ExpansionHubPidConstants::ExpansionHubPidConstants(int usbId, int channel, bool isVelocityPid) { auto systemServer = SystemServer::GetSystemServer(); - nt::PubSubOptions options; + wpi::nt::PubSubOptions options; options.sendAll = true; options.keepDuplicates = true; options.periodic = 0.005; diff --git a/wpilibc/src/main/native/cpp/ExpansionHubServo.cpp b/wpilibc/src/main/native/cpp/ExpansionHubServo.cpp index e84809d444..786de57e2c 100644 --- a/wpilibc/src/main/native/cpp/ExpansionHubServo.cpp +++ b/wpilibc/src/main/native/cpp/ExpansionHubServo.cpp @@ -7,7 +7,7 @@ #include "wpi/system/Errors.hpp" #include "wpi/system/SystemServer.hpp" -using namespace frc; +using namespace wpi; ExpansionHubServo::ExpansionHubServo(int usbId, int channel) : m_hub{usbId}, m_channel{channel} { @@ -22,7 +22,7 @@ ExpansionHubServo::ExpansionHubServo(int usbId, int channel) auto systemServer = SystemServer::GetSystemServer(); - nt::PubSubOptions options; + wpi::nt::PubSubOptions options; options.sendAll = true; options.keepDuplicates = true; options.periodic = 0.005; @@ -67,14 +67,14 @@ void ExpansionHubServo::Set(double value) { SetPulseWidth(rawValue); } -void ExpansionHubServo::SetAngle(units::degree_t angle) { +void ExpansionHubServo::SetAngle(wpi::units::degree_t angle) { angle = std::clamp(angle, m_minServoAngle, m_maxServoAngle); // NOLINTNEXTLINE(bugprone-integer-division) Set((angle - m_minServoAngle) / GetServoAngleRange()); } -void ExpansionHubServo::SetPulseWidth(units::microsecond_t pulseWidth) { +void ExpansionHubServo::SetPulseWidth(wpi::units::microsecond_t pulseWidth) { m_pulseWidthPublisher.Set(pulseWidth.to()); } @@ -82,20 +82,20 @@ void ExpansionHubServo::SetEnabled(bool enabled) { m_enabledPublisher.Set(enabled); } -void ExpansionHubServo::SetFramePeriod(units::microsecond_t framePeriod) { +void ExpansionHubServo::SetFramePeriod(wpi::units::microsecond_t framePeriod) { m_framePeriodPublisher.Set(framePeriod.to()); } -units::microsecond_t ExpansionHubServo::GetFullRangeScaleFactor() { +wpi::units::microsecond_t ExpansionHubServo::GetFullRangeScaleFactor() { return m_maxPwm - m_minPwm; } -units::degree_t ExpansionHubServo::GetServoAngleRange() { +wpi::units::degree_t ExpansionHubServo::GetServoAngleRange() { return m_maxServoAngle - m_minServoAngle; } -void ExpansionHubServo::SetPWMRange(units::microsecond_t minPwm, - units::microsecond_t maxPwm) { +void ExpansionHubServo::SetPWMRange(wpi::units::microsecond_t minPwm, + wpi::units::microsecond_t maxPwm) { if (maxPwm <= minPwm) { throw FRC_MakeError(err::ParameterOutOfRange, "Max PWM must be greater than Min PWM"); @@ -106,8 +106,8 @@ void ExpansionHubServo::SetPWMRange(units::microsecond_t minPwm, void ExpansionHubServo::SetReversed(bool reversed) {} -void ExpansionHubServo::SetAngleRange(units::degree_t minAngle, - units::degree_t maxAngle) { +void ExpansionHubServo::SetAngleRange(wpi::units::degree_t minAngle, + wpi::units::degree_t maxAngle) { if (maxAngle <= minAngle) { throw FRC_MakeError(err::ParameterOutOfRange, "Max angle must be greater than Min angle"); diff --git a/wpilibc/src/main/native/cpp/counter/Tachometer.cpp b/wpilibc/src/main/native/cpp/counter/Tachometer.cpp index 731ded1126..180121e967 100644 --- a/wpilibc/src/main/native/cpp/counter/Tachometer.cpp +++ b/wpilibc/src/main/native/cpp/counter/Tachometer.cpp @@ -12,19 +12,19 @@ #include "wpi/util/StackTrace.hpp" #include "wpi/util/sendable/SendableBuilder.hpp" -using namespace frc; +using namespace wpi; Tachometer::Tachometer(int channel, EdgeConfiguration configuration) : m_channel{channel} { int32_t status = 0; - std::string stackTrace = wpi::GetStackTrace(1); + std::string stackTrace = wpi::util::GetStackTrace(1); m_handle = HAL_InitializeCounter( channel, configuration == EdgeConfiguration::kRisingEdge, stackTrace.c_str(), &status); FRC_CheckErrorStatus(status, "{}", channel); HAL_ReportUsage("IO", channel, "Tachometer"); - wpi::SendableRegistry::Add(this, "Tachometer", channel); + wpi::util::SendableRegistry::Add(this, "Tachometer", channel); } void Tachometer::SetEdgeConfiguration(EdgeConfiguration configuration) { @@ -34,7 +34,7 @@ void Tachometer::SetEdgeConfiguration(EdgeConfiguration configuration) { FRC_CheckErrorStatus(status, "{}", m_channel); } -units::hertz_t Tachometer::GetFrequency() const { +wpi::units::hertz_t Tachometer::GetFrequency() const { auto period = GetPeriod(); if (period.value() == 0) { return 0_Hz; @@ -42,11 +42,11 @@ units::hertz_t Tachometer::GetFrequency() const { return 1 / period; } -units::second_t Tachometer::GetPeriod() const { +wpi::units::second_t Tachometer::GetPeriod() const { int32_t status = 0; double period = HAL_GetCounterPeriod(m_handle, &status); FRC_CheckErrorStatus(status, "Channel {}", m_channel); - return units::second_t{period}; + return wpi::units::second_t{period}; } int Tachometer::GetEdgesPerRevolution() const { @@ -56,7 +56,7 @@ void Tachometer::SetEdgesPerRevolution(int edges) { m_edgesPerRevolution = edges; } -units::turns_per_second_t Tachometer::GetRevolutionsPerSecond() const { +wpi::units::turns_per_second_t Tachometer::GetRevolutionsPerSecond() const { auto period = GetPeriod(); if (period.value() == 0) { return 0_tps; @@ -66,11 +66,11 @@ units::turns_per_second_t Tachometer::GetRevolutionsPerSecond() const { return 0_tps; } auto rotationHz = ((1.0 / edgesPerRevolution) / period); - return units::turns_per_second_t{rotationHz.value()}; + return wpi::units::turns_per_second_t{rotationHz.value()}; } -units::revolutions_per_minute_t Tachometer::GetRevolutionsPerMinute() const { - return units::revolutions_per_minute_t{GetRevolutionsPerSecond()}; +wpi::units::revolutions_per_minute_t Tachometer::GetRevolutionsPerMinute() const { + return wpi::units::revolutions_per_minute_t{GetRevolutionsPerSecond()}; } bool Tachometer::GetStopped() const { @@ -80,13 +80,13 @@ bool Tachometer::GetStopped() const { return stopped; } -void Tachometer::SetMaxPeriod(units::second_t maxPeriod) { +void Tachometer::SetMaxPeriod(wpi::units::second_t maxPeriod) { int32_t status = 0; HAL_SetCounterMaxPeriod(m_handle, maxPeriod.value(), &status); FRC_CheckErrorStatus(status, "Channel {}", m_channel); } -void Tachometer::InitSendable(wpi::SendableBuilder& builder) { +void Tachometer::InitSendable(wpi::util::SendableBuilder& builder) { builder.SetSmartDashboardType("Tachometer"); builder.AddDoubleProperty( "RPS", [&] { return GetRevolutionsPerSecond().value(); }, nullptr); diff --git a/wpilibc/src/main/native/cpp/counter/UpDownCounter.cpp b/wpilibc/src/main/native/cpp/counter/UpDownCounter.cpp index f996b4e32a..9aaef67aed 100644 --- a/wpilibc/src/main/native/cpp/counter/UpDownCounter.cpp +++ b/wpilibc/src/main/native/cpp/counter/UpDownCounter.cpp @@ -13,12 +13,12 @@ #include "wpi/util/StackTrace.hpp" #include "wpi/util/sendable/SendableBuilder.hpp" -using namespace frc; +using namespace wpi; UpDownCounter::UpDownCounter(int channel, EdgeConfiguration configuration) : m_channel{channel} { int32_t status = 0; - std::string stackTrace = wpi::GetStackTrace(1); + std::string stackTrace = wpi::util::GetStackTrace(1); m_handle = HAL_InitializeCounter( channel, configuration == EdgeConfiguration::kRisingEdge, stackTrace.c_str(), &status); @@ -27,7 +27,7 @@ UpDownCounter::UpDownCounter(int channel, EdgeConfiguration configuration) Reset(); HAL_ReportUsage("IO", channel, "UpDownCounter"); - wpi::SendableRegistry::Add(this, "UpDown Counter", channel); + wpi::util::SendableRegistry::Add(this, "UpDown Counter", channel); } int UpDownCounter::GetCount() const { @@ -50,7 +50,7 @@ void UpDownCounter::SetEdgeConfiguration(EdgeConfiguration configuration) { FRC_CheckErrorStatus(status, "{}", m_channel); } -void UpDownCounter::InitSendable(wpi::SendableBuilder& builder) { +void UpDownCounter::InitSendable(wpi::util::SendableBuilder& builder) { builder.SetSmartDashboardType("UpDown Counter"); builder.AddDoubleProperty("Count", [&] { return GetCount(); }, nullptr); } diff --git a/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp b/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp index 0d3ed58b49..0630209fdc 100644 --- a/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp +++ b/wpilibc/src/main/native/cpp/drive/DifferentialDrive.cpp @@ -15,7 +15,7 @@ #include "wpi/util/sendable/SendableBuilder.hpp" #include "wpi/util/sendable/SendableRegistry.hpp" -using namespace frc; +using namespace wpi; WPI_IGNORE_DEPRECATED @@ -23,8 +23,8 @@ DifferentialDrive::DifferentialDrive(MotorController& leftMotor, MotorController& rightMotor) : DifferentialDrive{[&](double output) { leftMotor.Set(output); }, [&](double output) { rightMotor.Set(output); }} { - wpi::SendableRegistry::AddChild(this, &leftMotor); - wpi::SendableRegistry::AddChild(this, &rightMotor); + wpi::util::SendableRegistry::AddChild(this, &leftMotor); + wpi::util::SendableRegistry::AddChild(this, &rightMotor); } WPI_UNIGNORE_DEPRECATED @@ -34,7 +34,7 @@ DifferentialDrive::DifferentialDrive(std::function leftMotor, : m_leftMotor{std::move(leftMotor)}, m_rightMotor{std::move(rightMotor)} { static int instances = 0; ++instances; - wpi::SendableRegistry::Add(this, "DifferentialDrive", instances); + wpi::util::SendableRegistry::Add(this, "DifferentialDrive", instances); } void DifferentialDrive::ArcadeDrive(double xSpeed, double zRotation, @@ -45,8 +45,8 @@ void DifferentialDrive::ArcadeDrive(double xSpeed, double zRotation, reported = true; } - xSpeed = ApplyDeadband(xSpeed, m_deadband); - zRotation = ApplyDeadband(zRotation, m_deadband); + xSpeed = wpi::math::ApplyDeadband(xSpeed, m_deadband); + zRotation = wpi::math::ApplyDeadband(zRotation, m_deadband); auto [left, right] = ArcadeDriveIK(xSpeed, zRotation, squareInputs); @@ -67,8 +67,8 @@ void DifferentialDrive::CurvatureDrive(double xSpeed, double zRotation, reported = true; } - xSpeed = ApplyDeadband(xSpeed, m_deadband); - zRotation = ApplyDeadband(zRotation, m_deadband); + xSpeed = wpi::math::ApplyDeadband(xSpeed, m_deadband); + zRotation = wpi::math::ApplyDeadband(zRotation, m_deadband); auto [left, right] = CurvatureDriveIK(xSpeed, zRotation, allowTurnInPlace); @@ -89,8 +89,8 @@ void DifferentialDrive::TankDrive(double leftSpeed, double rightSpeed, reported = true; } - leftSpeed = ApplyDeadband(leftSpeed, m_deadband); - rightSpeed = ApplyDeadband(rightSpeed, m_deadband); + leftSpeed = wpi::math::ApplyDeadband(leftSpeed, m_deadband); + rightSpeed = wpi::math::ApplyDeadband(rightSpeed, m_deadband); auto [left, right] = TankDriveIK(leftSpeed, rightSpeed, squareInputs); @@ -111,8 +111,8 @@ DifferentialDrive::WheelSpeeds DifferentialDrive::ArcadeDriveIK( // Square the inputs (while preserving the sign) to increase fine control // while permitting full power. if (squareInputs) { - xSpeed = CopyDirectionPow(xSpeed, 2); - zRotation = CopyDirectionPow(zRotation, 2); + xSpeed = wpi::math::CopyDirectionPow(xSpeed, 2); + zRotation = wpi::math::CopyDirectionPow(zRotation, 2); } double leftSpeed = xSpeed - zRotation; @@ -166,8 +166,8 @@ DifferentialDrive::WheelSpeeds DifferentialDrive::TankDriveIK( // Square the inputs (while preserving the sign) to increase fine control // while permitting full power. if (squareInputs) { - leftSpeed = CopyDirectionPow(leftSpeed, 2); - rightSpeed = CopyDirectionPow(rightSpeed, 2); + leftSpeed = wpi::math::CopyDirectionPow(leftSpeed, 2); + rightSpeed = wpi::math::CopyDirectionPow(rightSpeed, 2); } return {leftSpeed, rightSpeed}; @@ -187,7 +187,7 @@ std::string DifferentialDrive::GetDescription() const { return "DifferentialDrive"; } -void DifferentialDrive::InitSendable(wpi::SendableBuilder& builder) { +void DifferentialDrive::InitSendable(wpi::util::SendableBuilder& builder) { builder.SetSmartDashboardType("DifferentialDrive"); builder.SetActuator(true); builder.AddDoubleProperty( diff --git a/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp b/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp index e5ea2f5810..93711c60a0 100644 --- a/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp +++ b/wpilibc/src/main/native/cpp/drive/MecanumDrive.cpp @@ -15,7 +15,7 @@ #include "wpi/util/sendable/SendableBuilder.hpp" #include "wpi/util/sendable/SendableRegistry.hpp" -using namespace frc; +using namespace wpi; WPI_IGNORE_DEPRECATED @@ -27,10 +27,10 @@ MecanumDrive::MecanumDrive(MotorController& frontLeftMotor, [&](double output) { rearLeftMotor.Set(output); }, [&](double output) { frontRightMotor.Set(output); }, [&](double output) { rearRightMotor.Set(output); }} { - wpi::SendableRegistry::AddChild(this, &frontLeftMotor); - wpi::SendableRegistry::AddChild(this, &rearLeftMotor); - wpi::SendableRegistry::AddChild(this, &frontRightMotor); - wpi::SendableRegistry::AddChild(this, &rearRightMotor); + wpi::util::SendableRegistry::AddChild(this, &frontLeftMotor); + wpi::util::SendableRegistry::AddChild(this, &rearLeftMotor); + wpi::util::SendableRegistry::AddChild(this, &frontRightMotor); + wpi::util::SendableRegistry::AddChild(this, &rearRightMotor); } WPI_UNIGNORE_DEPRECATED @@ -45,18 +45,18 @@ MecanumDrive::MecanumDrive(std::function frontLeftMotor, m_rearRightMotor{std::move(rearRightMotor)} { static int instances = 0; ++instances; - wpi::SendableRegistry::Add(this, "MecanumDrive", instances); + wpi::util::SendableRegistry::Add(this, "MecanumDrive", instances); } void MecanumDrive::DriveCartesian(double xSpeed, double ySpeed, - double zRotation, Rotation2d gyroAngle) { + double zRotation, wpi::math::Rotation2d gyroAngle) { if (!reported) { HAL_ReportUsage("RobotDrive", "MecanumCartesian"); reported = true; } - xSpeed = ApplyDeadband(xSpeed, m_deadband); - ySpeed = ApplyDeadband(ySpeed, m_deadband); + xSpeed = wpi::math::ApplyDeadband(xSpeed, m_deadband); + ySpeed = wpi::math::ApplyDeadband(ySpeed, m_deadband); auto [frontLeft, frontRight, rearLeft, rearRight] = DriveCartesianIK(xSpeed, ySpeed, zRotation, gyroAngle); @@ -74,7 +74,7 @@ void MecanumDrive::DriveCartesian(double xSpeed, double ySpeed, Feed(); } -void MecanumDrive::DrivePolar(double magnitude, Rotation2d angle, +void MecanumDrive::DrivePolar(double magnitude, wpi::math::Rotation2d angle, double zRotation) { if (!reported) { HAL_ReportUsage("RobotDrive", "MecanumPolar"); @@ -102,13 +102,13 @@ void MecanumDrive::StopMotor() { MecanumDrive::WheelSpeeds MecanumDrive::DriveCartesianIK(double xSpeed, double ySpeed, double zRotation, - Rotation2d gyroAngle) { + wpi::math::Rotation2d gyroAngle) { xSpeed = std::clamp(xSpeed, -1.0, 1.0); ySpeed = std::clamp(ySpeed, -1.0, 1.0); // Compensate for gyro angle. auto input = - Translation2d{units::meter_t{xSpeed}, units::meter_t{ySpeed}}.RotateBy( + wpi::math::Translation2d{wpi::units::meter_t{xSpeed}, wpi::units::meter_t{ySpeed}}.RotateBy( -gyroAngle); double wheelSpeeds[4]; @@ -127,7 +127,7 @@ std::string MecanumDrive::GetDescription() const { return "MecanumDrive"; } -void MecanumDrive::InitSendable(wpi::SendableBuilder& builder) { +void MecanumDrive::InitSendable(wpi::util::SendableBuilder& builder) { builder.SetSmartDashboardType("MecanumDrive"); builder.SetActuator(true); builder.AddDoubleProperty( diff --git a/wpilibc/src/main/native/cpp/drive/RobotDriveBase.cpp b/wpilibc/src/main/native/cpp/drive/RobotDriveBase.cpp index 982b4687cc..577a2790ce 100644 --- a/wpilibc/src/main/native/cpp/drive/RobotDriveBase.cpp +++ b/wpilibc/src/main/native/cpp/drive/RobotDriveBase.cpp @@ -10,7 +10,7 @@ #include "wpi/hardware/motor/MotorController.hpp" -using namespace frc; +using namespace wpi; RobotDriveBase::RobotDriveBase() { SetSafetyEnabled(true); diff --git a/wpilibc/src/main/native/cpp/driverstation/DSControlWord.cpp b/wpilibc/src/main/native/cpp/driverstation/DSControlWord.cpp index cf9d9f5c4d..35a2de8be4 100644 --- a/wpilibc/src/main/native/cpp/driverstation/DSControlWord.cpp +++ b/wpilibc/src/main/native/cpp/driverstation/DSControlWord.cpp @@ -6,7 +6,7 @@ #include "wpi/hal/DriverStation.h" -using namespace frc; +using namespace wpi; DSControlWord::DSControlWord() { HAL_GetControlWord(&m_controlWord); diff --git a/wpilibc/src/main/native/cpp/driverstation/DriverStation.cpp b/wpilibc/src/main/native/cpp/driverstation/DriverStation.cpp index 20cb4d3208..6dc93e0607 100644 --- a/wpilibc/src/main/native/cpp/driverstation/DriverStation.cpp +++ b/wpilibc/src/main/native/cpp/driverstation/DriverStation.cpp @@ -33,7 +33,7 @@ #include "wpi/util/mutex.hpp" #include "wpi/util/timestamp.h" -using namespace frc; +using namespace wpi; static constexpr int availableToCount(uint64_t available) { return 64 - std::countl_zero(available); @@ -45,10 +45,10 @@ namespace { template class MatchDataSenderEntry { public: - MatchDataSenderEntry(const std::shared_ptr& table, + MatchDataSenderEntry(const std::shared_ptr& table, std::string_view key, typename Topic::ParamType initialVal, - wpi::json topicProperties = wpi::json::object()) + wpi::util::json topicProperties = wpi::util::json::object()) : publisher{Topic{table->GetTopic(key)}.PublishEx(Topic::kTypeString, topicProperties)}, prevVal{initialVal} { @@ -70,22 +70,22 @@ class MatchDataSenderEntry { static constexpr std::string_view kSmartDashboardType = "FMSInfo"; struct MatchDataSender { - std::shared_ptr table = - nt::NetworkTableInstance::GetDefault().GetTable("FMSInfo"); - MatchDataSenderEntry typeMetaData{ + std::shared_ptr table = + wpi::nt::NetworkTableInstance::GetDefault().GetTable("FMSInfo"); + MatchDataSenderEntry typeMetaData{ table, ".type", kSmartDashboardType, {{"SmartDashboard", kSmartDashboardType}}}; - MatchDataSenderEntry gameSpecificMessage{ + MatchDataSenderEntry gameSpecificMessage{ table, "GameSpecificMessage", ""}; - MatchDataSenderEntry eventName{table, "EventName", ""}; - MatchDataSenderEntry matchNumber{table, "MatchNumber", 0}; - MatchDataSenderEntry replayNumber{table, "ReplayNumber", 0}; - MatchDataSenderEntry matchType{table, "MatchType", 0}; - MatchDataSenderEntry alliance{table, "IsRedAlliance", true}; - MatchDataSenderEntry station{table, "StationNumber", 1}; - MatchDataSenderEntry controlWord{table, "FMSControlData", + MatchDataSenderEntry eventName{table, "EventName", ""}; + MatchDataSenderEntry matchNumber{table, "MatchNumber", 0}; + MatchDataSenderEntry replayNumber{table, "ReplayNumber", 0}; + MatchDataSenderEntry matchType{table, "MatchType", 0}; + MatchDataSenderEntry alliance{table, "IsRedAlliance", true}; + MatchDataSenderEntry station{table, "StationNumber", 1}; + MatchDataSenderEntry controlWord{table, "FMSControlData", 0}; }; @@ -129,12 +129,12 @@ struct Instance { Instance(); ~Instance(); - wpi::EventVector refreshEvents; + wpi::util::EventVector refreshEvents; MatchDataSender matchDataSender; std::atomic dataLogSender{nullptr}; // Joystick button rising/falling edge flags - wpi::mutex buttonEdgeMutex; + wpi::util::mutex buttonEdgeMutex; std::array previousButtonStates; std::array joystickButtonsPressed; @@ -148,7 +148,7 @@ struct Instance { bool userInTeleop = false; bool userInTest = false; - units::second_t nextMessageTime = 0_s; + wpi::units::second_t nextMessageTime = 0_s; }; } // namespace @@ -624,9 +624,9 @@ std::optional DriverStation::GetLocation() { } } -units::second_t DriverStation::GetMatchTime() { +wpi::units::second_t DriverStation::GetMatchTime() { int32_t status = 0; - return units::second_t{HAL_GetMatchTime(&status)}; + return wpi::units::second_t{HAL_GetMatchTime(&status)}; } double DriverStation::GetBatteryVoltage() { @@ -670,7 +670,7 @@ void DriverStation::RefreshData() { SendMatchData(); if (auto sender = inst.dataLogSender.load()) { - sender->Send(wpi::Now()); + sender->Send(wpi::util::Now()); } } @@ -706,7 +706,7 @@ void DriverStation::StartDataLog(wpi::log::DataLog& log, bool logJoysticks) { if (oldSender) { delete newSender; // already had a sender } else { - newSender->Init(log, logJoysticks, wpi::Now()); + newSender->Init(log, logJoysticks, wpi::util::Now()); } } diff --git a/wpilibc/src/main/native/cpp/driverstation/Gamepad.cpp b/wpilibc/src/main/native/cpp/driverstation/Gamepad.cpp index 3289642b63..cc808f9694 100644 --- a/wpilibc/src/main/native/cpp/driverstation/Gamepad.cpp +++ b/wpilibc/src/main/native/cpp/driverstation/Gamepad.cpp @@ -8,7 +8,7 @@ #include "wpi/hal/UsageReporting.h" #include "wpi/util/sendable/SendableBuilder.hpp" -using namespace frc; +using namespace wpi; Gamepad::Gamepad(int port) : GenericHID(port) { HAL_ReportUsage("HID", port, "Gamepad"); @@ -484,7 +484,7 @@ bool Gamepad::GetButtonForSendable(int button) const { .value_or(false); } -void Gamepad::InitSendable(wpi::SendableBuilder& builder) { +void Gamepad::InitSendable(wpi::util::SendableBuilder& builder) { builder.SetSmartDashboardType("HID"); builder.PublishConstString("ControllerType", "Gamepad"); builder.AddDoubleProperty( diff --git a/wpilibc/src/main/native/cpp/driverstation/GenericHID.cpp b/wpilibc/src/main/native/cpp/driverstation/GenericHID.cpp index 5e212f68fb..a9f497f2e0 100644 --- a/wpilibc/src/main/native/cpp/driverstation/GenericHID.cpp +++ b/wpilibc/src/main/native/cpp/driverstation/GenericHID.cpp @@ -11,7 +11,7 @@ #include "wpi/hal/DriverStation.h" #include "wpi/system/Errors.hpp" -using namespace frc; +using namespace wpi; GenericHID::GenericHID(int port) { if (port < 0 || port >= DriverStation::kJoystickPorts) { diff --git a/wpilibc/src/main/native/cpp/driverstation/Joystick.cpp b/wpilibc/src/main/native/cpp/driverstation/Joystick.cpp index 5eaddf8269..1c21c3c3f9 100644 --- a/wpilibc/src/main/native/cpp/driverstation/Joystick.cpp +++ b/wpilibc/src/main/native/cpp/driverstation/Joystick.cpp @@ -9,7 +9,7 @@ #include "wpi/event/BooleanEvent.hpp" #include "wpi/hal/UsageReporting.h" -using namespace frc; +using namespace wpi; Joystick::Joystick(int port) : GenericHID(port) { m_axes[Axis::kX] = kDefaultXChannel; @@ -117,7 +117,7 @@ double Joystick::GetMagnitude() const { return std::hypot(GetX(), GetY()); } -units::radian_t Joystick::GetDirection() const { +wpi::units::radian_t Joystick::GetDirection() const { // https://docs.wpilib.org/en/stable/docs/software/basic-programming/coordinate-system.html#joystick-and-controller-coordinate-system // A positive rotation around the X axis moves the joystick right, and a // positive rotation around the Y axis moves the joystick backward. When @@ -126,5 +126,5 @@ units::radian_t Joystick::GetDirection() const { // // It's rotated 90 degrees CCW (y is negated and the arguments are reversed) // so that 0 radians is forward. - return units::radian_t{std::atan2(GetX(), -GetY())}; + return wpi::units::radian_t{std::atan2(GetX(), -GetY())}; } diff --git a/wpilibc/src/main/native/cpp/event/BooleanEvent.cpp b/wpilibc/src/main/native/cpp/event/BooleanEvent.cpp index 8d85a34429..35f9f457b7 100644 --- a/wpilibc/src/main/native/cpp/event/BooleanEvent.cpp +++ b/wpilibc/src/main/native/cpp/event/BooleanEvent.cpp @@ -7,7 +7,7 @@ #include #include -using namespace frc; +using namespace wpi; BooleanEvent::BooleanEvent(EventLoop* loop, std::function condition) : m_loop(loop), m_signal(std::move(condition)) { @@ -67,10 +67,10 @@ BooleanEvent BooleanEvent::Falling() { }); } -BooleanEvent BooleanEvent::Debounce(units::second_t debounceTime, - frc::Debouncer::DebounceType type) { +BooleanEvent BooleanEvent::Debounce(wpi::units::second_t debounceTime, + wpi::math::Debouncer::DebounceType type) { return BooleanEvent( this->m_loop, - [debouncer = frc::Debouncer(debounceTime, type), + [debouncer = wpi::math::Debouncer(debounceTime, type), state = m_state]() mutable { return debouncer.Calculate(*state); }); } diff --git a/wpilibc/src/main/native/cpp/event/EventLoop.cpp b/wpilibc/src/main/native/cpp/event/EventLoop.cpp index f3c445eaae..03d31c1353 100644 --- a/wpilibc/src/main/native/cpp/event/EventLoop.cpp +++ b/wpilibc/src/main/native/cpp/event/EventLoop.cpp @@ -8,7 +8,7 @@ #include "wpi/system/Errors.hpp" -using namespace frc; +using namespace wpi; namespace { struct RunningSetter { @@ -22,7 +22,7 @@ struct RunningSetter { EventLoop::EventLoop() {} -void EventLoop::Bind(wpi::unique_function action) { +void EventLoop::Bind(wpi::util::unique_function action) { if (m_running) { throw FRC_MakeError(err::Error, "Cannot bind EventLoop while it is running"); @@ -32,7 +32,7 @@ void EventLoop::Bind(wpi::unique_function action) { void EventLoop::Poll() { RunningSetter runSetter{m_running}; - for (wpi::unique_function& action : m_bindings) { + for (wpi::util::unique_function& action : m_bindings) { action(); } } diff --git a/wpilibc/src/main/native/cpp/event/NetworkBooleanEvent.cpp b/wpilibc/src/main/native/cpp/event/NetworkBooleanEvent.cpp index 47b6129648..e11d2124da 100644 --- a/wpilibc/src/main/native/cpp/event/NetworkBooleanEvent.cpp +++ b/wpilibc/src/main/native/cpp/event/NetworkBooleanEvent.cpp @@ -11,33 +11,33 @@ #include "wpi/nt/NetworkTable.hpp" #include "wpi/nt/NetworkTableInstance.hpp" -using namespace frc; +using namespace wpi; NetworkBooleanEvent::NetworkBooleanEvent(EventLoop* loop, - nt::BooleanTopic topic) + wpi::nt::BooleanTopic topic) : NetworkBooleanEvent{loop, topic.Subscribe(false)} {} NetworkBooleanEvent::NetworkBooleanEvent(EventLoop* loop, - nt::BooleanSubscriber sub) + wpi::nt::BooleanSubscriber sub) : BooleanEvent{ loop, - [sub = std::make_shared(std::move(sub))] { + [sub = std::make_shared(std::move(sub))] { return sub->GetTopic().GetInstance().IsConnected() && sub->Get(); }} {} NetworkBooleanEvent::NetworkBooleanEvent( - EventLoop* loop, std::shared_ptr table, + EventLoop* loop, std::shared_ptr table, std::string_view topicName) : NetworkBooleanEvent{loop, table->GetBooleanTopic(topicName)} {} NetworkBooleanEvent::NetworkBooleanEvent(EventLoop* loop, std::string_view tableName, std::string_view topicName) - : NetworkBooleanEvent{loop, nt::NetworkTableInstance::GetDefault(), + : NetworkBooleanEvent{loop, wpi::nt::NetworkTableInstance::GetDefault(), tableName, topicName} {} NetworkBooleanEvent::NetworkBooleanEvent(EventLoop* loop, - nt::NetworkTableInstance inst, + wpi::nt::NetworkTableInstance inst, std::string_view tableName, std::string_view topicName) : NetworkBooleanEvent{loop, inst.GetTable(tableName), topicName} {} diff --git a/wpilibc/src/main/native/cpp/hardware/accelerometer/ADXL345_I2C.cpp b/wpilibc/src/main/native/cpp/hardware/accelerometer/ADXL345_I2C.cpp index 41fa7b3f83..e4a12a94c5 100644 --- a/wpilibc/src/main/native/cpp/hardware/accelerometer/ADXL345_I2C.cpp +++ b/wpilibc/src/main/native/cpp/hardware/accelerometer/ADXL345_I2C.cpp @@ -9,18 +9,18 @@ #include "wpi/nt/NTSendableBuilder.hpp" #include "wpi/util/sendable/SendableRegistry.hpp" -using namespace frc; +using namespace wpi; ADXL345_I2C::ADXL345_I2C(I2C::Port port, Range range, int deviceAddress) : m_i2c(port, deviceAddress), m_simDevice("Accel:ADXL345_I2C", port, deviceAddress) { if (m_simDevice) { - m_simRange = m_simDevice.CreateEnumDouble("range", hal::SimDevice::kOutput, + m_simRange = m_simDevice.CreateEnumDouble("range", wpi::hal::SimDevice::kOutput, {"2G", "4G", "8G", "16G"}, {2.0, 4.0, 8.0, 16.0}, 0); - m_simX = m_simDevice.CreateDouble("x", hal::SimDevice::kInput, 0.0); - m_simY = m_simDevice.CreateDouble("y", hal::SimDevice::kInput, 0.0); - m_simZ = m_simDevice.CreateDouble("z", hal::SimDevice::kInput, 0.0); + m_simX = m_simDevice.CreateDouble("x", wpi::hal::SimDevice::kInput, 0.0); + m_simY = m_simDevice.CreateDouble("y", wpi::hal::SimDevice::kInput, 0.0); + m_simZ = m_simDevice.CreateDouble("z", wpi::hal::SimDevice::kInput, 0.0); } // Turn on the measurements m_i2c.Write(kPowerCtlRegister, kPowerCtl_Measure); @@ -31,7 +31,7 @@ ADXL345_I2C::ADXL345_I2C(I2C::Port port, Range range, int deviceAddress) fmt::format("I2C[{}][{}]", static_cast(port), deviceAddress), "ADXL345"); - wpi::SendableRegistry::Add(this, "ADXL345_I2C", port); + wpi::util::SendableRegistry::Add(this, "ADXL345_I2C", port); } I2C::Port ADXL345_I2C::GetI2CPort() const { @@ -93,12 +93,12 @@ ADXL345_I2C::AllAxes ADXL345_I2C::GetAccelerations() { return data; } -void ADXL345_I2C::InitSendable(nt::NTSendableBuilder& builder) { +void ADXL345_I2C::InitSendable(wpi::nt::NTSendableBuilder& builder) { builder.SetSmartDashboardType("3AxisAccelerometer"); builder.SetUpdateTable( - [this, x = nt::DoubleTopic{builder.GetTopic("X")}.Publish(), - y = nt::DoubleTopic{builder.GetTopic("Y")}.Publish(), - z = nt::DoubleTopic{builder.GetTopic("Z")}.Publish()]() mutable { + [this, x = wpi::nt::DoubleTopic{builder.GetTopic("X")}.Publish(), + y = wpi::nt::DoubleTopic{builder.GetTopic("Y")}.Publish(), + z = wpi::nt::DoubleTopic{builder.GetTopic("Z")}.Publish()]() mutable { auto data = GetAccelerations(); x.Set(data.XAxis); y.Set(data.YAxis); diff --git a/wpilibc/src/main/native/cpp/hardware/accelerometer/AnalogAccelerometer.cpp b/wpilibc/src/main/native/cpp/hardware/accelerometer/AnalogAccelerometer.cpp index 3e6ed317c7..e350913b25 100644 --- a/wpilibc/src/main/native/cpp/hardware/accelerometer/AnalogAccelerometer.cpp +++ b/wpilibc/src/main/native/cpp/hardware/accelerometer/AnalogAccelerometer.cpp @@ -10,15 +10,15 @@ #include "wpi/util/sendable/SendableBuilder.hpp" #include "wpi/util/sendable/SendableRegistry.hpp" -using namespace frc; +using namespace wpi; AnalogAccelerometer::AnalogAccelerometer(int channel) : AnalogAccelerometer(std::make_shared(channel)) { - wpi::SendableRegistry::AddChild(this, m_analogInput.get()); + wpi::util::SendableRegistry::AddChild(this, m_analogInput.get()); } AnalogAccelerometer::AnalogAccelerometer(AnalogInput* channel) - : m_analogInput(channel, wpi::NullDeleter()) { + : m_analogInput(channel, wpi::util::NullDeleter()) { if (!channel) { throw FRC_MakeError(err::NullParameter, "channel"); } @@ -45,7 +45,7 @@ void AnalogAccelerometer::SetZero(double zero) { m_zeroGVoltage = zero; } -void AnalogAccelerometer::InitSendable(wpi::SendableBuilder& builder) { +void AnalogAccelerometer::InitSendable(wpi::util::SendableBuilder& builder) { builder.SetSmartDashboardType("Accelerometer"); builder.AddDoubleProperty( "Value", [=, this] { return GetAcceleration(); }, nullptr); @@ -54,6 +54,6 @@ void AnalogAccelerometer::InitSendable(wpi::SendableBuilder& builder) { void AnalogAccelerometer::InitAccelerometer() { HAL_ReportUsage("IO", m_analogInput->GetChannel(), "Accelerometer"); - wpi::SendableRegistry::Add(this, "Accelerometer", + wpi::util::SendableRegistry::Add(this, "Accelerometer", m_analogInput->GetChannel()); } diff --git a/wpilibc/src/main/native/cpp/hardware/bus/CAN.cpp b/wpilibc/src/main/native/cpp/hardware/bus/CAN.cpp index 0855298f9e..ab84e8831a 100644 --- a/wpilibc/src/main/native/cpp/hardware/bus/CAN.cpp +++ b/wpilibc/src/main/native/cpp/hardware/bus/CAN.cpp @@ -12,7 +12,7 @@ #include "wpi/hal/UsageReporting.h" #include "wpi/system/Errors.hpp" -using namespace frc; +using namespace wpi; CAN::CAN(int busId, int deviceId) : CAN{busId, deviceId, kTeamManufacturer, kTeamDeviceType} {} diff --git a/wpilibc/src/main/native/cpp/hardware/bus/I2C.cpp b/wpilibc/src/main/native/cpp/hardware/bus/I2C.cpp index ad09146dca..9c10fb2bb5 100644 --- a/wpilibc/src/main/native/cpp/hardware/bus/I2C.cpp +++ b/wpilibc/src/main/native/cpp/hardware/bus/I2C.cpp @@ -10,7 +10,7 @@ #include "wpi/hal/UsageReporting.h" #include "wpi/system/Errors.hpp" -using namespace frc; +using namespace wpi; I2C::I2C(Port port, int deviceAddress) : m_port(static_cast(port)), m_deviceAddress(deviceAddress) { diff --git a/wpilibc/src/main/native/cpp/hardware/bus/SerialPort.cpp b/wpilibc/src/main/native/cpp/hardware/bus/SerialPort.cpp index 41077a3f4d..33c3b8b46d 100644 --- a/wpilibc/src/main/native/cpp/hardware/bus/SerialPort.cpp +++ b/wpilibc/src/main/native/cpp/hardware/bus/SerialPort.cpp @@ -10,7 +10,7 @@ #include "wpi/hal/UsageReporting.h" #include "wpi/system/Errors.hpp" -using namespace frc; +using namespace wpi; SerialPort::SerialPort(int baudRate, Port port, int dataBits, SerialPort::Parity parity, @@ -116,7 +116,7 @@ int SerialPort::Write(std::string_view buffer) { return retVal; } -void SerialPort::SetTimeout(units::second_t timeout) { +void SerialPort::SetTimeout(wpi::units::second_t timeout) { int32_t status = 0; HAL_SetSerialTimeout(m_portHandle, timeout.value(), &status); FRC_CheckErrorStatus(status, "SetTimeout"); diff --git a/wpilibc/src/main/native/cpp/hardware/discrete/AnalogInput.cpp b/wpilibc/src/main/native/cpp/hardware/discrete/AnalogInput.cpp index 718125159a..88672b7195 100644 --- a/wpilibc/src/main/native/cpp/hardware/discrete/AnalogInput.cpp +++ b/wpilibc/src/main/native/cpp/hardware/discrete/AnalogInput.cpp @@ -17,7 +17,7 @@ #include "wpi/util/sendable/SendableBuilder.hpp" #include "wpi/util/sendable/SendableRegistry.hpp" -using namespace frc; +using namespace wpi; AnalogInput::AnalogInput(int channel) { if (!SensorUtil::CheckAnalogInputChannel(channel)) { @@ -26,13 +26,13 @@ AnalogInput::AnalogInput(int channel) { m_channel = channel; int32_t status = 0; - std::string stackTrace = wpi::GetStackTrace(1); + std::string stackTrace = wpi::util::GetStackTrace(1); m_port = HAL_InitializeAnalogInputPort(channel, stackTrace.c_str(), &status); FRC_CheckErrorStatus(status, "Channel {}", channel); HAL_ReportUsage("IO", channel, "AnalogInput"); - wpi::SendableRegistry::Add(this, "AnalogInput", channel); + wpi::util::SendableRegistry::Add(this, "AnalogInput", channel); } int AnalogInput::GetValue() const { @@ -124,7 +124,7 @@ void AnalogInput::SetSimDevice(HAL_SimDeviceHandle device) { HAL_SetAnalogInputSimDevice(m_port, device); } -void AnalogInput::InitSendable(wpi::SendableBuilder& builder) { +void AnalogInput::InitSendable(wpi::util::SendableBuilder& builder) { builder.SetSmartDashboardType("Analog Input"); builder.AddDoubleProperty( "Value", [=, this] { return GetAverageVoltage(); }, nullptr); diff --git a/wpilibc/src/main/native/cpp/hardware/discrete/DigitalInput.cpp b/wpilibc/src/main/native/cpp/hardware/discrete/DigitalInput.cpp index e4f00eed7b..8e4c0554a3 100644 --- a/wpilibc/src/main/native/cpp/hardware/discrete/DigitalInput.cpp +++ b/wpilibc/src/main/native/cpp/hardware/discrete/DigitalInput.cpp @@ -16,7 +16,7 @@ #include "wpi/util/sendable/SendableBuilder.hpp" #include "wpi/util/sendable/SendableRegistry.hpp" -using namespace frc; +using namespace wpi; DigitalInput::DigitalInput(int channel) { if (!SensorUtil::CheckDigitalChannel(channel)) { @@ -25,12 +25,12 @@ DigitalInput::DigitalInput(int channel) { m_channel = channel; int32_t status = 0; - std::string stackTrace = wpi::GetStackTrace(1); + std::string stackTrace = wpi::util::GetStackTrace(1); m_handle = HAL_InitializeDIOPort(channel, true, stackTrace.c_str(), &status); FRC_CheckErrorStatus(status, "Channel {}", channel); HAL_ReportUsage("IO", channel, "DigitalInput"); - wpi::SendableRegistry::Add(this, "DigitalInput", channel); + wpi::util::SendableRegistry::Add(this, "DigitalInput", channel); } bool DigitalInput::Get() const { @@ -48,7 +48,7 @@ int DigitalInput::GetChannel() const { return m_channel; } -void DigitalInput::InitSendable(wpi::SendableBuilder& builder) { +void DigitalInput::InitSendable(wpi::util::SendableBuilder& builder) { builder.SetSmartDashboardType("Digital Input"); builder.AddBooleanProperty("Value", [=, this] { return Get(); }, nullptr); } diff --git a/wpilibc/src/main/native/cpp/hardware/discrete/DigitalOutput.cpp b/wpilibc/src/main/native/cpp/hardware/discrete/DigitalOutput.cpp index d8549b3241..40725aeaf1 100644 --- a/wpilibc/src/main/native/cpp/hardware/discrete/DigitalOutput.cpp +++ b/wpilibc/src/main/native/cpp/hardware/discrete/DigitalOutput.cpp @@ -16,7 +16,7 @@ #include "wpi/util/sendable/SendableBuilder.hpp" #include "wpi/util/sendable/SendableRegistry.hpp" -using namespace frc; +using namespace wpi; DigitalOutput::DigitalOutput(int channel) { m_pwmGenerator = HAL_kInvalidHandle; @@ -26,12 +26,12 @@ DigitalOutput::DigitalOutput(int channel) { m_channel = channel; int32_t status = 0; - std::string stackTrace = wpi::GetStackTrace(1); + std::string stackTrace = wpi::util::GetStackTrace(1); m_handle = HAL_InitializeDIOPort(channel, false, stackTrace.c_str(), &status); FRC_CheckErrorStatus(status, "Channel {}", channel); HAL_ReportUsage("IO", channel, "DigitalOutput"); - wpi::SendableRegistry::Add(this, "DigitalOutput", channel); + wpi::util::SendableRegistry::Add(this, "DigitalOutput", channel); } DigitalOutput::~DigitalOutput() { @@ -62,7 +62,7 @@ int DigitalOutput::GetChannel() const { return m_channel; } -void DigitalOutput::Pulse(units::second_t pulseLength) { +void DigitalOutput::Pulse(wpi::units::second_t pulseLength) { int32_t status = 0; HAL_Pulse(m_handle, pulseLength.value(), &status); FRC_CheckErrorStatus(status, "Channel {}", m_channel); @@ -142,7 +142,7 @@ void DigitalOutput::SetSimDevice(HAL_SimDeviceHandle device) { HAL_SetDIOSimDevice(m_handle, device); } -void DigitalOutput::InitSendable(wpi::SendableBuilder& builder) { +void DigitalOutput::InitSendable(wpi::util::SendableBuilder& builder) { builder.SetSmartDashboardType("Digital Output"); builder.AddBooleanProperty( "Value", [=, this] { return Get(); }, diff --git a/wpilibc/src/main/native/cpp/hardware/discrete/PWM.cpp b/wpilibc/src/main/native/cpp/hardware/discrete/PWM.cpp index 33cfa1d9f4..eb589eb98b 100644 --- a/wpilibc/src/main/native/cpp/hardware/discrete/PWM.cpp +++ b/wpilibc/src/main/native/cpp/hardware/discrete/PWM.cpp @@ -16,14 +16,14 @@ #include "wpi/util/sendable/SendableBuilder.hpp" #include "wpi/util/sendable/SendableRegistry.hpp" -using namespace frc; +using namespace wpi; PWM::PWM(int channel, bool registerSendable) { if (!SensorUtil::CheckPWMChannel(channel)) { throw FRC_MakeError(err::ChannelIndexOutOfRange, "Channel {}", channel); } - auto stack = wpi::GetStackTrace(1); + auto stack = wpi::util::GetStackTrace(1); int32_t status = 0; m_handle = HAL_InitializePWMPort(channel, stack.c_str(), &status); FRC_CheckErrorStatus(status, "Channel {}", channel); @@ -34,7 +34,7 @@ PWM::PWM(int channel, bool registerSendable) { HAL_ReportUsage("IO", channel, "PWM"); if (registerSendable) { - wpi::SendableRegistry::Add(this, "PWM", channel); + wpi::util::SendableRegistry::Add(this, "PWM", channel); } } @@ -44,18 +44,18 @@ PWM::~PWM() { } } -void PWM::SetPulseTime(units::microsecond_t time) { +void PWM::SetPulseTime(wpi::units::microsecond_t time) { int32_t status = 0; HAL_SetPWMPulseTimeMicroseconds(m_handle, time.value(), &status); FRC_CheckErrorStatus(status, "Channel {}", m_channel); } -units::microsecond_t PWM::GetPulseTime() const { +wpi::units::microsecond_t PWM::GetPulseTime() const { int32_t status = 0; double value = HAL_GetPWMPulseTimeMicroseconds(m_handle, &status); FRC_CheckErrorStatus(status, "Channel {}", m_channel); - return units::microsecond_t{value}; + return wpi::units::microsecond_t{value}; } void PWM::SetDisabled() { @@ -96,10 +96,10 @@ void PWM::SetSimDevice(HAL_SimDeviceHandle device) { HAL_SetPWMSimDevice(m_handle, device); } -void PWM::InitSendable(wpi::SendableBuilder& builder) { +void PWM::InitSendable(wpi::util::SendableBuilder& builder) { builder.SetSmartDashboardType("PWM"); builder.SetActuator(true); builder.AddDoubleProperty( "Value", [=, this] { return GetPulseTime().value(); }, - [=, this](double value) { SetPulseTime(units::millisecond_t{value}); }); + [=, this](double value) { SetPulseTime(wpi::units::millisecond_t{value}); }); } diff --git a/wpilibc/src/main/native/cpp/hardware/imu/OnboardIMU.cpp b/wpilibc/src/main/native/cpp/hardware/imu/OnboardIMU.cpp index 7f7154f6e1..3c99e038ac 100644 --- a/wpilibc/src/main/native/cpp/hardware/imu/OnboardIMU.cpp +++ b/wpilibc/src/main/native/cpp/hardware/imu/OnboardIMU.cpp @@ -7,14 +7,14 @@ #include "wpi/hal/IMU.h" #include "wpi/system/Errors.hpp" -using namespace frc; +using namespace wpi; OnboardIMU::OnboardIMU(MountOrientation mountOrientation) : m_mountOrientation{mountOrientation} { // TODO: usage reporting } -units::radian_t OnboardIMU::GetYawNoOffset() { +wpi::units::radian_t OnboardIMU::GetYawNoOffset() { int64_t timestamp; double val; switch (m_mountOrientation) { @@ -30,10 +30,10 @@ units::radian_t OnboardIMU::GetYawNoOffset() { default: val = 0; } - return units::radian_t{val}; + return wpi::units::radian_t{val}; } -units::radian_t OnboardIMU::GetYaw() { +wpi::units::radian_t OnboardIMU::GetYaw() { return GetYawNoOffset() - m_yawOffset; } @@ -41,23 +41,23 @@ void OnboardIMU::ResetYaw() { m_yawOffset = GetYawNoOffset(); } -Rotation2d OnboardIMU::GetRotation2d() { - return Rotation2d{GetYaw()}; +wpi::math::Rotation2d OnboardIMU::GetRotation2d() { + return wpi::math::Rotation2d{GetYaw()}; } -Rotation3d OnboardIMU::GetRotation3d() { - return Rotation3d{GetQuaternion()}; +wpi::math::Rotation3d OnboardIMU::GetRotation3d() { + return wpi::math::Rotation3d{GetQuaternion()}; } -Quaternion OnboardIMU::GetQuaternion() { +wpi::math::Quaternion OnboardIMU::GetQuaternion() { HAL_Quaternion val; int32_t status = 0; HAL_GetIMUQuaternion(&val, &status); FRC_CheckErrorStatus(status, "Onboard IMU"); - return Quaternion{val.w, val.x, val.y, val.z}; + return wpi::math::Quaternion{val.w, val.x, val.y, val.z}; } -units::radian_t OnboardIMU::GetAngleX() { +wpi::units::radian_t OnboardIMU::GetAngleX() { HAL_EulerAngles3d val; int32_t status = 0; switch (m_mountOrientation) { @@ -72,10 +72,10 @@ units::radian_t OnboardIMU::GetAngleX() { break; } FRC_CheckErrorStatus(status, "Onboard IMU"); - return units::radian_t{val.x}; + return wpi::units::radian_t{val.x}; } -units::radian_t OnboardIMU::GetAngleY() { +wpi::units::radian_t OnboardIMU::GetAngleY() { HAL_EulerAngles3d val; int32_t status = 0; switch (m_mountOrientation) { @@ -90,10 +90,10 @@ units::radian_t OnboardIMU::GetAngleY() { break; } FRC_CheckErrorStatus(status, "Onboard IMU"); - return units::radian_t{val.y}; + return wpi::units::radian_t{val.y}; } -units::radian_t OnboardIMU::GetAngleZ() { +wpi::units::radian_t OnboardIMU::GetAngleZ() { HAL_EulerAngles3d val; int32_t status = 0; switch (m_mountOrientation) { @@ -108,53 +108,53 @@ units::radian_t OnboardIMU::GetAngleZ() { break; } FRC_CheckErrorStatus(status, "Onboard IMU"); - return units::radian_t{val.z}; + return wpi::units::radian_t{val.z}; } -units::radians_per_second_t OnboardIMU::GetGyroRateX() { +wpi::units::radians_per_second_t OnboardIMU::GetGyroRateX() { HAL_GyroRate3d val; int32_t status = 0; HAL_GetIMUGyroRates(&val, &status); FRC_CheckErrorStatus(status, "Onboard IMU"); - return units::radians_per_second_t{val.x}; + return wpi::units::radians_per_second_t{val.x}; } -units::radians_per_second_t OnboardIMU::GetGyroRateY() { +wpi::units::radians_per_second_t OnboardIMU::GetGyroRateY() { HAL_GyroRate3d val; int32_t status = 0; HAL_GetIMUGyroRates(&val, &status); FRC_CheckErrorStatus(status, "Onboard IMU"); - return units::radians_per_second_t{val.y}; + return wpi::units::radians_per_second_t{val.y}; } -units::radians_per_second_t OnboardIMU::GetGyroRateZ() { +wpi::units::radians_per_second_t OnboardIMU::GetGyroRateZ() { HAL_GyroRate3d val; int32_t status = 0; HAL_GetIMUGyroRates(&val, &status); FRC_CheckErrorStatus(status, "Onboard IMU"); - return units::radians_per_second_t{val.z}; + return wpi::units::radians_per_second_t{val.z}; } -units::meters_per_second_squared_t OnboardIMU::GetAccelX() { +wpi::units::meters_per_second_squared_t OnboardIMU::GetAccelX() { HAL_Acceleration3d val; int32_t status = 0; HAL_GetIMUAcceleration(&val, &status); FRC_CheckErrorStatus(status, "Onboard IMU"); - return units::meters_per_second_squared_t{val.x}; + return wpi::units::meters_per_second_squared_t{val.x}; } -units::meters_per_second_squared_t OnboardIMU::GetAccelY() { +wpi::units::meters_per_second_squared_t OnboardIMU::GetAccelY() { HAL_Acceleration3d val; int32_t status = 0; HAL_GetIMUAcceleration(&val, &status); FRC_CheckErrorStatus(status, "Onboard IMU"); - return units::meters_per_second_squared_t{val.x}; + return wpi::units::meters_per_second_squared_t{val.x}; } -units::meters_per_second_squared_t OnboardIMU::GetAccelZ() { +wpi::units::meters_per_second_squared_t OnboardIMU::GetAccelZ() { HAL_Acceleration3d val; int32_t status = 0; HAL_GetIMUAcceleration(&val, &status); FRC_CheckErrorStatus(status, "Onboard IMU"); - return units::meters_per_second_squared_t{val.x}; + return wpi::units::meters_per_second_squared_t{val.x}; } diff --git a/wpilibc/src/main/native/cpp/hardware/led/AddressableLED.cpp b/wpilibc/src/main/native/cpp/hardware/led/AddressableLED.cpp index b1057a31e1..175ecdfcb9 100644 --- a/wpilibc/src/main/native/cpp/hardware/led/AddressableLED.cpp +++ b/wpilibc/src/main/native/cpp/hardware/led/AddressableLED.cpp @@ -15,7 +15,7 @@ #include "wpi/util/SensorUtil.hpp" #include "wpi/util/StackTrace.hpp" -using namespace frc; +using namespace wpi; AddressableLED::AddressableLED(int channel) : m_channel{channel} { if (!SensorUtil::CheckDigitalChannel(channel)) { @@ -23,7 +23,7 @@ AddressableLED::AddressableLED(int channel) : m_channel{channel} { } int32_t status = 0; - auto stack = wpi::GetStackTrace(1); + auto stack = wpi::util::GetStackTrace(1); m_handle = HAL_InitializeAddressableLED(channel, stack.c_str(), &status); FRC_CheckErrorStatus(status, "Channel {}", channel); diff --git a/wpilibc/src/main/native/cpp/hardware/led/LEDPattern.cpp b/wpilibc/src/main/native/cpp/hardware/led/LEDPattern.cpp index bb0219fd00..cbc04f621c 100644 --- a/wpilibc/src/main/native/cpp/hardware/led/LEDPattern.cpp +++ b/wpilibc/src/main/native/cpp/hardware/led/LEDPattern.cpp @@ -15,20 +15,20 @@ #include "wpi/util/MathExtras.hpp" #include "wpi/util/timestamp.h" -using namespace frc; +using namespace wpi; -LEDPattern::LEDPattern(std::function)> +LEDPattern::LEDPattern(std::function)> impl) : m_impl(std::move(impl)) {} void LEDPattern::ApplyTo(LEDPattern::LEDReader reader, - std::function writer) const { + std::function writer) const { m_impl(reader, writer); } void LEDPattern::ApplyTo(std::span data, - std::function writer) const { + std::function writer) const { ApplyTo(LEDPattern::LEDReader{[=](size_t i) { return data[i]; }, data.size()}, writer); } @@ -54,39 +54,39 @@ LEDPattern LEDPattern::Reversed() { LEDPattern LEDPattern::OffsetBy(int offset) { return MapIndex([offset](size_t bufLen, size_t i) { - return frc::FloorMod(static_cast(i) + offset, + return wpi::math::FloorMod(static_cast(i) + offset, static_cast(bufLen)); }); } -LEDPattern LEDPattern::ScrollAtRelativeSpeed(units::hertz_t velocity) { +LEDPattern LEDPattern::ScrollAtRelativeSpeed(wpi::units::hertz_t velocity) { // velocity is in terms of LED lengths per second (1_hz = full cycle per // second, 0.5_hz = half cycle per second, 2_hz = two cycles per second) // Invert and multiply by 1,000,000 to get microseconds double periodMicros = 1e6 / velocity.value(); return MapIndex([=](size_t bufLen, size_t i) { - auto now = wpi::Now(); + auto now = wpi::util::Now(); // index should move by (bufLen) / (period) double t = (now % static_cast(std::floor(periodMicros))) / periodMicros; int offset = static_cast(std::floor(t * bufLen)); - return frc::FloorMod(static_cast(i) + offset, + return wpi::math::FloorMod(static_cast(i) + offset, static_cast(bufLen)); }); } LEDPattern LEDPattern::ScrollAtAbsoluteSpeed( - units::meters_per_second_t velocity, units::meter_t ledSpacing) { + wpi::units::meters_per_second_t velocity, wpi::units::meter_t ledSpacing) { // Velocity is in terms of meters per second // Multiply by 1,000,000 to use microseconds instead of seconds auto microsPerLed = static_cast(std::floor((ledSpacing / velocity).value() * 1e6)); return MapIndex([=](size_t bufLen, size_t i) { - auto now = wpi::Now(); + auto now = wpi::util::Now(); // every step in time that's a multiple of microsPerLED will increment // the offset by 1 @@ -94,17 +94,17 @@ LEDPattern LEDPattern::ScrollAtAbsoluteSpeed( // offset values for negative velocities auto offset = static_cast(now) / microsPerLed; - return frc::FloorMod(static_cast(i) + offset, + return wpi::math::FloorMod(static_cast(i) + offset, static_cast(bufLen)); }); } -LEDPattern LEDPattern::Blink(units::second_t onTime, units::second_t offTime) { - auto totalMicros = units::microsecond_t{onTime + offTime}.to(); - auto onMicros = units::microsecond_t{onTime}.to(); +LEDPattern LEDPattern::Blink(wpi::units::second_t onTime, wpi::units::second_t offTime) { + auto totalMicros = wpi::units::microsecond_t{onTime + offTime}.to(); + auto onMicros = wpi::units::microsecond_t{onTime}.to(); return LEDPattern{[=, self = *this](auto data, auto writer) { - if (wpi::Now() % totalMicros < onMicros) { + if (wpi::util::Now() % totalMicros < onMicros) { self.ApplyTo(data, writer); } else { LEDPattern::Off().ApplyTo(data, writer); @@ -112,7 +112,7 @@ LEDPattern LEDPattern::Blink(units::second_t onTime, units::second_t offTime) { }}; } -LEDPattern LEDPattern::Blink(units::second_t onTime) { +LEDPattern LEDPattern::Blink(wpi::units::second_t onTime) { return LEDPattern::Blink(onTime, onTime); } @@ -126,12 +126,12 @@ LEDPattern LEDPattern::SynchronizedBlink(std::function signal) { }}; } -LEDPattern LEDPattern::Breathe(units::second_t period) { - auto periodMicros = units::microsecond_t{period}; +LEDPattern LEDPattern::Breathe(wpi::units::second_t period) { + auto periodMicros = wpi::units::microsecond_t{period}; return LEDPattern{[periodMicros, self = *this](auto data, auto writer) { self.ApplyTo(data, [&writer, periodMicros](int i, Color color) { - double t = (wpi::Now() % periodMicros.to()) / + double t = (wpi::util::Now() % periodMicros.to()) / periodMicros.to(); double phase = t * 2 * std::numbers::pi; @@ -299,9 +299,9 @@ LEDPattern LEDPattern::Gradient(GradientType type, auto color = colors[colorIndex]; auto nextColor = colors[nextColorIndex]; - Color gradientColor{wpi::Lerp(color.red, nextColor.red, t), - wpi::Lerp(color.green, nextColor.green, t), - wpi::Lerp(color.blue, nextColor.blue, t)}; + Color gradientColor{wpi::util::Lerp(color.red, nextColor.red, t), + wpi::util::Lerp(color.green, nextColor.green, t), + wpi::util::Lerp(color.blue, nextColor.blue, t)}; writer(led, gradientColor); } }}; diff --git a/wpilibc/src/main/native/cpp/hardware/motor/MotorSafety.cpp b/wpilibc/src/main/native/cpp/hardware/motor/MotorSafety.cpp index 1b2543f818..4191dca54f 100644 --- a/wpilibc/src/main/native/cpp/hardware/motor/MotorSafety.cpp +++ b/wpilibc/src/main/native/cpp/hardware/motor/MotorSafety.cpp @@ -13,23 +13,23 @@ #include "wpi/util/SafeThread.hpp" #include "wpi/util/SmallPtrSet.hpp" -using namespace frc; +using namespace wpi; namespace { -class Thread : public wpi::SafeThread { +class Thread : public wpi::util::SafeThread { public: Thread() {} void Main() override; }; void Thread::Main() { - wpi::Event event{false, false}; + wpi::util::Event event{false, false}; HAL_ProvideNewDataEventHandle(event.GetHandle()); int safetyCounter = 0; while (m_active) { bool timedOut = false; - bool signaled = wpi::WaitForObject(event.GetHandle(), 0.1, &timedOut); + bool signaled = wpi::util::WaitForObject(event.GetHandle(), 0.1, &timedOut); if (signaled) { HAL_ControlWord controlWord; std::memset(&controlWord, 0, sizeof(controlWord)); @@ -56,9 +56,9 @@ namespace { struct MotorSafetyManager { ~MotorSafetyManager() { gShutdown = true; } - wpi::SafeThreadOwner thread; - wpi::SmallPtrSet instanceList; - wpi::mutex listMutex; + wpi::util::SafeThreadOwner thread; + wpi::util::SmallPtrSet instanceList; + wpi::util::mutex listMutex; bool threadStarted = false; }; } // namespace @@ -69,17 +69,17 @@ static MotorSafetyManager& GetManager() { } #ifndef __FRC_SYSTEMCORE__ -namespace frc::impl { +namespace wpi::impl { void ResetMotorSafety() { auto& manager = GetManager(); std::scoped_lock lock(manager.listMutex); manager.instanceList.clear(); manager.thread.Stop(); manager.thread.Join(); - manager.thread = wpi::SafeThreadOwner{}; + manager.thread = wpi::util::SafeThreadOwner{}; manager.threadStarted = false; } -} // namespace frc::impl +} // namespace wpi::impl #endif MotorSafety::MotorSafety() { @@ -118,12 +118,12 @@ void MotorSafety::Feed() { m_stopTime = Timer::GetFPGATimestamp() + m_expiration; } -void MotorSafety::SetExpiration(units::second_t expirationTime) { +void MotorSafety::SetExpiration(wpi::units::second_t expirationTime) { std::scoped_lock lock(m_thisMutex); m_expiration = expirationTime; } -units::second_t MotorSafety::GetExpiration() const { +wpi::units::second_t MotorSafety::GetExpiration() const { std::scoped_lock lock(m_thisMutex); return m_expiration; } @@ -145,7 +145,7 @@ bool MotorSafety::IsSafetyEnabled() const { void MotorSafety::Check() { bool enabled; - units::second_t stopTime; + wpi::units::second_t stopTime; { std::scoped_lock lock(m_thisMutex); @@ -165,7 +165,7 @@ void MotorSafety::Check() { try { StopMotor(); - } catch (frc::RuntimeError& e) { + } catch (wpi::RuntimeError& e) { e.Report(); } catch (std::exception& e) { FRC_ReportError(err::Error, "{} StopMotor threw unexpected exception: {}", diff --git a/wpilibc/src/main/native/cpp/hardware/pneumatic/Compressor.cpp b/wpilibc/src/main/native/cpp/hardware/pneumatic/Compressor.cpp index b320c048a1..6cd10ed747 100644 --- a/wpilibc/src/main/native/cpp/hardware/pneumatic/Compressor.cpp +++ b/wpilibc/src/main/native/cpp/hardware/pneumatic/Compressor.cpp @@ -10,7 +10,7 @@ #include "wpi/util/sendable/SendableBuilder.hpp" #include "wpi/util/sendable/SendableRegistry.hpp" -using namespace frc; +using namespace wpi; Compressor::Compressor(int busId, int module, PneumaticsModuleType moduleType) : m_module{PneumaticsBase::GetForType(busId, module, moduleType)}, @@ -22,7 +22,7 @@ Compressor::Compressor(int busId, int module, PneumaticsModuleType moduleType) m_module->EnableCompressorDigital(); m_module->ReportUsage("Compressor", ""); - wpi::SendableRegistry::Add(this, "Compressor", module); + wpi::util::SendableRegistry::Add(this, "Compressor", module); } Compressor::Compressor(int busId, PneumaticsModuleType moduleType) @@ -43,15 +43,15 @@ bool Compressor::GetPressureSwitchValue() const { return m_module->GetPressureSwitch(); } -units::ampere_t Compressor::GetCurrent() const { +wpi::units::ampere_t Compressor::GetCurrent() const { return m_module->GetCompressorCurrent(); } -units::volt_t Compressor::GetAnalogVoltage() const { +wpi::units::volt_t Compressor::GetAnalogVoltage() const { return m_module->GetAnalogVoltage(0); } -units::pounds_per_square_inch_t Compressor::GetPressure() const { +wpi::units::pounds_per_square_inch_t Compressor::GetPressure() const { return m_module->GetPressure(0); } @@ -63,13 +63,13 @@ void Compressor::EnableDigital() { m_module->EnableCompressorDigital(); } -void Compressor::EnableAnalog(units::pounds_per_square_inch_t minPressure, - units::pounds_per_square_inch_t maxPressure) { +void Compressor::EnableAnalog(wpi::units::pounds_per_square_inch_t minPressure, + wpi::units::pounds_per_square_inch_t maxPressure) { m_module->EnableCompressorAnalog(minPressure, maxPressure); } -void Compressor::EnableHybrid(units::pounds_per_square_inch_t minPressure, - units::pounds_per_square_inch_t maxPressure) { +void Compressor::EnableHybrid(wpi::units::pounds_per_square_inch_t minPressure, + wpi::units::pounds_per_square_inch_t maxPressure) { m_module->EnableCompressorHybrid(minPressure, maxPressure); } @@ -77,7 +77,7 @@ CompressorConfigType Compressor::GetConfigType() const { return m_module->GetCompressorConfigType(); } -void Compressor::InitSendable(wpi::SendableBuilder& builder) { +void Compressor::InitSendable(wpi::util::SendableBuilder& builder) { builder.SetSmartDashboardType("Compressor"); builder.AddBooleanProperty( "Enabled", [this] { return IsEnabled(); }, nullptr); diff --git a/wpilibc/src/main/native/cpp/hardware/pneumatic/DoubleSolenoid.cpp b/wpilibc/src/main/native/cpp/hardware/pneumatic/DoubleSolenoid.cpp index 28865514fa..adc46f6298 100644 --- a/wpilibc/src/main/native/cpp/hardware/pneumatic/DoubleSolenoid.cpp +++ b/wpilibc/src/main/native/cpp/hardware/pneumatic/DoubleSolenoid.cpp @@ -13,7 +13,7 @@ #include "wpi/util/sendable/SendableBuilder.hpp" #include "wpi/util/sendable/SendableRegistry.hpp" -using namespace frc; +using namespace wpi; DoubleSolenoid::DoubleSolenoid(int busId, int module, PneumaticsModuleType moduleType, @@ -52,7 +52,7 @@ DoubleSolenoid::DoubleSolenoid(int busId, int module, fmt::format("Solenoid[{},{}]", m_forwardChannel, m_reverseChannel), "DoubleSolenoid"); - wpi::SendableRegistry::Add(this, "DoubleSolenoid", + wpi::util::SendableRegistry::Add(this, "DoubleSolenoid", m_module->GetModuleNumber(), m_forwardChannel); } @@ -123,12 +123,12 @@ bool DoubleSolenoid::IsRevSolenoidDisabled() const { return (m_module->GetSolenoidDisabledList() & m_reverseMask) != 0; } -void DoubleSolenoid::InitSendable(wpi::SendableBuilder& builder) { +void DoubleSolenoid::InitSendable(wpi::util::SendableBuilder& builder) { builder.SetSmartDashboardType("Double Solenoid"); builder.SetActuator(true); builder.AddSmallStringProperty( "Value", - [=, this](wpi::SmallVectorImpl& buf) -> std::string_view { + [=, this](wpi::util::SmallVectorImpl& buf) -> std::string_view { switch (Get()) { case kForward: return "Forward"; diff --git a/wpilibc/src/main/native/cpp/hardware/pneumatic/PneumaticHub.cpp b/wpilibc/src/main/native/cpp/hardware/pneumatic/PneumaticHub.cpp index 24de9fd6bd..e394842586 100644 --- a/wpilibc/src/main/native/cpp/hardware/pneumatic/PneumaticHub.cpp +++ b/wpilibc/src/main/native/cpp/hardware/pneumatic/PneumaticHub.cpp @@ -23,24 +23,24 @@ #include "wpi/util/SensorUtil.hpp" #include "wpi/util/StackTrace.hpp" -using namespace frc; +using namespace wpi; /** Converts volts to PSI per the REV Analog Pressure Sensor datasheet. */ -units::pounds_per_square_inch_t VoltsToPSI(units::volt_t sensorVoltage, - units::volt_t supplyVoltage) { - return units::pounds_per_square_inch_t{ +wpi::units::pounds_per_square_inch_t VoltsToPSI(wpi::units::volt_t sensorVoltage, + wpi::units::volt_t supplyVoltage) { + return wpi::units::pounds_per_square_inch_t{ 250 * (sensorVoltage.value() / supplyVoltage.value()) - 25}; } /** Converts PSI to volts per the REV Analog Pressure Sensor datasheet. */ -units::volt_t PSIToVolts(units::pounds_per_square_inch_t pressure, - units::volt_t supplyVoltage) { - return units::volt_t{supplyVoltage.value() * +wpi::units::volt_t PSIToVolts(wpi::units::pounds_per_square_inch_t pressure, + wpi::units::volt_t supplyVoltage) { + return wpi::units::volt_t{supplyVoltage.value() * (0.004 * pressure.value() + 0.1)}; } -wpi::mutex PneumaticHub::m_handleLock; -std::unique_ptr>[]> +wpi::util::mutex PneumaticHub::m_handleLock; +std::unique_ptr>[]> PneumaticHub::m_handleMaps = nullptr; // Always called under lock, so we can avoid the double lock from the magic @@ -52,7 +52,7 @@ std::weak_ptr& PneumaticHub::GetDataStore(int busId, "Bus {} out of range. Must be [0-{}).", busId, numBuses); if (!m_handleMaps) { m_handleMaps = std::make_unique< - wpi::DenseMap>[]>(numBuses); + wpi::util::DenseMap>[]>(numBuses); } return m_handleMaps[busId][module]; } @@ -66,7 +66,7 @@ class PneumaticHub::DataStore { FRC_CheckErrorStatus(status, "Module {}", module); m_moduleObject = PneumaticHub{busId, handle, module}; m_moduleObject.m_dataStore = - std::shared_ptr{this, wpi::NullDeleter()}; + std::shared_ptr{this, wpi::util::NullDeleter()}; auto version = m_moduleObject.GetVersion(); @@ -89,16 +89,16 @@ class PneumaticHub::DataStore { friend class PneumaticHub; uint32_t m_reservedMask{0}; bool m_compressorReserved{false}; - wpi::mutex m_reservedLock; + wpi::util::mutex m_reservedLock; PneumaticHub m_moduleObject{0, HAL_kInvalidHandle, 0}; - std::array m_oneShotDurMs{0_ms}; + std::array m_oneShotDurMs{0_ms}; }; PneumaticHub::PneumaticHub(int busId) : PneumaticHub{busId, SensorUtil::GetDefaultREVPHModule()} {} PneumaticHub::PneumaticHub(int busId, int module) { - std::string stackTrace = wpi::GetStackTrace(1); + std::string stackTrace = wpi::util::GetStackTrace(1); std::scoped_lock lock(m_handleLock); auto& res = GetDataStore(busId, module); m_dataStore = res.lock(); @@ -134,8 +134,8 @@ void PneumaticHub::EnableCompressorDigital() { } void PneumaticHub::EnableCompressorAnalog( - units::pounds_per_square_inch_t minPressure, - units::pounds_per_square_inch_t maxPressure) { + wpi::units::pounds_per_square_inch_t minPressure, + wpi::units::pounds_per_square_inch_t maxPressure) { if (minPressure >= maxPressure) { throw FRC_MakeError(err::InvalidParameter, "maxPressure must be greater than minPressure"); @@ -154,8 +154,8 @@ void PneumaticHub::EnableCompressorAnalog( // Send the voltage as it would be if the 5V rail was at exactly 5V. // The firmware will compensate for the real 5V rail voltage, which // can fluctuate somewhat over time. - units::volt_t minAnalogVoltage = PSIToVolts(minPressure, 5_V); - units::volt_t maxAnalogVoltage = PSIToVolts(maxPressure, 5_V); + wpi::units::volt_t minAnalogVoltage = PSIToVolts(minPressure, 5_V); + wpi::units::volt_t maxAnalogVoltage = PSIToVolts(maxPressure, 5_V); int32_t status = 0; HAL_SetREVPHClosedLoopControlAnalog(m_handle, minAnalogVoltage.value(), @@ -164,8 +164,8 @@ void PneumaticHub::EnableCompressorAnalog( } void PneumaticHub::EnableCompressorHybrid( - units::pounds_per_square_inch_t minPressure, - units::pounds_per_square_inch_t maxPressure) { + wpi::units::pounds_per_square_inch_t minPressure, + wpi::units::pounds_per_square_inch_t maxPressure) { if (minPressure >= maxPressure) { throw FRC_MakeError(err::InvalidParameter, "maxPressure must be greater than minPressure"); @@ -184,8 +184,8 @@ void PneumaticHub::EnableCompressorHybrid( // Send the voltage as it would be if the 5V rail was at exactly 5V. // The firmware will compensate for the real 5V rail voltage, which // can fluctuate somewhat over time. - units::volt_t minAnalogVoltage = PSIToVolts(minPressure, 5_V); - units::volt_t maxAnalogVoltage = PSIToVolts(maxPressure, 5_V); + wpi::units::volt_t minAnalogVoltage = PSIToVolts(minPressure, 5_V); + wpi::units::volt_t maxAnalogVoltage = PSIToVolts(maxPressure, 5_V); int32_t status = 0; HAL_SetREVPHClosedLoopControlHybrid(m_handle, minAnalogVoltage.value(), @@ -207,11 +207,11 @@ bool PneumaticHub::GetPressureSwitch() const { return result; } -units::ampere_t PneumaticHub::GetCompressorCurrent() const { +wpi::units::ampere_t PneumaticHub::GetCompressorCurrent() const { int32_t status = 0; auto result = HAL_GetREVPHCompressorCurrent(m_handle, &status); FRC_ReportError(status, "Module {}", m_module); - return units::ampere_t{result}; + return wpi::units::ampere_t{result}; } void PneumaticHub::SetSolenoids(int mask, int values) { @@ -245,7 +245,7 @@ void PneumaticHub::FireOneShot(int index) { FRC_ReportError(status, "Module {}", m_module); } -void PneumaticHub::SetOneShotDuration(int index, units::second_t duration) { +void PneumaticHub::SetOneShotDuration(int index, wpi::units::second_t duration) { m_dataStore->m_oneShotDurMs[index] = duration; } @@ -370,48 +370,48 @@ void PneumaticHub::ClearStickyFaults() { FRC_ReportError(status, "Module {}", m_module); } -units::volt_t PneumaticHub::GetInputVoltage() const { +wpi::units::volt_t PneumaticHub::GetInputVoltage() const { int32_t status = 0; auto voltage = HAL_GetREVPHVoltage(m_handle, &status); FRC_ReportError(status, "Module {}", m_module); - return units::volt_t{voltage}; + return wpi::units::volt_t{voltage}; } -units::volt_t PneumaticHub::Get5VRegulatedVoltage() const { +wpi::units::volt_t PneumaticHub::Get5VRegulatedVoltage() const { int32_t status = 0; auto voltage = HAL_GetREVPH5VVoltage(m_handle, &status); FRC_ReportError(status, "Module {}", m_module); - return units::volt_t{voltage}; + return wpi::units::volt_t{voltage}; } -units::ampere_t PneumaticHub::GetSolenoidsTotalCurrent() const { +wpi::units::ampere_t PneumaticHub::GetSolenoidsTotalCurrent() const { int32_t status = 0; auto current = HAL_GetREVPHSolenoidCurrent(m_handle, &status); FRC_ReportError(status, "Module {}", m_module); - return units::ampere_t{current}; + return wpi::units::ampere_t{current}; } -units::volt_t PneumaticHub::GetSolenoidsVoltage() const { +wpi::units::volt_t PneumaticHub::GetSolenoidsVoltage() const { int32_t status = 0; auto voltage = HAL_GetREVPHSolenoidVoltage(m_handle, &status); FRC_ReportError(status, "Module {}", m_module); - return units::volt_t{voltage}; + return wpi::units::volt_t{voltage}; } -units::volt_t PneumaticHub::GetAnalogVoltage(int channel) const { +wpi::units::volt_t PneumaticHub::GetAnalogVoltage(int channel) const { int32_t status = 0; auto voltage = HAL_GetREVPHAnalogVoltage(m_handle, channel, &status); FRC_ReportError(status, "Module {}", m_module); - return units::volt_t{voltage}; + return wpi::units::volt_t{voltage}; } -units::pounds_per_square_inch_t PneumaticHub::GetPressure(int channel) const { +wpi::units::pounds_per_square_inch_t PneumaticHub::GetPressure(int channel) const { int32_t status = 0; auto sensorVoltage = HAL_GetREVPHAnalogVoltage(m_handle, channel, &status); FRC_ReportError(status, "Module {}", m_module); auto supplyVoltage = HAL_GetREVPH5VVoltage(m_handle, &status); FRC_ReportError(status, "Module {}", m_module); - return VoltsToPSI(units::volt_t{sensorVoltage}, units::volt_t{supplyVoltage}); + return VoltsToPSI(wpi::units::volt_t{sensorVoltage}, wpi::units::volt_t{supplyVoltage}); } Solenoid PneumaticHub::MakeSolenoid(int channel) { @@ -434,7 +434,7 @@ void PneumaticHub::ReportUsage(std::string_view device, std::string_view data) { std::shared_ptr PneumaticHub::GetForModule(int busId, int module) { - std::string stackTrace = wpi::GetStackTrace(1); + std::string stackTrace = wpi::util::GetStackTrace(1); std::scoped_lock lock(m_handleLock); auto& res = GetDataStore(busId, module); std::shared_ptr dataStore = res.lock(); diff --git a/wpilibc/src/main/native/cpp/hardware/pneumatic/PneumaticsBase.cpp b/wpilibc/src/main/native/cpp/hardware/pneumatic/PneumaticsBase.cpp index 50cfd6c31a..072f02eb57 100644 --- a/wpilibc/src/main/native/cpp/hardware/pneumatic/PneumaticsBase.cpp +++ b/wpilibc/src/main/native/cpp/hardware/pneumatic/PneumaticsBase.cpp @@ -12,7 +12,7 @@ #include "wpi/system/Errors.hpp" #include "wpi/util/SensorUtil.hpp" -using namespace frc; +using namespace wpi; static_assert( static_cast(CompressorConfigType::Disabled) == diff --git a/wpilibc/src/main/native/cpp/hardware/pneumatic/PneumaticsControlModule.cpp b/wpilibc/src/main/native/cpp/hardware/pneumatic/PneumaticsControlModule.cpp index f408496148..9278ec3760 100644 --- a/wpilibc/src/main/native/cpp/hardware/pneumatic/PneumaticsControlModule.cpp +++ b/wpilibc/src/main/native/cpp/hardware/pneumatic/PneumaticsControlModule.cpp @@ -20,11 +20,11 @@ #include "wpi/util/SensorUtil.hpp" #include "wpi/util/StackTrace.hpp" -using namespace frc; +using namespace wpi; -wpi::mutex PneumaticsControlModule::m_handleLock; +wpi::util::mutex PneumaticsControlModule::m_handleLock; std::unique_ptr< - wpi::DenseMap>[]> + wpi::util::DenseMap>[]> PneumaticsControlModule::m_handleMaps = nullptr; // Always called under lock, so we can avoid the double lock from the magic @@ -35,7 +35,7 @@ PneumaticsControlModule::GetDataStore(int busId, int module) { FRC_AssertMessage(busId >= 0 && busId < numBuses, "Bus {} out of range. Must be [0-{}).", busId, numBuses); if (!m_handleMaps) { - m_handleMaps = std::make_unique>[]>(numBuses); } @@ -51,7 +51,7 @@ class PneumaticsControlModule::DataStore { FRC_CheckErrorStatus(status, "Module {}", module); m_moduleObject = PneumaticsControlModule{busId, handle, module}; m_moduleObject.m_dataStore = - std::shared_ptr{this, wpi::NullDeleter()}; + std::shared_ptr{this, wpi::util::NullDeleter()}; } ~DataStore() noexcept { HAL_FreeCTREPCM(m_moduleObject.m_handle); } @@ -63,7 +63,7 @@ class PneumaticsControlModule::DataStore { friend class PneumaticsControlModule; uint32_t m_reservedMask{0}; bool m_compressorReserved{false}; - wpi::mutex m_reservedLock; + wpi::util::mutex m_reservedLock; PneumaticsControlModule m_moduleObject{0, HAL_kInvalidHandle, 0}; }; @@ -71,7 +71,7 @@ PneumaticsControlModule::PneumaticsControlModule(int busId) : PneumaticsControlModule{busId, SensorUtil::GetDefaultCTREPCMModule()} {} PneumaticsControlModule::PneumaticsControlModule(int busId, int module) { - std::string stackTrace = wpi::GetStackTrace(1); + std::string stackTrace = wpi::util::GetStackTrace(1); std::scoped_lock lock(m_handleLock); auto& res = GetDataStore(busId, module); m_dataStore = res.lock(); @@ -109,16 +109,16 @@ void PneumaticsControlModule::EnableCompressorDigital() { } void PneumaticsControlModule::EnableCompressorAnalog( - units::pounds_per_square_inch_t minPressure, - units::pounds_per_square_inch_t maxPressure) { + wpi::units::pounds_per_square_inch_t minPressure, + wpi::units::pounds_per_square_inch_t maxPressure) { int32_t status = 0; HAL_SetCTREPCMClosedLoopControl(m_handle, true, &status); FRC_ReportError(status, "Module {}", m_module); } void PneumaticsControlModule::EnableCompressorHybrid( - units::pounds_per_square_inch_t minPressure, - units::pounds_per_square_inch_t maxPressure) { + wpi::units::pounds_per_square_inch_t minPressure, + wpi::units::pounds_per_square_inch_t maxPressure) { int32_t status = 0; HAL_SetCTREPCMClosedLoopControl(m_handle, true, &status); FRC_ReportError(status, "Module {}", m_module); @@ -139,11 +139,11 @@ bool PneumaticsControlModule::GetPressureSwitch() const { return result; } -units::ampere_t PneumaticsControlModule::GetCompressorCurrent() const { +wpi::units::ampere_t PneumaticsControlModule::GetCompressorCurrent() const { int32_t status = 0; auto result = HAL_GetCTREPCMCompressorCurrent(m_handle, &status); FRC_ReportError(status, "Module {}", m_module); - return units::ampere_t{result}; + return wpi::units::ampere_t{result}; } bool PneumaticsControlModule::GetCompressorCurrentTooHighFault() const { @@ -235,9 +235,9 @@ void PneumaticsControlModule::FireOneShot(int index) { } void PneumaticsControlModule::SetOneShotDuration(int index, - units::second_t duration) { + wpi::units::second_t duration) { int32_t status = 0; - units::millisecond_t millis = duration; + wpi::units::millisecond_t millis = duration; HAL_SetCTREPCMOneShotDuration(m_handle, index, millis.to(), &status); FRC_ReportError(status, "Module {}", m_module); } @@ -275,11 +275,11 @@ void PneumaticsControlModule::UnreserveCompressor() { m_dataStore->m_compressorReserved = false; } -units::volt_t PneumaticsControlModule::GetAnalogVoltage(int channel) const { +wpi::units::volt_t PneumaticsControlModule::GetAnalogVoltage(int channel) const { return 0_V; } -units::pounds_per_square_inch_t PneumaticsControlModule::GetPressure( +wpi::units::pounds_per_square_inch_t PneumaticsControlModule::GetPressure( int channel) const { return 0_psi; } @@ -305,7 +305,7 @@ void PneumaticsControlModule::ReportUsage(std::string_view device, std::shared_ptr PneumaticsControlModule::GetForModule( int busId, int module) { - std::string stackTrace = wpi::GetStackTrace(1); + std::string stackTrace = wpi::util::GetStackTrace(1); std::scoped_lock lock(m_handleLock); auto& res = GetDataStore(busId, module); std::shared_ptr dataStore = res.lock(); diff --git a/wpilibc/src/main/native/cpp/hardware/pneumatic/Solenoid.cpp b/wpilibc/src/main/native/cpp/hardware/pneumatic/Solenoid.cpp index 6f6e1474ec..66eda08750 100644 --- a/wpilibc/src/main/native/cpp/hardware/pneumatic/Solenoid.cpp +++ b/wpilibc/src/main/native/cpp/hardware/pneumatic/Solenoid.cpp @@ -12,7 +12,7 @@ #include "wpi/util/sendable/SendableBuilder.hpp" #include "wpi/util/sendable/SendableRegistry.hpp" -using namespace frc; +using namespace wpi; Solenoid::Solenoid(int busId, int module, PneumaticsModuleType moduleType, int channel) @@ -28,7 +28,7 @@ Solenoid::Solenoid(int busId, int module, PneumaticsModuleType moduleType, } m_module->ReportUsage(fmt::format("Solenoid[{}]", m_channel), "Solenoid"); - wpi::SendableRegistry::Add(this, "Solenoid", m_module->GetModuleNumber(), + wpi::util::SendableRegistry::Add(this, "Solenoid", m_module->GetModuleNumber(), m_channel); } @@ -64,7 +64,7 @@ bool Solenoid::IsDisabled() const { return (m_module->GetSolenoidDisabledList() & m_mask) != 0; } -void Solenoid::SetPulseDuration(units::second_t duration) { +void Solenoid::SetPulseDuration(wpi::units::second_t duration) { m_module->SetOneShotDuration(m_channel, duration); } @@ -72,7 +72,7 @@ void Solenoid::StartPulse() { m_module->FireOneShot(m_channel); } -void Solenoid::InitSendable(wpi::SendableBuilder& builder) { +void Solenoid::InitSendable(wpi::util::SendableBuilder& builder) { builder.SetSmartDashboardType("Solenoid"); builder.SetActuator(true); builder.AddBooleanProperty( diff --git a/wpilibc/src/main/native/cpp/hardware/power/PowerDistribution.cpp b/wpilibc/src/main/native/cpp/hardware/power/PowerDistribution.cpp index 2ba6f2d0d9..1f1886bbd0 100644 --- a/wpilibc/src/main/native/cpp/hardware/power/PowerDistribution.cpp +++ b/wpilibc/src/main/native/cpp/hardware/power/PowerDistribution.cpp @@ -17,18 +17,18 @@ #include "wpi/util/sendable/SendableRegistry.hpp" static_assert(static_cast( - frc::PowerDistribution::ModuleType::kCTRE) == + wpi::PowerDistribution::ModuleType::kCTRE) == HAL_PowerDistributionType::HAL_PowerDistributionType_kCTRE); static_assert(static_cast( - frc::PowerDistribution::ModuleType::kRev) == + wpi::PowerDistribution::ModuleType::kRev) == HAL_PowerDistributionType::HAL_PowerDistributionType_kRev); -static_assert(frc::PowerDistribution::kDefaultModule == +static_assert(wpi::PowerDistribution::kDefaultModule == HAL_DEFAULT_POWER_DISTRIBUTION_MODULE); -using namespace frc; +using namespace wpi; PowerDistribution::PowerDistribution(int busId) { - auto stack = wpi::GetStackTrace(1); + auto stack = wpi::util::GetStackTrace(1); int32_t status = 0; m_handle = HAL_InitializePowerDistribution( @@ -45,12 +45,12 @@ PowerDistribution::PowerDistribution(int busId) { } else { HAL_ReportUsage("PDH", m_module, ""); } - wpi::SendableRegistry::Add(this, "PowerDistribution", m_module); + wpi::util::SendableRegistry::Add(this, "PowerDistribution", m_module); } PowerDistribution::PowerDistribution(int busId, int module, ModuleType moduleType) { - auto stack = wpi::GetStackTrace(1); + auto stack = wpi::util::GetStackTrace(1); int32_t status = 0; m_handle = HAL_InitializePowerDistribution( @@ -65,7 +65,7 @@ PowerDistribution::PowerDistribution(int busId, int module, } else { HAL_ReportUsage("PDH_REV", m_module, ""); } - wpi::SendableRegistry::Add(this, "PowerDistribution", m_module); + wpi::util::SendableRegistry::Add(this, "PowerDistribution", m_module); } int PowerDistribution::GetNumChannels() const { @@ -320,7 +320,7 @@ PowerDistribution::StickyFaults PowerDistribution::GetStickyFaults() const { return stickyFaults; } -void PowerDistribution::InitSendable(wpi::SendableBuilder& builder) { +void PowerDistribution::InitSendable(wpi::util::SendableBuilder& builder) { builder.SetSmartDashboardType("PowerDistribution"); int numChannels = GetNumChannels(); // Use manual reads to avoid printing errors diff --git a/wpilibc/src/main/native/cpp/hardware/range/SharpIR.cpp b/wpilibc/src/main/native/cpp/hardware/range/SharpIR.cpp index 9f8e4ce2ce..cececa4e32 100644 --- a/wpilibc/src/main/native/cpp/hardware/range/SharpIR.cpp +++ b/wpilibc/src/main/native/cpp/hardware/range/SharpIR.cpp @@ -12,7 +12,7 @@ #include "wpi/util/sendable/SendableBuilder.hpp" #include "wpi/util/sendable/SendableRegistry.hpp" -using namespace frc; +using namespace wpi; SharpIR SharpIR::GP2Y0A02YK0F(int channel) { return SharpIR(channel, 62.28, -1.092, 20_cm, 150_cm); @@ -30,13 +30,13 @@ SharpIR SharpIR::GP2Y0A51SK0F(int channel) { return SharpIR(channel, 5.2819, -1.161, 2_cm, 15_cm); } -SharpIR::SharpIR(int channel, double a, double b, units::meter_t min, - units::meter_t max) +SharpIR::SharpIR(int channel, double a, double b, wpi::units::meter_t min, + wpi::units::meter_t max) : m_sensor(channel), m_A(a), m_B(b), m_min(min), m_max(max) { HAL_ReportUsage("IO", channel, "SharpIR"); - wpi::SendableRegistry::Add(this, "SharpIR", channel); + wpi::util::SendableRegistry::Add(this, "SharpIR", channel); - m_simDevice = hal::SimDevice("SharpIR", m_sensor.GetChannel()); + m_simDevice = wpi::hal::SimDevice("SharpIR", m_sensor.GetChannel()); if (m_simDevice) { m_simRange = m_simDevice.CreateDouble("Range (m)", false, 0.0); m_sensor.SetSimDevice(m_simDevice); @@ -47,19 +47,19 @@ int SharpIR::GetChannel() const { return m_sensor.GetChannel(); } -units::meter_t SharpIR::GetRange() const { +wpi::units::meter_t SharpIR::GetRange() const { if (m_simRange) { - return std::clamp(units::meter_t{m_simRange.Get()}, m_min, m_max); + return std::clamp(wpi::units::meter_t{m_simRange.Get()}, m_min, m_max); } else { // Don't allow zero/negative values auto v = std::max(m_sensor.GetVoltage(), 0.00001); - return std::clamp(units::meter_t{m_A * std::pow(v, m_B) * 1e-2}, m_min, + return std::clamp(wpi::units::meter_t{m_A * std::pow(v, m_B) * 1e-2}, m_min, m_max); } } -void SharpIR::InitSendable(wpi::SendableBuilder& builder) { +void SharpIR::InitSendable(wpi::util::SendableBuilder& builder) { builder.SetSmartDashboardType("Ultrasonic"); builder.AddDoubleProperty( "Value", [=, this] { return GetRange().value(); }, nullptr); diff --git a/wpilibc/src/main/native/cpp/hardware/rotation/AnalogEncoder.cpp b/wpilibc/src/main/native/cpp/hardware/rotation/AnalogEncoder.cpp index 6f5ca07265..1185afe8c3 100644 --- a/wpilibc/src/main/native/cpp/hardware/rotation/AnalogEncoder.cpp +++ b/wpilibc/src/main/native/cpp/hardware/rotation/AnalogEncoder.cpp @@ -13,7 +13,7 @@ #include "wpi/util/NullDeleter.hpp" #include "wpi/util/sendable/SendableBuilder.hpp" -using namespace frc; +using namespace wpi; AnalogEncoder::~AnalogEncoder() {} @@ -21,12 +21,12 @@ AnalogEncoder::AnalogEncoder(int channel) : AnalogEncoder(std::make_shared(channel)) {} AnalogEncoder::AnalogEncoder(AnalogInput& analogInput) - : m_analogInput{&analogInput, wpi::NullDeleter{}} { + : m_analogInput{&analogInput, wpi::util::NullDeleter{}} { Init(1.0, 0.0); } AnalogEncoder::AnalogEncoder(AnalogInput* analogInput) - : m_analogInput{analogInput, wpi::NullDeleter{}} { + : m_analogInput{analogInput, wpi::util::NullDeleter{}} { Init(1.0, 0.0); } @@ -41,13 +41,13 @@ AnalogEncoder::AnalogEncoder(int channel, double fullRange, double expectedZero) AnalogEncoder::AnalogEncoder(AnalogInput& analogInput, double fullRange, double expectedZero) - : m_analogInput{&analogInput, wpi::NullDeleter{}} { + : m_analogInput{&analogInput, wpi::util::NullDeleter{}} { Init(fullRange, expectedZero); } AnalogEncoder::AnalogEncoder(AnalogInput* analogInput, double fullRange, double expectedZero) - : m_analogInput{analogInput, wpi::NullDeleter{}} { + : m_analogInput{analogInput, wpi::util::NullDeleter{}} { Init(fullRange, expectedZero); } @@ -58,7 +58,7 @@ AnalogEncoder::AnalogEncoder(std::shared_ptr analogInput, } void AnalogEncoder::Init(double fullRange, double expectedZero) { - m_simDevice = hal::SimDevice{"AnalogEncoder", m_analogInput->GetChannel()}; + m_simDevice = wpi::hal::SimDevice{"AnalogEncoder", m_analogInput->GetChannel()}; if (m_simDevice) { m_simPosition = m_simDevice.CreateDouble("Position", false, 0.0); @@ -69,7 +69,7 @@ void AnalogEncoder::Init(double fullRange, double expectedZero) { HAL_ReportUsage("IO", m_analogInput->GetChannel(), "AnalogEncoder"); - wpi::SendableRegistry::Add(this, "Analog Encoder", + wpi::util::SendableRegistry::Add(this, "Analog Encoder", m_analogInput->GetChannel()); } @@ -88,7 +88,7 @@ double AnalogEncoder::Get() const { pos = pos * m_fullRange - m_expectedZero; // Map from 0 - Full Range - double result = InputModulus(pos, 0.0, m_fullRange); + double result = wpi::math::InputModulus(pos, 0.0, m_fullRange); // Invert if necessary if (m_isInverted) { return m_fullRange - result; @@ -120,7 +120,7 @@ double AnalogEncoder::MapSensorRange(double pos) const { return pos; } -void AnalogEncoder::InitSendable(wpi::SendableBuilder& builder) { +void AnalogEncoder::InitSendable(wpi::util::SendableBuilder& builder) { builder.SetSmartDashboardType("AbsoluteEncoder"); builder.AddDoubleProperty( "Position", [this] { return this->Get(); }, nullptr); diff --git a/wpilibc/src/main/native/cpp/hardware/rotation/AnalogPotentiometer.cpp b/wpilibc/src/main/native/cpp/hardware/rotation/AnalogPotentiometer.cpp index 0f5e8a59c4..e3e28bf78c 100644 --- a/wpilibc/src/main/native/cpp/hardware/rotation/AnalogPotentiometer.cpp +++ b/wpilibc/src/main/native/cpp/hardware/rotation/AnalogPotentiometer.cpp @@ -12,19 +12,19 @@ #include "wpi/util/sendable/SendableBuilder.hpp" #include "wpi/util/sendable/SendableRegistry.hpp" -using namespace frc; +using namespace wpi; AnalogPotentiometer::AnalogPotentiometer(int channel, double fullRange, double offset) : AnalogPotentiometer(std::make_shared(channel), fullRange, offset) { - wpi::SendableRegistry::AddChild(this, m_analog_input.get()); + wpi::util::SendableRegistry::AddChild(this, m_analog_input.get()); } AnalogPotentiometer::AnalogPotentiometer(AnalogInput* input, double fullRange, double offset) : AnalogPotentiometer( - std::shared_ptr(input, wpi::NullDeleter()), + std::shared_ptr(input, wpi::util::NullDeleter()), fullRange, offset) {} AnalogPotentiometer::AnalogPotentiometer(std::shared_ptr input, @@ -32,7 +32,7 @@ AnalogPotentiometer::AnalogPotentiometer(std::shared_ptr input, : m_analog_input(std::move(input)), m_fullRange(fullRange), m_offset(offset) { - wpi::SendableRegistry::Add(this, "AnalogPotentiometer", + wpi::util::SendableRegistry::Add(this, "AnalogPotentiometer", m_analog_input->GetChannel()); } @@ -42,7 +42,7 @@ double AnalogPotentiometer::Get() const { m_offset; } -void AnalogPotentiometer::InitSendable(wpi::SendableBuilder& builder) { +void AnalogPotentiometer::InitSendable(wpi::util::SendableBuilder& builder) { builder.SetSmartDashboardType("Analog Input"); builder.AddDoubleProperty("Value", [=, this] { return Get(); }, nullptr); } diff --git a/wpilibc/src/main/native/cpp/hardware/rotation/DutyCycle.cpp b/wpilibc/src/main/native/cpp/hardware/rotation/DutyCycle.cpp index e866a754dc..24b4f33cfa 100644 --- a/wpilibc/src/main/native/cpp/hardware/rotation/DutyCycle.cpp +++ b/wpilibc/src/main/native/cpp/hardware/rotation/DutyCycle.cpp @@ -16,7 +16,7 @@ #include "wpi/util/StackTrace.hpp" #include "wpi/util/sendable/SendableBuilder.hpp" -using namespace frc; +using namespace wpi; DutyCycle::DutyCycle(int channel) : m_channel{channel} { if (!SensorUtil::CheckDigitalChannel(channel)) { @@ -27,18 +27,18 @@ DutyCycle::DutyCycle(int channel) : m_channel{channel} { void DutyCycle::InitDutyCycle() { int32_t status = 0; - std::string stackTrace = wpi::GetStackTrace(1); + std::string stackTrace = wpi::util::GetStackTrace(1); m_handle = HAL_InitializeDutyCycle(m_channel, stackTrace.c_str(), &status); FRC_CheckErrorStatus(status, "Channel {}", GetSourceChannel()); HAL_ReportUsage("IO", m_channel, "DutyCycle"); - wpi::SendableRegistry::Add(this, "Duty Cycle", m_channel); + wpi::util::SendableRegistry::Add(this, "Duty Cycle", m_channel); } -units::hertz_t DutyCycle::GetFrequency() const { +wpi::units::hertz_t DutyCycle::GetFrequency() const { int32_t status = 0; auto retVal = HAL_GetDutyCycleFrequency(m_handle, &status); FRC_CheckErrorStatus(status, "Channel {}", GetSourceChannel()); - return units::hertz_t{retVal}; + return wpi::units::hertz_t{retVal}; } double DutyCycle::GetOutput() const { @@ -48,18 +48,18 @@ double DutyCycle::GetOutput() const { return retVal; } -units::second_t DutyCycle::GetHighTime() const { +wpi::units::second_t DutyCycle::GetHighTime() const { int32_t status = 0; auto retVal = HAL_GetDutyCycleHighTime(m_handle, &status); FRC_CheckErrorStatus(status, "Channel {}", GetSourceChannel()); - return units::nanosecond_t{static_cast(retVal)}; + return wpi::units::nanosecond_t{static_cast(retVal)}; } int DutyCycle::GetSourceChannel() const { return m_channel; } -void DutyCycle::InitSendable(wpi::SendableBuilder& builder) { +void DutyCycle::InitSendable(wpi::util::SendableBuilder& builder) { builder.SetSmartDashboardType("Duty Cycle"); builder.AddDoubleProperty( "Frequency", [this] { return this->GetFrequency().value(); }, nullptr); diff --git a/wpilibc/src/main/native/cpp/hardware/rotation/DutyCycleEncoder.cpp b/wpilibc/src/main/native/cpp/hardware/rotation/DutyCycleEncoder.cpp index d0be46d51c..46e3351f4c 100644 --- a/wpilibc/src/main/native/cpp/hardware/rotation/DutyCycleEncoder.cpp +++ b/wpilibc/src/main/native/cpp/hardware/rotation/DutyCycleEncoder.cpp @@ -13,7 +13,7 @@ #include "wpi/util/NullDeleter.hpp" #include "wpi/util/sendable/SendableBuilder.hpp" -using namespace frc; +using namespace wpi; DutyCycleEncoder::DutyCycleEncoder(int channel) : m_dutyCycle{std::make_shared(channel)} { @@ -21,12 +21,12 @@ DutyCycleEncoder::DutyCycleEncoder(int channel) } DutyCycleEncoder::DutyCycleEncoder(DutyCycle& dutyCycle) - : m_dutyCycle{&dutyCycle, wpi::NullDeleter{}} { + : m_dutyCycle{&dutyCycle, wpi::util::NullDeleter{}} { Init(1.0, 0.0); } DutyCycleEncoder::DutyCycleEncoder(DutyCycle* dutyCycle) - : m_dutyCycle{dutyCycle, wpi::NullDeleter{}} { + : m_dutyCycle{dutyCycle, wpi::util::NullDeleter{}} { Init(1.0, 0.0); } @@ -43,13 +43,13 @@ DutyCycleEncoder::DutyCycleEncoder(int channel, double fullRange, DutyCycleEncoder::DutyCycleEncoder(DutyCycle& dutyCycle, double fullRange, double expectedZero) - : m_dutyCycle{&dutyCycle, wpi::NullDeleter{}} { + : m_dutyCycle{&dutyCycle, wpi::util::NullDeleter{}} { Init(fullRange, expectedZero); } DutyCycleEncoder::DutyCycleEncoder(DutyCycle* dutyCycle, double fullRange, double expectedZero) - : m_dutyCycle{dutyCycle, wpi::NullDeleter{}} { + : m_dutyCycle{dutyCycle, wpi::util::NullDeleter{}} { Init(fullRange, expectedZero); } @@ -60,19 +60,19 @@ DutyCycleEncoder::DutyCycleEncoder(std::shared_ptr dutyCycle, } void DutyCycleEncoder::Init(double fullRange, double expectedZero) { - m_simDevice = hal::SimDevice{"DutyCycle:DutyCycleEncoder", + m_simDevice = wpi::hal::SimDevice{"DutyCycle:DutyCycleEncoder", m_dutyCycle->GetSourceChannel()}; if (m_simDevice) { m_simPosition = m_simDevice.CreateDouble("Position", false, 0.0); m_simIsConnected = - m_simDevice.CreateBoolean("Connected", hal::SimDevice::kInput, true); + m_simDevice.CreateBoolean("Connected", wpi::hal::SimDevice::kInput, true); } m_fullRange = fullRange; m_expectedZero = expectedZero; - wpi::SendableRegistry::Add(this, "DutyCycle Encoder", + wpi::util::SendableRegistry::Add(this, "DutyCycle Encoder", m_dutyCycle->GetSourceChannel()); } @@ -97,7 +97,7 @@ double DutyCycleEncoder::Get() const { pos = pos * m_fullRange - m_expectedZero; // Map from 0 - Full Range - double result = InputModulus(pos, 0.0, m_fullRange); + double result = wpi::math::InputModulus(pos, 0.0, m_fullRange); // Invert if necessary if (m_isInverted) { return m_fullRange - result; @@ -121,7 +121,7 @@ void DutyCycleEncoder::SetDutyCycleRange(double min, double max) { m_sensorMax = std::clamp(max, 0.0, 1.0); } -units::hertz_t DutyCycleEncoder::GetFrequency() const { +wpi::units::hertz_t DutyCycleEncoder::GetFrequency() const { return m_dutyCycle->GetFrequency(); } @@ -133,7 +133,7 @@ bool DutyCycleEncoder::IsConnected() const { } void DutyCycleEncoder::SetConnectedFrequencyThreshold( - units::hertz_t frequency) { + wpi::units::hertz_t frequency) { if (frequency < 0_Hz) { frequency = 0_Hz; } @@ -144,7 +144,7 @@ void DutyCycleEncoder::SetInverted(bool inverted) { m_isInverted = inverted; } -void DutyCycleEncoder::SetAssumedFrequency(units::hertz_t frequency) { +void DutyCycleEncoder::SetAssumedFrequency(wpi::units::hertz_t frequency) { if (frequency.value() == 0) { m_period = 0_s; } else { @@ -156,7 +156,7 @@ int DutyCycleEncoder::GetSourceChannel() const { return m_dutyCycle->GetSourceChannel(); } -void DutyCycleEncoder::InitSendable(wpi::SendableBuilder& builder) { +void DutyCycleEncoder::InitSendable(wpi::util::SendableBuilder& builder) { builder.SetSmartDashboardType("AbsoluteEncoder"); builder.AddDoubleProperty( "Position", [this] { return this->Get(); }, nullptr); diff --git a/wpilibc/src/main/native/cpp/hardware/rotation/Encoder.cpp b/wpilibc/src/main/native/cpp/hardware/rotation/Encoder.cpp index 217eb9d6bb..047691b652 100644 --- a/wpilibc/src/main/native/cpp/hardware/rotation/Encoder.cpp +++ b/wpilibc/src/main/native/cpp/hardware/rotation/Encoder.cpp @@ -15,7 +15,7 @@ #include "wpi/util/sendable/SendableBuilder.hpp" #include "wpi/util/sendable/SendableRegistry.hpp" -using namespace frc; +using namespace wpi; Encoder::Encoder(int aChannel, int bChannel, bool reverseDirection, EncodingType encodingType) { @@ -35,14 +35,14 @@ void Encoder::Reset() { FRC_CheckErrorStatus(status, "Reset"); } -units::second_t Encoder::GetPeriod() const { +wpi::units::second_t Encoder::GetPeriod() const { int32_t status = 0; double value = HAL_GetEncoderPeriod(m_encoder, &status); FRC_CheckErrorStatus(status, "GetPeriod"); - return units::second_t{value}; + return wpi::units::second_t{value}; } -void Encoder::SetMaxPeriod(units::second_t maxPeriod) { +void Encoder::SetMaxPeriod(wpi::units::second_t maxPeriod) { int32_t status = 0; HAL_SetEncoderMaxPeriod(m_encoder, maxPeriod.value(), &status); FRC_CheckErrorStatus(status, "SetMaxPeriod"); @@ -145,7 +145,7 @@ int Encoder::GetFPGAIndex() const { return val; } -void Encoder::InitSendable(wpi::SendableBuilder& builder) { +void Encoder::InitSendable(wpi::util::SendableBuilder& builder) { int32_t status = 0; HAL_EncoderEncodingType type = HAL_GetEncoderEncodingType(m_encoder, &status); FRC_CheckErrorStatus(status, "GetEncodingType"); @@ -184,7 +184,7 @@ void Encoder::InitEncoder(int aChannel, int bChannel, bool reverseDirection, break; } HAL_ReportUsage(fmt::format("IO[{},{}]", aChannel, bChannel), type); - // wpi::SendableRegistry::Add(this, "Encoder", m_aSource->GetChannel()); + // wpi::util::SendableRegistry::Add(this, "Encoder", m_aSource->GetChannel()); } double Encoder::DecodingScaleFactor() const { diff --git a/wpilibc/src/main/native/cpp/internal/DriverStationModeThread.cpp b/wpilibc/src/main/native/cpp/internal/DriverStationModeThread.cpp index 4412a6d715..7b776f6a17 100644 --- a/wpilibc/src/main/native/cpp/internal/DriverStationModeThread.cpp +++ b/wpilibc/src/main/native/cpp/internal/DriverStationModeThread.cpp @@ -8,7 +8,7 @@ #include "wpi/hal/DriverStation.h" #include "wpi/util/Synchronization.h" -using namespace frc::internal; +using namespace wpi::internal; DriverStationModeThread::DriverStationModeThread() { m_keepAlive = true; @@ -39,13 +39,13 @@ void DriverStationModeThread::InTest(bool entering) { } void DriverStationModeThread::Run() { - wpi::Event event{false, false}; + wpi::util::Event event{false, false}; HAL_ProvideNewDataEventHandle(event.GetHandle()); while (m_keepAlive.load()) { bool timedOut = false; - wpi::WaitForObject(event.GetHandle(), 0.1, &timedOut); - frc::DriverStation::RefreshData(); + wpi::util::WaitForObject(event.GetHandle(), 0.1, &timedOut); + wpi::DriverStation::RefreshData(); if (m_userInDisabled) { HAL_ObserveUserProgramDisabled(); } diff --git a/wpilibc/src/main/native/cpp/motorcontrol/MotorController.cpp b/wpilibc/src/main/native/cpp/motorcontrol/MotorController.cpp index 68ef44e54b..d01d1d78e7 100644 --- a/wpilibc/src/main/native/cpp/motorcontrol/MotorController.cpp +++ b/wpilibc/src/main/native/cpp/motorcontrol/MotorController.cpp @@ -6,9 +6,9 @@ #include "wpi/system/RobotController.hpp" -using namespace frc; +using namespace wpi; -void MotorController::SetVoltage(units::volt_t output) { +void MotorController::SetVoltage(wpi::units::volt_t output) { // NOLINTNEXTLINE(bugprone-integer-division) Set(output / RobotController::GetBatteryVoltage()); } diff --git a/wpilibc/src/main/native/cpp/motorcontrol/MotorControllerGroup.cpp b/wpilibc/src/main/native/cpp/motorcontrol/MotorControllerGroup.cpp index 9bbef758c0..311c71f7b1 100644 --- a/wpilibc/src/main/native/cpp/motorcontrol/MotorControllerGroup.cpp +++ b/wpilibc/src/main/native/cpp/motorcontrol/MotorControllerGroup.cpp @@ -10,7 +10,7 @@ #include "wpi/util/sendable/SendableBuilder.hpp" #include "wpi/util/sendable/SendableRegistry.hpp" -using namespace frc; +using namespace wpi; // Can't use a delegated constructor here because of an MSVC bug. // https://developercommunity.visualstudio.com/content/problem/583/compiler-bug-with-delegating-a-constructor.html @@ -25,11 +25,11 @@ MotorControllerGroup::MotorControllerGroup( void MotorControllerGroup::Initialize() { for (auto& motorController : m_motorControllers) { - wpi::SendableRegistry::AddChild(this, &motorController.get()); + wpi::util::SendableRegistry::AddChild(this, &motorController.get()); } static int instances = 0; ++instances; - wpi::SendableRegistry::Add(this, "MotorControllerGroup", instances); + wpi::util::SendableRegistry::Add(this, "MotorControllerGroup", instances); } void MotorControllerGroup::Set(double speed) { @@ -38,7 +38,7 @@ void MotorControllerGroup::Set(double speed) { } } -void MotorControllerGroup::SetVoltage(units::volt_t output) { +void MotorControllerGroup::SetVoltage(wpi::units::volt_t output) { for (auto motorController : m_motorControllers) { motorController.get().SetVoltage(m_isInverted ? -output : output); } @@ -71,7 +71,7 @@ void MotorControllerGroup::StopMotor() { } } -void MotorControllerGroup::InitSendable(wpi::SendableBuilder& builder) { +void MotorControllerGroup::InitSendable(wpi::util::SendableBuilder& builder) { builder.SetSmartDashboardType("Motor Controller"); builder.SetActuator(true); builder.AddDoubleProperty( diff --git a/wpilibc/src/main/native/cpp/motorcontrol/PWMMotorController.cpp b/wpilibc/src/main/native/cpp/motorcontrol/PWMMotorController.cpp index c4b2e66463..198ed0d358 100644 --- a/wpilibc/src/main/native/cpp/motorcontrol/PWMMotorController.cpp +++ b/wpilibc/src/main/native/cpp/motorcontrol/PWMMotorController.cpp @@ -12,7 +12,7 @@ #include "wpi/util/sendable/SendableBuilder.hpp" #include "wpi/util/sendable/SendableRegistry.hpp" -using namespace frc; +using namespace wpi; void PWMMotorController::Set(double speed) { if (m_isInverted) { @@ -30,7 +30,7 @@ void PWMMotorController::Set(double speed) { Feed(); } -void PWMMotorController::SetVoltage(units::volt_t output) { +void PWMMotorController::SetVoltage(wpi::units::volt_t output) { // NOLINTNEXTLINE(bugprone-integer-division) Set(output / RobotController::GetBatteryVoltage()); } @@ -39,7 +39,7 @@ double PWMMotorController::Get() const { return GetSpeed() * (m_isInverted ? -1.0 : 1.0); } -units::volt_t PWMMotorController::GetVoltage() const { +wpi::units::volt_t PWMMotorController::GetVoltage() const { return Get() * RobotController::GetBatteryVoltage(); } @@ -98,9 +98,9 @@ WPI_IGNORE_DEPRECATED PWMMotorController::PWMMotorController(std::string_view name, int channel) : m_pwm(channel, false) { - wpi::SendableRegistry::Add(this, name, channel); + wpi::util::SendableRegistry::Add(this, name, channel); - m_simDevice = hal::SimDevice{"PWMMotorController", channel}; + m_simDevice = wpi::hal::SimDevice{"PWMMotorController", channel}; if (m_simDevice) { m_simSpeed = m_simDevice.CreateDouble("Speed", true, 0.0); m_pwm.SetSimDevice(m_simDevice); @@ -109,7 +109,7 @@ PWMMotorController::PWMMotorController(std::string_view name, int channel) WPI_UNIGNORE_DEPRECATED -void PWMMotorController::InitSendable(wpi::SendableBuilder& builder) { +void PWMMotorController::InitSendable(wpi::util::SendableBuilder& builder) { builder.SetSmartDashboardType("Motor Controller"); builder.SetActuator(true); builder.AddDoubleProperty( @@ -117,7 +117,7 @@ void PWMMotorController::InitSendable(wpi::SendableBuilder& builder) { [=, this](double value) { Set(value); }); } -units::microsecond_t PWMMotorController::GetMinPositivePwm() const { +wpi::units::microsecond_t PWMMotorController::GetMinPositivePwm() const { if (m_eliminateDeadband) { return m_deadbandMaxPwm; } else { @@ -125,7 +125,7 @@ units::microsecond_t PWMMotorController::GetMinPositivePwm() const { } } -units::microsecond_t PWMMotorController::GetMaxNegativePwm() const { +wpi::units::microsecond_t PWMMotorController::GetMaxNegativePwm() const { if (m_eliminateDeadband) { return m_deadbandMinPwm; } else { @@ -133,11 +133,11 @@ units::microsecond_t PWMMotorController::GetMaxNegativePwm() const { } } -units::microsecond_t PWMMotorController::GetPositiveScaleFactor() const { +wpi::units::microsecond_t PWMMotorController::GetPositiveScaleFactor() const { return m_maxPwm - GetMinPositivePwm(); } -units::microsecond_t PWMMotorController::GetNegativeScaleFactor() const { +wpi::units::microsecond_t PWMMotorController::GetNegativeScaleFactor() const { return GetMaxNegativePwm() - m_minPwm; } @@ -152,15 +152,15 @@ void PWMMotorController::SetSpeed(double speed) { m_simSpeed.Set(speed); } - units::microsecond_t rawValue; + wpi::units::microsecond_t rawValue; if (speed == 0.0) { rawValue = m_centerPwm; } else if (speed > 0.0) { - rawValue = units::microsecond_t{static_cast(std::lround( + rawValue = wpi::units::microsecond_t{static_cast(std::lround( (speed * GetPositiveScaleFactor()).to()))} + GetMinPositivePwm(); } else { - rawValue = units::microsecond_t{static_cast(std::lround( + rawValue = wpi::units::microsecond_t{static_cast(std::lround( (speed * GetNegativeScaleFactor()).to()))} + GetMaxNegativePwm(); } @@ -169,7 +169,7 @@ void PWMMotorController::SetSpeed(double speed) { } double PWMMotorController::GetSpeed() const { - units::microsecond_t rawValue = m_pwm.GetPulseTime(); + wpi::units::microsecond_t rawValue = m_pwm.GetPulseTime(); if (rawValue == 0_us) { return 0.0; @@ -188,11 +188,11 @@ double PWMMotorController::GetSpeed() const { } } -void PWMMotorController::SetBounds(units::microsecond_t maxPwm, - units::microsecond_t deadbandMaxPwm, - units::microsecond_t centerPwm, - units::microsecond_t deadbandMinPwm, - units::microsecond_t minPwm) { +void PWMMotorController::SetBounds(wpi::units::microsecond_t maxPwm, + wpi::units::microsecond_t deadbandMaxPwm, + wpi::units::microsecond_t centerPwm, + wpi::units::microsecond_t deadbandMinPwm, + wpi::units::microsecond_t minPwm) { m_maxPwm = maxPwm; m_deadbandMaxPwm = deadbandMaxPwm; m_centerPwm = centerPwm; diff --git a/wpilibc/src/main/native/cpp/opmode/IterativeRobotBase.cpp b/wpilibc/src/main/native/cpp/opmode/IterativeRobotBase.cpp index 0733ff2c9c..a5ea49f9c5 100644 --- a/wpilibc/src/main/native/cpp/opmode/IterativeRobotBase.cpp +++ b/wpilibc/src/main/native/cpp/opmode/IterativeRobotBase.cpp @@ -12,9 +12,9 @@ #include "wpi/system/Errors.hpp" #include "wpi/util/print.hpp" -using namespace frc; +using namespace wpi; -IterativeRobotBase::IterativeRobotBase(units::second_t period) +IterativeRobotBase::IterativeRobotBase(wpi::units::second_t period) : m_period(period), m_watchdog(period, [this] { PrintLoopOverrunMessage(); }) {} @@ -33,7 +33,7 @@ void IterativeRobotBase::TestInit() {} void IterativeRobotBase::RobotPeriodic() { static bool firstRun = true; if (firstRun) { - wpi::print("Default {}() method... Override me!\n", __FUNCTION__); + wpi::util::print("Default {}() method... Override me!\n", __FUNCTION__); firstRun = false; } } @@ -41,7 +41,7 @@ void IterativeRobotBase::RobotPeriodic() { void IterativeRobotBase::SimulationPeriodic() { static bool firstRun = true; if (firstRun) { - wpi::print("Default {}() method... Override me!\n", __FUNCTION__); + wpi::util::print("Default {}() method... Override me!\n", __FUNCTION__); firstRun = false; } } @@ -49,7 +49,7 @@ void IterativeRobotBase::SimulationPeriodic() { void IterativeRobotBase::DisabledPeriodic() { static bool firstRun = true; if (firstRun) { - wpi::print("Default {}() method... Override me!\n", __FUNCTION__); + wpi::util::print("Default {}() method... Override me!\n", __FUNCTION__); firstRun = false; } } @@ -57,7 +57,7 @@ void IterativeRobotBase::DisabledPeriodic() { void IterativeRobotBase::AutonomousPeriodic() { static bool firstRun = true; if (firstRun) { - wpi::print("Default {}() method... Override me!\n", __FUNCTION__); + wpi::util::print("Default {}() method... Override me!\n", __FUNCTION__); firstRun = false; } } @@ -65,7 +65,7 @@ void IterativeRobotBase::AutonomousPeriodic() { void IterativeRobotBase::TeleopPeriodic() { static bool firstRun = true; if (firstRun) { - wpi::print("Default {}() method... Override me!\n", __FUNCTION__); + wpi::util::print("Default {}() method... Override me!\n", __FUNCTION__); firstRun = false; } } @@ -73,7 +73,7 @@ void IterativeRobotBase::TeleopPeriodic() { void IterativeRobotBase::TestPeriodic() { static bool firstRun = true; if (firstRun) { - wpi::print("Default {}() method... Override me!\n", __FUNCTION__); + wpi::util::print("Default {}() method... Override me!\n", __FUNCTION__); firstRun = false; } } @@ -90,7 +90,7 @@ void IterativeRobotBase::SetNetworkTablesFlushEnabled(bool enabled) { m_ntFlushEnabled = enabled; } -units::second_t IterativeRobotBase::GetPeriod() const { +wpi::units::second_t IterativeRobotBase::GetPeriod() const { return m_period; } @@ -183,7 +183,7 @@ void IterativeRobotBase::LoopFunc() { // Flush NetworkTables if (m_ntFlushEnabled) { - nt::NetworkTableInstance::GetDefault().FlushLocal(); + wpi::nt::NetworkTableInstance::GetDefault().FlushLocal(); } // Warn on loop time overruns diff --git a/wpilibc/src/main/native/cpp/opmode/RobotState.cpp b/wpilibc/src/main/native/cpp/opmode/RobotState.cpp index 9155e7af30..34543aa78c 100644 --- a/wpilibc/src/main/native/cpp/opmode/RobotState.cpp +++ b/wpilibc/src/main/native/cpp/opmode/RobotState.cpp @@ -6,7 +6,7 @@ #include "wpi/driverstation/DriverStation.hpp" -using namespace frc; +using namespace wpi; bool RobotState::IsDisabled() { return DriverStation::IsDisabled(); diff --git a/wpilibc/src/main/native/cpp/opmode/TimedRobot.cpp b/wpilibc/src/main/native/cpp/opmode/TimedRobot.cpp index 04bf0feaf0..07bee23974 100644 --- a/wpilibc/src/main/native/cpp/opmode/TimedRobot.cpp +++ b/wpilibc/src/main/native/cpp/opmode/TimedRobot.cpp @@ -14,7 +14,7 @@ #include "wpi/hal/UsageReporting.h" #include "wpi/system/Errors.hpp" -using namespace frc; +using namespace wpi; void TimedRobot::StartCompetition() { if constexpr (IsSimulation()) { @@ -75,7 +75,7 @@ void TimedRobot::EndCompetition() { HAL_StopNotifier(m_notifier, &status); } -TimedRobot::TimedRobot(units::second_t period) : IterativeRobotBase(period) { +TimedRobot::TimedRobot(wpi::units::second_t period) : IterativeRobotBase(period) { m_startTime = std::chrono::microseconds{RobotController::GetFPGATime()}; AddPeriodic([=, this] { LoopFunc(); }, period); @@ -87,7 +87,7 @@ TimedRobot::TimedRobot(units::second_t period) : IterativeRobotBase(period) { HAL_ReportUsage("Framework", "TimedRobot"); } -TimedRobot::TimedRobot(units::hertz_t frequency) : TimedRobot{1 / frequency} {} +TimedRobot::TimedRobot(wpi::units::hertz_t frequency) : TimedRobot{1 / frequency} {} TimedRobot::~TimedRobot() { if (m_notifier != HAL_kInvalidHandle) { @@ -102,7 +102,7 @@ uint64_t TimedRobot::GetLoopStartTime() { } void TimedRobot::AddPeriodic(std::function callback, - units::second_t period, units::second_t offset) { + wpi::units::second_t period, wpi::units::second_t offset) { m_callbacks.emplace( callback, m_startTime, std::chrono::microseconds{static_cast(period.value() * 1e6)}, diff --git a/wpilibc/src/main/native/cpp/opmode/TimesliceRobot.cpp b/wpilibc/src/main/native/cpp/opmode/TimesliceRobot.cpp index 8dc82edc2a..ab37fcda29 100644 --- a/wpilibc/src/main/native/cpp/opmode/TimesliceRobot.cpp +++ b/wpilibc/src/main/native/cpp/opmode/TimesliceRobot.cpp @@ -6,15 +6,15 @@ #include "wpi/system/Errors.hpp" -using namespace frc; +using namespace wpi; -TimesliceRobot::TimesliceRobot(units::second_t robotPeriodicAllocation, - units::second_t controllerPeriod) +TimesliceRobot::TimesliceRobot(wpi::units::second_t robotPeriodicAllocation, + wpi::units::second_t controllerPeriod) : m_nextOffset{robotPeriodicAllocation}, m_controllerPeriod{controllerPeriod} {} void TimesliceRobot::Schedule(std::function func, - units::second_t allocation) { + wpi::units::second_t allocation) { if (m_nextOffset + allocation > m_controllerPeriod) { throw FRC_MakeError(err::Error, "Function scheduled at offset {} with allocation {} " diff --git a/wpilibc/src/main/native/cpp/simulation/ADXL345Sim.cpp b/wpilibc/src/main/native/cpp/simulation/ADXL345Sim.cpp index aa00c2b68a..c09feed64d 100644 --- a/wpilibc/src/main/native/cpp/simulation/ADXL345Sim.cpp +++ b/wpilibc/src/main/native/cpp/simulation/ADXL345Sim.cpp @@ -7,10 +7,10 @@ #include "wpi/hardware/accelerometer/ADXL345_I2C.hpp" #include "wpi/simulation/SimDeviceSim.hpp" -using namespace frc::sim; +using namespace wpi::sim; -ADXL345Sim::ADXL345Sim(const frc::ADXL345_I2C& accel) { - frc::sim::SimDeviceSim deviceSim{"Accel:ADXL345_I2C", accel.GetI2CPort(), +ADXL345Sim::ADXL345Sim(const wpi::ADXL345_I2C& accel) { + wpi::sim::SimDeviceSim deviceSim{"Accel:ADXL345_I2C", accel.GetI2CPort(), accel.GetI2CDeviceAddress()}; m_simX = deviceSim.GetDouble("x"); m_simY = deviceSim.GetDouble("y"); diff --git a/wpilibc/src/main/native/cpp/simulation/AddressableLEDSim.cpp b/wpilibc/src/main/native/cpp/simulation/AddressableLEDSim.cpp index 1b5b3b8574..59cd3ac7cb 100644 --- a/wpilibc/src/main/native/cpp/simulation/AddressableLEDSim.cpp +++ b/wpilibc/src/main/native/cpp/simulation/AddressableLEDSim.cpp @@ -10,8 +10,8 @@ #include "wpi/hal/simulation/AddressableLEDData.h" #include "wpi/hardware/led/AddressableLED.hpp" -using namespace frc; -using namespace frc::sim; +using namespace wpi; +using namespace wpi::sim; AddressableLEDSim::AddressableLEDSim(int channel) : m_channel{channel} {} diff --git a/wpilibc/src/main/native/cpp/simulation/AnalogEncoderSim.cpp b/wpilibc/src/main/native/cpp/simulation/AnalogEncoderSim.cpp index c952f45398..2b924f4025 100644 --- a/wpilibc/src/main/native/cpp/simulation/AnalogEncoderSim.cpp +++ b/wpilibc/src/main/native/cpp/simulation/AnalogEncoderSim.cpp @@ -7,10 +7,10 @@ #include "wpi/hardware/rotation/AnalogEncoder.hpp" #include "wpi/simulation/SimDeviceSim.hpp" -using namespace frc::sim; +using namespace wpi::sim; -AnalogEncoderSim::AnalogEncoderSim(const frc::AnalogEncoder& encoder) { - frc::sim::SimDeviceSim deviceSim{"AnalogEncoder", encoder.GetChannel()}; +AnalogEncoderSim::AnalogEncoderSim(const wpi::AnalogEncoder& encoder) { + wpi::sim::SimDeviceSim deviceSim{"AnalogEncoder", encoder.GetChannel()}; m_positionSim = deviceSim.GetDouble("Position"); } diff --git a/wpilibc/src/main/native/cpp/simulation/AnalogInputSim.cpp b/wpilibc/src/main/native/cpp/simulation/AnalogInputSim.cpp index 1d7604f68b..58e742baa2 100644 --- a/wpilibc/src/main/native/cpp/simulation/AnalogInputSim.cpp +++ b/wpilibc/src/main/native/cpp/simulation/AnalogInputSim.cpp @@ -9,8 +9,8 @@ #include "wpi/hal/simulation/AnalogInData.h" #include "wpi/hardware/discrete/AnalogInput.hpp" -using namespace frc; -using namespace frc::sim; +using namespace wpi; +using namespace wpi::sim; AnalogInputSim::AnalogInputSim(const AnalogInput& analogInput) : m_index{analogInput.GetChannel()} {} diff --git a/wpilibc/src/main/native/cpp/simulation/CTREPCMSim.cpp b/wpilibc/src/main/native/cpp/simulation/CTREPCMSim.cpp index b2a41457a0..65247619e7 100644 --- a/wpilibc/src/main/native/cpp/simulation/CTREPCMSim.cpp +++ b/wpilibc/src/main/native/cpp/simulation/CTREPCMSim.cpp @@ -9,8 +9,8 @@ #include "wpi/hal/simulation/CTREPCMData.h" #include "wpi/util/SensorUtil.hpp" -using namespace frc; -using namespace frc::sim; +using namespace wpi; +using namespace wpi::sim; CTREPCMSim::CTREPCMSim() : PneumaticsBaseSim{SensorUtil::GetDefaultCTREPCMModule()} {} diff --git a/wpilibc/src/main/native/cpp/simulation/CallbackStore.cpp b/wpilibc/src/main/native/cpp/simulation/CallbackStore.cpp index 0d18b0c325..ae99e5e276 100644 --- a/wpilibc/src/main/native/cpp/simulation/CallbackStore.cpp +++ b/wpilibc/src/main/native/cpp/simulation/CallbackStore.cpp @@ -6,15 +6,15 @@ #include -using namespace frc; -using namespace frc::sim; +using namespace wpi; +using namespace wpi::sim; -void frc::sim::CallbackStoreThunk(const char* name, void* param, +void wpi::sim::CallbackStoreThunk(const char* name, void* param, const HAL_Value* value) { reinterpret_cast(param)->callback(name, value); } -void frc::sim::ConstBufferCallbackStoreThunk(const char* name, void* param, +void wpi::sim::ConstBufferCallbackStoreThunk(const char* name, void* param, const unsigned char* buffer, unsigned int count) { reinterpret_cast(param)->constBufferCallback(name, buffer, diff --git a/wpilibc/src/main/native/cpp/simulation/DCMotorSim.cpp b/wpilibc/src/main/native/cpp/simulation/DCMotorSim.cpp index 10786d96ca..d7b14fc3f7 100644 --- a/wpilibc/src/main/native/cpp/simulation/DCMotorSim.cpp +++ b/wpilibc/src/main/native/cpp/simulation/DCMotorSim.cpp @@ -7,11 +7,11 @@ #include "wpi/system/RobotController.hpp" #include "wpi/util/MathExtras.hpp" -using namespace frc; -using namespace frc::sim; +using namespace wpi; +using namespace wpi::sim; -DCMotorSim::DCMotorSim(const LinearSystem<2, 1, 2>& plant, - const DCMotor& gearbox, +DCMotorSim::DCMotorSim(const wpi::math::LinearSystem<2, 1, 2>& plant, + const wpi::math::DCMotor& gearbox, const std::array& measurementStdDevs) : LinearSystemSim<2, 1, 2>(plant, measurementStdDevs), m_gearbox(gearbox), @@ -36,56 +36,56 @@ DCMotorSim::DCMotorSim(const LinearSystem<2, 1, 2>& plant, m_j(m_gearing * gearbox.Kt.value() / (gearbox.R.value() * m_plant.B(1, 0))) {} -void DCMotorSim::SetState(units::radian_t angularPosition, - units::radians_per_second_t angularVelocity) { - SetState(Vectord<2>{angularPosition, angularVelocity}); +void DCMotorSim::SetState(wpi::units::radian_t angularPosition, + wpi::units::radians_per_second_t angularVelocity) { + SetState(wpi::math::Vectord<2>{angularPosition, angularVelocity}); } -void DCMotorSim::SetAngle(units::radian_t angularPosition) { +void DCMotorSim::SetAngle(wpi::units::radian_t angularPosition) { SetState(angularPosition, GetAngularVelocity()); } void DCMotorSim::SetAngularVelocity( - units::radians_per_second_t angularVelocity) { + wpi::units::radians_per_second_t angularVelocity) { SetState(GetAngularPosition(), angularVelocity); } -units::radian_t DCMotorSim::GetAngularPosition() const { - return units::radian_t{GetOutput(0)}; +wpi::units::radian_t DCMotorSim::GetAngularPosition() const { + return wpi::units::radian_t{GetOutput(0)}; } -units::radians_per_second_t DCMotorSim::GetAngularVelocity() const { - return units::radians_per_second_t{GetOutput(1)}; +wpi::units::radians_per_second_t DCMotorSim::GetAngularVelocity() const { + return wpi::units::radians_per_second_t{GetOutput(1)}; } -units::radians_per_second_squared_t DCMotorSim::GetAngularAcceleration() const { - return units::radians_per_second_squared_t{ +wpi::units::radians_per_second_squared_t DCMotorSim::GetAngularAcceleration() const { + return wpi::units::radians_per_second_squared_t{ (m_plant.A() * m_x + m_plant.B() * m_u)(1, 0)}; } -units::newton_meter_t DCMotorSim::GetTorque() const { - return units::newton_meter_t{GetAngularAcceleration().value() * m_j.value()}; +wpi::units::newton_meter_t DCMotorSim::GetTorque() const { + return wpi::units::newton_meter_t{GetAngularAcceleration().value() * m_j.value()}; } -units::ampere_t DCMotorSim::GetCurrentDraw() const { +wpi::units::ampere_t DCMotorSim::GetCurrentDraw() const { // I = V / R - omega / (Kv * R) // Reductions are greater than 1, so a reduction of 10:1 would mean the motor // is spinning 10x faster than the output. - return m_gearbox.Current(units::radians_per_second_t{m_x(1)} * m_gearing, - units::volt_t{m_u(0)}) * - wpi::sgn(m_u(0)); + return m_gearbox.Current(wpi::units::radians_per_second_t{m_x(1)} * m_gearing, + wpi::units::volt_t{m_u(0)}) * + wpi::util::sgn(m_u(0)); } -units::volt_t DCMotorSim::GetInputVoltage() const { - return units::volt_t{GetInput(0)}; +wpi::units::volt_t DCMotorSim::GetInputVoltage() const { + return wpi::units::volt_t{GetInput(0)}; } -void DCMotorSim::SetInputVoltage(units::volt_t voltage) { - SetInput(Vectord<1>{voltage.value()}); - ClampInput(frc::RobotController::GetBatteryVoltage().value()); +void DCMotorSim::SetInputVoltage(wpi::units::volt_t voltage) { + SetInput(wpi::math::Vectord<1>{voltage.value()}); + ClampInput(wpi::RobotController::GetBatteryVoltage().value()); } -const DCMotor& DCMotorSim::GetGearbox() const { +const wpi::math::DCMotor& DCMotorSim::GetGearbox() const { return m_gearbox; } @@ -93,6 +93,6 @@ double DCMotorSim::GetGearing() const { return m_gearing; } -units::kilogram_square_meter_t DCMotorSim::GetJ() const { +wpi::units::kilogram_square_meter_t DCMotorSim::GetJ() const { return m_j; } diff --git a/wpilibc/src/main/native/cpp/simulation/DIOSim.cpp b/wpilibc/src/main/native/cpp/simulation/DIOSim.cpp index 4e27727ef8..65bdf13709 100644 --- a/wpilibc/src/main/native/cpp/simulation/DIOSim.cpp +++ b/wpilibc/src/main/native/cpp/simulation/DIOSim.cpp @@ -10,8 +10,8 @@ #include "wpi/hardware/discrete/DigitalInput.hpp" #include "wpi/hardware/discrete/DigitalOutput.hpp" -using namespace frc; -using namespace frc::sim; +using namespace wpi; +using namespace wpi::sim; DIOSim::DIOSim(const DigitalInput& input) : m_index{input.GetChannel()} {} diff --git a/wpilibc/src/main/native/cpp/simulation/DifferentialDrivetrainSim.cpp b/wpilibc/src/main/native/cpp/simulation/DifferentialDrivetrainSim.cpp index becdcbe7f8..e9000db1d0 100644 --- a/wpilibc/src/main/native/cpp/simulation/DifferentialDrivetrainSim.cpp +++ b/wpilibc/src/main/native/cpp/simulation/DifferentialDrivetrainSim.cpp @@ -12,12 +12,12 @@ #include "wpi/system/RobotController.hpp" #include "wpi/util/MathExtras.hpp" -using namespace frc; -using namespace frc::sim; +using namespace wpi; +using namespace wpi::sim; DifferentialDrivetrainSim::DifferentialDrivetrainSim( - LinearSystem<2, 2, 2> plant, units::meter_t trackwidth, DCMotor driveMotor, - double gearRatio, units::meter_t wheelRadius, + wpi::math::LinearSystem<2, 2, 2> plant, wpi::units::meter_t trackwidth, wpi::math::DCMotor driveMotor, + double gearRatio, wpi::units::meter_t wheelRadius, const std::array& measurementStdDevs) : m_plant(std::move(plant)), m_rb(trackwidth / 2.0), @@ -32,22 +32,22 @@ DifferentialDrivetrainSim::DifferentialDrivetrainSim( } DifferentialDrivetrainSim::DifferentialDrivetrainSim( - frc::DCMotor driveMotor, double gearing, units::kilogram_square_meter_t J, - units::kilogram_t mass, units::meter_t wheelRadius, - units::meter_t trackwidth, const std::array& measurementStdDevs) + wpi::math::DCMotor driveMotor, double gearing, wpi::units::kilogram_square_meter_t J, + wpi::units::kilogram_t mass, wpi::units::meter_t wheelRadius, + wpi::units::meter_t trackwidth, const std::array& measurementStdDevs) : DifferentialDrivetrainSim( - frc::LinearSystemId::DrivetrainVelocitySystem( + wpi::math::LinearSystemId::DrivetrainVelocitySystem( driveMotor, mass, wheelRadius, trackwidth / 2.0, J, gearing), trackwidth, driveMotor, gearing, wheelRadius, measurementStdDevs) {} Eigen::Vector2d DifferentialDrivetrainSim::ClampInput( const Eigen::Vector2d& u) { - return frc::DesaturateInputVector<2>(u, - frc::RobotController::GetInputVoltage()); + return wpi::math::DesaturateInputVector<2>(u, + wpi::RobotController::GetInputVoltage()); } -void DifferentialDrivetrainSim::SetInputs(units::volt_t leftVoltage, - units::volt_t rightVoltage) { +void DifferentialDrivetrainSim::SetInputs(wpi::units::volt_t leftVoltage, + wpi::units::volt_t rightVoltage) { m_u << leftVoltage.value(), rightVoltage.value(); m_u = ClampInput(m_u); } @@ -56,20 +56,20 @@ void DifferentialDrivetrainSim::SetGearing(double newGearing) { m_currentGearing = newGearing; } -void DifferentialDrivetrainSim::Update(units::second_t dt) { - m_x = RKDP([this](auto& x, auto& u) { return Dynamics(x, u); }, m_x, m_u, dt); - m_y = m_x + frc::MakeWhiteNoiseVector<7>(m_measurementStdDevs); +void DifferentialDrivetrainSim::Update(wpi::units::second_t dt) { + m_x = wpi::math::RKDP([this](auto& x, auto& u) { return Dynamics(x, u); }, m_x, m_u, dt); + m_y = m_x + wpi::math::MakeWhiteNoiseVector<7>(m_measurementStdDevs); } double DifferentialDrivetrainSim::GetGearing() const { return m_currentGearing; } -Vectord<7> DifferentialDrivetrainSim::GetOutput() const { +wpi::math::Vectord<7> DifferentialDrivetrainSim::GetOutput() const { return m_y; } -Vectord<7> DifferentialDrivetrainSim::GetState() const { +wpi::math::Vectord<7> DifferentialDrivetrainSim::GetState() const { return m_x; } @@ -81,41 +81,41 @@ double DifferentialDrivetrainSim::GetState(int state) const { return m_x(state); } -Rotation2d DifferentialDrivetrainSim::GetHeading() const { - return units::radian_t{GetOutput(State::kHeading)}; +wpi::math::Rotation2d DifferentialDrivetrainSim::GetHeading() const { + return wpi::units::radian_t{GetOutput(State::kHeading)}; } -Pose2d DifferentialDrivetrainSim::GetPose() const { - return Pose2d{units::meter_t{GetOutput(State::kX)}, - units::meter_t{GetOutput(State::kY)}, GetHeading()}; +wpi::math::Pose2d DifferentialDrivetrainSim::GetPose() const { + return wpi::math::Pose2d{wpi::units::meter_t{GetOutput(State::kX)}, + wpi::units::meter_t{GetOutput(State::kY)}, GetHeading()}; } -units::ampere_t DifferentialDrivetrainSim::GetLeftCurrentDraw() const { - return m_motor.Current(units::radians_per_second_t{m_x(State::kLeftVelocity) * +wpi::units::ampere_t DifferentialDrivetrainSim::GetLeftCurrentDraw() const { + return m_motor.Current(wpi::units::radians_per_second_t{m_x(State::kLeftVelocity) * m_currentGearing / m_wheelRadius.value()}, - units::volt_t{m_u(0)}) * - wpi::sgn(m_u(0)); + wpi::units::volt_t{m_u(0)}) * + wpi::util::sgn(m_u(0)); } -units::ampere_t DifferentialDrivetrainSim::GetRightCurrentDraw() const { +wpi::units::ampere_t DifferentialDrivetrainSim::GetRightCurrentDraw() const { return m_motor.Current( - units::radians_per_second_t{m_x(State::kRightVelocity) * + wpi::units::radians_per_second_t{m_x(State::kRightVelocity) * m_currentGearing / m_wheelRadius.value()}, - units::volt_t{m_u(1)}) * - wpi::sgn(m_u(1)); + wpi::units::volt_t{m_u(1)}) * + wpi::util::sgn(m_u(1)); } -units::ampere_t DifferentialDrivetrainSim::GetCurrentDraw() const { +wpi::units::ampere_t DifferentialDrivetrainSim::GetCurrentDraw() const { return GetLeftCurrentDraw() + GetRightCurrentDraw(); } -void DifferentialDrivetrainSim::SetState(const Vectord<7>& state) { +void DifferentialDrivetrainSim::SetState(const wpi::math::Vectord<7>& state) { m_x = state; } -void DifferentialDrivetrainSim::SetPose(const frc::Pose2d& pose) { +void DifferentialDrivetrainSim::SetPose(const wpi::math::Pose2d& pose) { m_x(State::kX) = pose.X().value(); m_x(State::kY) = pose.Y().value(); m_x(State::kHeading) = pose.Rotation().Radians().value(); @@ -123,19 +123,19 @@ void DifferentialDrivetrainSim::SetPose(const frc::Pose2d& pose) { m_x(State::kRightPosition) = 0; } -Vectord<7> DifferentialDrivetrainSim::Dynamics(const Vectord<7>& x, +wpi::math::Vectord<7> DifferentialDrivetrainSim::Dynamics(const wpi::math::Vectord<7>& x, const Eigen::Vector2d& u) { // Because G² can be factored out of A, we can divide by the old ratio // squared and multiply by the new ratio squared to get a new drivetrain // model. - Matrixd<4, 2> B; + wpi::math::Matrixd<4, 2> B; B.block<2, 2>(0, 0) = m_plant.B() * m_currentGearing * m_currentGearing / m_originalGearing / m_originalGearing; B.block<2, 2>(2, 0).setZero(); // Because G can be factored out of B, we can divide by the old ratio and // multiply by the new ratio to get a new drivetrain model. - Matrixd<4, 4> A; + wpi::math::Matrixd<4, 4> A; A.block<2, 2>(0, 0) = m_plant.A() * m_currentGearing / m_originalGearing; A.block<2, 2>(2, 0).setIdentity(); @@ -143,7 +143,7 @@ Vectord<7> DifferentialDrivetrainSim::Dynamics(const Vectord<7>& x, double v = (x(State::kLeftVelocity) + x(State::kRightVelocity)) / 2.0; - Vectord<7> xdot; + wpi::math::Vectord<7> xdot; xdot(0) = v * std::cos(x(State::kHeading)); xdot(1) = v * std::sin(x(State::kHeading)); xdot(2) = diff --git a/wpilibc/src/main/native/cpp/simulation/DigitalPWMSim.cpp b/wpilibc/src/main/native/cpp/simulation/DigitalPWMSim.cpp index 46b6eae653..daa69a098c 100644 --- a/wpilibc/src/main/native/cpp/simulation/DigitalPWMSim.cpp +++ b/wpilibc/src/main/native/cpp/simulation/DigitalPWMSim.cpp @@ -10,8 +10,8 @@ #include "wpi/hal/simulation/DigitalPWMData.h" #include "wpi/hardware/discrete/DigitalOutput.hpp" -using namespace frc; -using namespace frc::sim; +using namespace wpi; +using namespace wpi::sim; DigitalPWMSim::DigitalPWMSim(const DigitalOutput& digitalOutput) : m_index{digitalOutput.GetChannel()} {} diff --git a/wpilibc/src/main/native/cpp/simulation/DoubleSolenoidSim.cpp b/wpilibc/src/main/native/cpp/simulation/DoubleSolenoidSim.cpp index 5501dc3db2..c3b3b2a7c8 100644 --- a/wpilibc/src/main/native/cpp/simulation/DoubleSolenoidSim.cpp +++ b/wpilibc/src/main/native/cpp/simulation/DoubleSolenoidSim.cpp @@ -9,8 +9,8 @@ #include "wpi/hardware/pneumatic/PneumaticsBase.hpp" -using namespace frc; -using namespace frc::sim; +using namespace wpi; +using namespace wpi::sim; DoubleSolenoidSim::DoubleSolenoidSim( std::shared_ptr moduleSim, int fwd, int rev) diff --git a/wpilibc/src/main/native/cpp/simulation/DriverStationSim.cpp b/wpilibc/src/main/native/cpp/simulation/DriverStationSim.cpp index d040cdc31c..28da8ad988 100644 --- a/wpilibc/src/main/native/cpp/simulation/DriverStationSim.cpp +++ b/wpilibc/src/main/native/cpp/simulation/DriverStationSim.cpp @@ -11,8 +11,8 @@ #include "wpi/hal/simulation/DriverStationData.h" #include "wpi/hal/simulation/MockHooks.h" -using namespace frc; -using namespace frc::sim; +using namespace wpi; +using namespace wpi::sim; std::unique_ptr DriverStationSim::RegisterEnabledCallback( NotifyCallback callback, bool initialNotify) { @@ -153,12 +153,12 @@ void DriverStationSim::SetMatchTime(double matchTime) { } void DriverStationSim::NotifyNewData() { - wpi::Event waitEvent{true}; + wpi::util::Event waitEvent{true}; HAL_ProvideNewDataEventHandle(waitEvent.GetHandle()); HALSIM_NotifyDriverStationNewData(); - wpi::WaitForObject(waitEvent.GetHandle()); + wpi::util::WaitForObject(waitEvent.GetHandle()); HAL_RemoveNewDataEventHandle(waitEvent.GetHandle()); - frc::DriverStation::RefreshData(); + wpi::DriverStation::RefreshData(); } void DriverStationSim::SetSendError(bool shouldSend) { @@ -266,17 +266,17 @@ void DriverStationSim::SetJoystickType(int stick, int type) { } void DriverStationSim::SetJoystickName(int stick, std::string_view name) { - auto str = wpi::make_string(name); + auto str = wpi::util::make_string(name); HALSIM_SetJoystickName(stick, &str); } void DriverStationSim::SetGameSpecificMessage(std::string_view message) { - auto str = wpi::make_string(message); + auto str = wpi::util::make_string(message); HALSIM_SetGameSpecificMessage(&str); } void DriverStationSim::SetEventName(std::string_view name) { - auto str = wpi::make_string(name); + auto str = wpi::util::make_string(name); HALSIM_SetEventName(&str); } diff --git a/wpilibc/src/main/native/cpp/simulation/DutyCycleEncoderSim.cpp b/wpilibc/src/main/native/cpp/simulation/DutyCycleEncoderSim.cpp index 7c7fb9b852..5dee8c152c 100644 --- a/wpilibc/src/main/native/cpp/simulation/DutyCycleEncoderSim.cpp +++ b/wpilibc/src/main/native/cpp/simulation/DutyCycleEncoderSim.cpp @@ -7,13 +7,13 @@ #include "wpi/hardware/rotation/DutyCycleEncoder.hpp" #include "wpi/simulation/SimDeviceSim.hpp" -using namespace frc::sim; +using namespace wpi::sim; -DutyCycleEncoderSim::DutyCycleEncoderSim(const frc::DutyCycleEncoder& encoder) +DutyCycleEncoderSim::DutyCycleEncoderSim(const wpi::DutyCycleEncoder& encoder) : DutyCycleEncoderSim{encoder.GetSourceChannel()} {} DutyCycleEncoderSim::DutyCycleEncoderSim(int channel) { - frc::sim::SimDeviceSim deviceSim{"DutyCycle:DutyCycleEncoder", channel}; + wpi::sim::SimDeviceSim deviceSim{"DutyCycle:DutyCycleEncoder", channel}; m_simPosition = deviceSim.GetDouble("Position"); m_simIsConnected = deviceSim.GetBoolean("Connected"); } diff --git a/wpilibc/src/main/native/cpp/simulation/DutyCycleSim.cpp b/wpilibc/src/main/native/cpp/simulation/DutyCycleSim.cpp index 5bbe46632b..a98f1a378e 100644 --- a/wpilibc/src/main/native/cpp/simulation/DutyCycleSim.cpp +++ b/wpilibc/src/main/native/cpp/simulation/DutyCycleSim.cpp @@ -10,8 +10,8 @@ #include "wpi/hal/simulation/DutyCycleData.h" #include "wpi/hardware/rotation/DutyCycle.hpp" -using namespace frc; -using namespace frc::sim; +using namespace wpi; +using namespace wpi::sim; DutyCycleSim::DutyCycleSim(const DutyCycle& dutyCycle) : m_index{dutyCycle.GetSourceChannel()} {} @@ -46,11 +46,11 @@ std::unique_ptr DutyCycleSim::RegisterFrequencyCallback( return store; } -units::hertz_t DutyCycleSim::GetFrequency() const { - return units::hertz_t{HALSIM_GetDutyCycleFrequency(m_index)}; +wpi::units::hertz_t DutyCycleSim::GetFrequency() const { + return wpi::units::hertz_t{HALSIM_GetDutyCycleFrequency(m_index)}; } -void DutyCycleSim::SetFrequency(units::hertz_t frequency) { +void DutyCycleSim::SetFrequency(wpi::units::hertz_t frequency) { HALSIM_SetDutyCycleFrequency(m_index, frequency.value()); } diff --git a/wpilibc/src/main/native/cpp/simulation/ElevatorSim.cpp b/wpilibc/src/main/native/cpp/simulation/ElevatorSim.cpp index 605bfe38e1..aab83e05c3 100644 --- a/wpilibc/src/main/native/cpp/simulation/ElevatorSim.cpp +++ b/wpilibc/src/main/native/cpp/simulation/ElevatorSim.cpp @@ -9,13 +9,13 @@ #include "wpi/system/RobotController.hpp" #include "wpi/util/MathExtras.hpp" -using namespace frc; -using namespace frc::sim; +using namespace wpi; +using namespace wpi::sim; -ElevatorSim::ElevatorSim(const LinearSystem<2, 1, 2>& plant, - const DCMotor& gearbox, units::meter_t minHeight, - units::meter_t maxHeight, bool simulateGravity, - units::meter_t startingHeight, +ElevatorSim::ElevatorSim(const wpi::math::LinearSystem<2, 1, 2>& plant, + const wpi::math::DCMotor& gearbox, wpi::units::meter_t minHeight, + wpi::units::meter_t maxHeight, bool simulateGravity, + wpi::units::meter_t startingHeight, const std::array& measurementStdDevs) : LinearSystemSim(plant, measurementStdDevs), m_gearbox(gearbox), @@ -25,100 +25,100 @@ ElevatorSim::ElevatorSim(const LinearSystem<2, 1, 2>& plant, SetState(startingHeight, 0_mps); } -ElevatorSim::ElevatorSim(const DCMotor& gearbox, double gearing, - units::kilogram_t carriageMass, - units::meter_t drumRadius, units::meter_t minHeight, - units::meter_t maxHeight, bool simulateGravity, - units::meter_t startingHeight, +ElevatorSim::ElevatorSim(const wpi::math::DCMotor& gearbox, double gearing, + wpi::units::kilogram_t carriageMass, + wpi::units::meter_t drumRadius, wpi::units::meter_t minHeight, + wpi::units::meter_t maxHeight, bool simulateGravity, + wpi::units::meter_t startingHeight, const std::array& measurementStdDevs) - : ElevatorSim(LinearSystemId::ElevatorSystem(gearbox, carriageMass, + : ElevatorSim(wpi::math::LinearSystemId::ElevatorSystem(gearbox, carriageMass, drumRadius, gearing), gearbox, minHeight, maxHeight, simulateGravity, startingHeight, measurementStdDevs) {} template - requires std::same_as || - std::same_as + requires std::same_as || + std::same_as ElevatorSim::ElevatorSim(decltype(1_V / Velocity_t(1)) kV, decltype(1_V / Acceleration_t(1)) kA, - const DCMotor& gearbox, units::meter_t minHeight, - units::meter_t maxHeight, bool simulateGravity, - units::meter_t startingHeight, + const wpi::math::DCMotor& gearbox, wpi::units::meter_t minHeight, + wpi::units::meter_t maxHeight, bool simulateGravity, + wpi::units::meter_t startingHeight, const std::array& measurementStdDevs) - : ElevatorSim(LinearSystemId::IdentifyPositionSystem(kV, kA), gearbox, + : ElevatorSim(wpi::math::LinearSystemId::IdentifyPositionSystem(kV, kA), gearbox, minHeight, maxHeight, simulateGravity, startingHeight, measurementStdDevs) {} -void ElevatorSim::SetState(units::meter_t position, - units::meters_per_second_t velocity) { +void ElevatorSim::SetState(wpi::units::meter_t position, + wpi::units::meters_per_second_t velocity) { SetState( - Vectord<2>{std::clamp(position, m_minHeight, m_maxHeight), velocity}); + wpi::math::Vectord<2>{std::clamp(position, m_minHeight, m_maxHeight), velocity}); } -bool ElevatorSim::WouldHitLowerLimit(units::meter_t elevatorHeight) const { +bool ElevatorSim::WouldHitLowerLimit(wpi::units::meter_t elevatorHeight) const { return elevatorHeight <= m_minHeight; } -bool ElevatorSim::WouldHitUpperLimit(units::meter_t elevatorHeight) const { +bool ElevatorSim::WouldHitUpperLimit(wpi::units::meter_t elevatorHeight) const { return elevatorHeight >= m_maxHeight; } bool ElevatorSim::HasHitLowerLimit() const { - return WouldHitLowerLimit(units::meter_t{m_y(0)}); + return WouldHitLowerLimit(wpi::units::meter_t{m_y(0)}); } bool ElevatorSim::HasHitUpperLimit() const { - return WouldHitUpperLimit(units::meter_t{m_y(0)}); + return WouldHitUpperLimit(wpi::units::meter_t{m_y(0)}); } -units::meter_t ElevatorSim::GetPosition() const { - return units::meter_t{m_y(0)}; +wpi::units::meter_t ElevatorSim::GetPosition() const { + return wpi::units::meter_t{m_y(0)}; } -units::meters_per_second_t ElevatorSim::GetVelocity() const { - return units::meters_per_second_t{m_x(1)}; +wpi::units::meters_per_second_t ElevatorSim::GetVelocity() const { + return wpi::units::meters_per_second_t{m_x(1)}; } -units::ampere_t ElevatorSim::GetCurrentDraw() const { +wpi::units::ampere_t ElevatorSim::GetCurrentDraw() const { // I = V / R - omega / (Kv * R) // Reductions are greater than 1, so a reduction of 10:1 would mean the motor // is spinning 10x faster than the output. double kA = 1.0 / m_plant.B(1, 0); - using Kv_t = units::unit_t>>; + using Kv_t = wpi::units::unit_t>>; Kv_t Kv = Kv_t{kA * m_plant.A(1, 1)}; - units::meters_per_second_t velocity{m_x(1)}; - units::radians_per_second_t motorVelocity = velocity * Kv * m_gearbox.Kv; + wpi::units::meters_per_second_t velocity{m_x(1)}; + wpi::units::radians_per_second_t motorVelocity = velocity * Kv * m_gearbox.Kv; // Perform calculation and return. - return m_gearbox.Current(motorVelocity, units::volt_t{m_u(0)}) * - wpi::sgn(m_u(0)); + return m_gearbox.Current(motorVelocity, wpi::units::volt_t{m_u(0)}) * + wpi::util::sgn(m_u(0)); } -void ElevatorSim::SetInputVoltage(units::volt_t voltage) { - SetInput(Vectord<1>{voltage.value()}); - ClampInput(frc::RobotController::GetBatteryVoltage().value()); +void ElevatorSim::SetInputVoltage(wpi::units::volt_t voltage) { + SetInput(wpi::math::Vectord<1>{voltage.value()}); + ClampInput(wpi::RobotController::GetBatteryVoltage().value()); } -Vectord<2> ElevatorSim::UpdateX(const Vectord<2>& currentXhat, - const Vectord<1>& u, units::second_t dt) { - auto updatedXhat = RKDP( - [&](const Vectord<2>& x, const Vectord<1>& u_) -> Vectord<2> { - Vectord<2> xdot = m_plant.A() * x + m_plant.B() * u; +wpi::math::Vectord<2> ElevatorSim::UpdateX(const wpi::math::Vectord<2>& currentXhat, + const wpi::math::Vectord<1>& u, wpi::units::second_t dt) { + auto updatedXhat = wpi::math::RKDP( + [&](const wpi::math::Vectord<2>& x, const wpi::math::Vectord<1>& u_) -> wpi::math::Vectord<2> { + wpi::math::Vectord<2> xdot = m_plant.A() * x + m_plant.B() * u; if (m_simulateGravity) { - xdot += Vectord<2>{0.0, -9.8}; + xdot += wpi::math::Vectord<2>{0.0, -9.8}; } return xdot; }, currentXhat, u, dt); // Check for collision after updating x-hat. - if (WouldHitLowerLimit(units::meter_t{updatedXhat(0)})) { - return Vectord<2>{m_minHeight.value(), 0.0}; + if (WouldHitLowerLimit(wpi::units::meter_t{updatedXhat(0)})) { + return wpi::math::Vectord<2>{m_minHeight.value(), 0.0}; } - if (WouldHitUpperLimit(units::meter_t{updatedXhat(0)})) { - return Vectord<2>{m_maxHeight.value(), 0.0}; + if (WouldHitUpperLimit(wpi::units::meter_t{updatedXhat(0)})) { + return wpi::math::Vectord<2>{m_maxHeight.value(), 0.0}; } return updatedXhat; } diff --git a/wpilibc/src/main/native/cpp/simulation/EncoderSim.cpp b/wpilibc/src/main/native/cpp/simulation/EncoderSim.cpp index cbf030ff48..1168a786e9 100644 --- a/wpilibc/src/main/native/cpp/simulation/EncoderSim.cpp +++ b/wpilibc/src/main/native/cpp/simulation/EncoderSim.cpp @@ -10,8 +10,8 @@ #include "wpi/hal/simulation/EncoderData.h" #include "wpi/hardware/rotation/Encoder.hpp" -using namespace frc; -using namespace frc::sim; +using namespace wpi; +using namespace wpi::sim; EncoderSim::EncoderSim(const Encoder& encoder) : m_index{encoder.GetFPGAIndex()} {} diff --git a/wpilibc/src/main/native/cpp/simulation/FlywheelSim.cpp b/wpilibc/src/main/native/cpp/simulation/FlywheelSim.cpp index 939f7c00d9..9327501b53 100644 --- a/wpilibc/src/main/native/cpp/simulation/FlywheelSim.cpp +++ b/wpilibc/src/main/native/cpp/simulation/FlywheelSim.cpp @@ -7,11 +7,11 @@ #include "wpi/system/RobotController.hpp" #include "wpi/util/MathExtras.hpp" -using namespace frc; -using namespace frc::sim; +using namespace wpi; +using namespace wpi::sim; -FlywheelSim::FlywheelSim(const LinearSystem<1, 1, 1>& plant, - const DCMotor& gearbox, +FlywheelSim::FlywheelSim(const wpi::math::LinearSystem<1, 1, 1>& plant, + const wpi::math::DCMotor& gearbox, const std::array& measurementStdDevs) : LinearSystemSim<1, 1, 1>(plant, measurementStdDevs), m_gearbox(gearbox), @@ -36,38 +36,38 @@ FlywheelSim::FlywheelSim(const LinearSystem<1, 1, 1>& plant, m_j(m_gearing * gearbox.Kt.value() / (gearbox.R.value() * m_plant.B(0, 0))) {} -void FlywheelSim::SetVelocity(units::radians_per_second_t velocity) { - LinearSystemSim::SetState(Vectord<1>{velocity.value()}); +void FlywheelSim::SetVelocity(wpi::units::radians_per_second_t velocity) { + LinearSystemSim::SetState(wpi::math::Vectord<1>{velocity.value()}); } -units::radians_per_second_t FlywheelSim::GetAngularVelocity() const { - return units::radians_per_second_t{GetOutput(0)}; +wpi::units::radians_per_second_t FlywheelSim::GetAngularVelocity() const { + return wpi::units::radians_per_second_t{GetOutput(0)}; } -units::radians_per_second_squared_t FlywheelSim::GetAngularAcceleration() +wpi::units::radians_per_second_squared_t FlywheelSim::GetAngularAcceleration() const { - return units::radians_per_second_squared_t{ + return wpi::units::radians_per_second_squared_t{ (m_plant.A() * m_x + m_plant.B() * m_u)(0, 0)}; } -units::newton_meter_t FlywheelSim::GetTorque() const { - return units::newton_meter_t{GetAngularAcceleration().value() * m_j.value()}; +wpi::units::newton_meter_t FlywheelSim::GetTorque() const { + return wpi::units::newton_meter_t{GetAngularAcceleration().value() * m_j.value()}; } -units::ampere_t FlywheelSim::GetCurrentDraw() const { +wpi::units::ampere_t FlywheelSim::GetCurrentDraw() const { // I = V / R - omega / (Kv * R) // Reductions are greater than 1, so a reduction of 10:1 would mean the motor // is spinning 10x faster than the output. - return m_gearbox.Current(units::radians_per_second_t{m_x(0)} * m_gearing, - units::volt_t{m_u(0)}) * - wpi::sgn(m_u(0)); + return m_gearbox.Current(wpi::units::radians_per_second_t{m_x(0)} * m_gearing, + wpi::units::volt_t{m_u(0)}) * + wpi::util::sgn(m_u(0)); } -units::volt_t FlywheelSim::GetInputVoltage() const { - return units::volt_t{GetInput(0)}; +wpi::units::volt_t FlywheelSim::GetInputVoltage() const { + return wpi::units::volt_t{GetInput(0)}; } -void FlywheelSim::SetInputVoltage(units::volt_t voltage) { - SetInput(Vectord<1>{voltage.value()}); - ClampInput(frc::RobotController::GetBatteryVoltage().value()); +void FlywheelSim::SetInputVoltage(wpi::units::volt_t voltage) { + SetInput(wpi::math::Vectord<1>{voltage.value()}); + ClampInput(wpi::RobotController::GetBatteryVoltage().value()); } diff --git a/wpilibc/src/main/native/cpp/simulation/GamepadSim.cpp b/wpilibc/src/main/native/cpp/simulation/GamepadSim.cpp index fda9b4f3a3..c643142449 100644 --- a/wpilibc/src/main/native/cpp/simulation/GamepadSim.cpp +++ b/wpilibc/src/main/native/cpp/simulation/GamepadSim.cpp @@ -6,8 +6,8 @@ #include "wpi/driverstation/Gamepad.hpp" -using namespace frc; -using namespace frc::sim; +using namespace wpi; +using namespace wpi::sim; GamepadSim::GamepadSim(const Gamepad& joystick) : GenericHIDSim{joystick} { SetAxesMaximumIndex(6); diff --git a/wpilibc/src/main/native/cpp/simulation/GenericHIDSim.cpp b/wpilibc/src/main/native/cpp/simulation/GenericHIDSim.cpp index c18b73548a..695f78b5f1 100644 --- a/wpilibc/src/main/native/cpp/simulation/GenericHIDSim.cpp +++ b/wpilibc/src/main/native/cpp/simulation/GenericHIDSim.cpp @@ -8,8 +8,8 @@ #include "wpi/driverstation/GenericHID.hpp" #include "wpi/simulation/DriverStationSim.hpp" -using namespace frc; -using namespace frc::sim; +using namespace wpi; +using namespace wpi::sim; GenericHIDSim::GenericHIDSim(const GenericHID& joystick) : m_port{joystick.GetPort()} {} diff --git a/wpilibc/src/main/native/cpp/simulation/JoystickSim.cpp b/wpilibc/src/main/native/cpp/simulation/JoystickSim.cpp index f6fc95ea75..3688e18458 100644 --- a/wpilibc/src/main/native/cpp/simulation/JoystickSim.cpp +++ b/wpilibc/src/main/native/cpp/simulation/JoystickSim.cpp @@ -7,8 +7,8 @@ #include "wpi/driverstation/Joystick.hpp" #include "wpi/simulation/GenericHIDSim.hpp" -using namespace frc; -using namespace frc::sim; +using namespace wpi; +using namespace wpi::sim; JoystickSim::JoystickSim(const Joystick& joystick) : GenericHIDSim{joystick}, m_joystick{&joystick} { diff --git a/wpilibc/src/main/native/cpp/simulation/PWMMotorControllerSim.cpp b/wpilibc/src/main/native/cpp/simulation/PWMMotorControllerSim.cpp index 560a927a89..1c926158d1 100644 --- a/wpilibc/src/main/native/cpp/simulation/PWMMotorControllerSim.cpp +++ b/wpilibc/src/main/native/cpp/simulation/PWMMotorControllerSim.cpp @@ -8,15 +8,15 @@ #include "wpi/simulation/SimDeviceSim.hpp" #include "wpi/units/length.hpp" -using namespace frc; -using namespace frc::sim; +using namespace wpi; +using namespace wpi::sim; PWMMotorControllerSim::PWMMotorControllerSim( const PWMMotorController& motorctrl) : PWMMotorControllerSim(motorctrl.GetChannel()) {} PWMMotorControllerSim::PWMMotorControllerSim(int channel) { - frc::sim::SimDeviceSim deviceSim{"PWMMotorController", channel}; + wpi::sim::SimDeviceSim deviceSim{"PWMMotorController", channel}; m_simSpeed = deviceSim.GetDouble("Speed"); } diff --git a/wpilibc/src/main/native/cpp/simulation/PWMSim.cpp b/wpilibc/src/main/native/cpp/simulation/PWMSim.cpp index 5f9d5d1f0f..62ba7a381a 100644 --- a/wpilibc/src/main/native/cpp/simulation/PWMSim.cpp +++ b/wpilibc/src/main/native/cpp/simulation/PWMSim.cpp @@ -10,8 +10,8 @@ #include "wpi/hardware/discrete/PWM.hpp" #include "wpi/hardware/motor/PWMMotorController.hpp" -using namespace frc; -using namespace frc::sim; +using namespace wpi; +using namespace wpi::sim; PWMSim::PWMSim(const PWM& pwm) : m_index{pwm.GetChannel()} {} diff --git a/wpilibc/src/main/native/cpp/simulation/PneumaticsBaseSim.cpp b/wpilibc/src/main/native/cpp/simulation/PneumaticsBaseSim.cpp index 7e7b32b281..9f245ebcc8 100644 --- a/wpilibc/src/main/native/cpp/simulation/PneumaticsBaseSim.cpp +++ b/wpilibc/src/main/native/cpp/simulation/PneumaticsBaseSim.cpp @@ -11,8 +11,8 @@ #include "wpi/simulation/REVPHSim.hpp" #include "wpi/system/Errors.hpp" -using namespace frc; -using namespace frc::sim; +using namespace wpi; +using namespace wpi::sim; std::shared_ptr PneumaticsBaseSim::GetForType( int module, PneumaticsModuleType type) { diff --git a/wpilibc/src/main/native/cpp/simulation/PowerDistributionSim.cpp b/wpilibc/src/main/native/cpp/simulation/PowerDistributionSim.cpp index b4b465eda7..3d950c5a93 100644 --- a/wpilibc/src/main/native/cpp/simulation/PowerDistributionSim.cpp +++ b/wpilibc/src/main/native/cpp/simulation/PowerDistributionSim.cpp @@ -9,8 +9,8 @@ #include "wpi/hal/simulation/PowerDistributionData.h" #include "wpi/hardware/power/PowerDistribution.hpp" -using namespace frc; -using namespace frc::sim; +using namespace wpi; +using namespace wpi::sim; PowerDistributionSim::PowerDistributionSim(int module) : m_index{module} {} diff --git a/wpilibc/src/main/native/cpp/simulation/REVPHSim.cpp b/wpilibc/src/main/native/cpp/simulation/REVPHSim.cpp index e40b9cd26e..f8c52be903 100644 --- a/wpilibc/src/main/native/cpp/simulation/REVPHSim.cpp +++ b/wpilibc/src/main/native/cpp/simulation/REVPHSim.cpp @@ -9,8 +9,8 @@ #include "wpi/hal/simulation/REVPHData.h" #include "wpi/util/SensorUtil.hpp" -using namespace frc; -using namespace frc::sim; +using namespace wpi; +using namespace wpi::sim; REVPHSim::REVPHSim() : PneumaticsBaseSim{SensorUtil::GetDefaultREVPHModule()} {} diff --git a/wpilibc/src/main/native/cpp/simulation/RoboRioSim.cpp b/wpilibc/src/main/native/cpp/simulation/RoboRioSim.cpp index 87c98e0598..0cc5a49dba 100644 --- a/wpilibc/src/main/native/cpp/simulation/RoboRioSim.cpp +++ b/wpilibc/src/main/native/cpp/simulation/RoboRioSim.cpp @@ -9,8 +9,8 @@ #include "wpi/hal/simulation/RoboRioData.h" -using namespace frc; -using namespace frc::sim; +using namespace wpi; +using namespace wpi::sim; std::unique_ptr RoboRioSim::RegisterVInVoltageCallback( NotifyCallback callback, bool initialNotify) { @@ -21,11 +21,11 @@ std::unique_ptr RoboRioSim::RegisterVInVoltageCallback( return store; } -units::volt_t RoboRioSim::GetVInVoltage() { - return units::volt_t{HALSIM_GetRoboRioVInVoltage()}; +wpi::units::volt_t RoboRioSim::GetVInVoltage() { + return wpi::units::volt_t{HALSIM_GetRoboRioVInVoltage()}; } -void RoboRioSim::SetVInVoltage(units::volt_t vInVoltage) { +void RoboRioSim::SetVInVoltage(wpi::units::volt_t vInVoltage) { HALSIM_SetRoboRioVInVoltage(vInVoltage.value()); } @@ -38,11 +38,11 @@ std::unique_ptr RoboRioSim::RegisterUserVoltage3V3Callback( return store; } -units::volt_t RoboRioSim::GetUserVoltage3V3() { - return units::volt_t{HALSIM_GetRoboRioUserVoltage3V3()}; +wpi::units::volt_t RoboRioSim::GetUserVoltage3V3() { + return wpi::units::volt_t{HALSIM_GetRoboRioUserVoltage3V3()}; } -void RoboRioSim::SetUserVoltage3V3(units::volt_t userVoltage3V3) { +void RoboRioSim::SetUserVoltage3V3(wpi::units::volt_t userVoltage3V3) { HALSIM_SetRoboRioUserVoltage3V3(userVoltage3V3.value()); } @@ -55,11 +55,11 @@ std::unique_ptr RoboRioSim::RegisterUserCurrent3V3Callback( return store; } -units::ampere_t RoboRioSim::GetUserCurrent3V3() { - return units::ampere_t{HALSIM_GetRoboRioUserCurrent3V3()}; +wpi::units::ampere_t RoboRioSim::GetUserCurrent3V3() { + return wpi::units::ampere_t{HALSIM_GetRoboRioUserCurrent3V3()}; } -void RoboRioSim::SetUserCurrent3V3(units::ampere_t userCurrent3V3) { +void RoboRioSim::SetUserCurrent3V3(wpi::units::ampere_t userCurrent3V3) { HALSIM_SetRoboRioUserCurrent3V3(userCurrent3V3.value()); } @@ -106,11 +106,11 @@ std::unique_ptr RoboRioSim::RegisterBrownoutVoltageCallback( return store; } -units::volt_t RoboRioSim::GetBrownoutVoltage() { - return units::volt_t{HALSIM_GetRoboRioBrownoutVoltage()}; +wpi::units::volt_t RoboRioSim::GetBrownoutVoltage() { + return wpi::units::volt_t{HALSIM_GetRoboRioBrownoutVoltage()}; } -void RoboRioSim::SetBrownoutVoltage(units::volt_t vInVoltage) { +void RoboRioSim::SetBrownoutVoltage(wpi::units::volt_t vInVoltage) { HALSIM_SetRoboRioBrownoutVoltage(vInVoltage.value()); } @@ -123,11 +123,11 @@ std::unique_ptr RoboRioSim::RegisterCPUTempCallback( return store; } -units::celsius_t RoboRioSim::GetCPUTemp() { - return units::celsius_t{HALSIM_GetRoboRioCPUTemp()}; +wpi::units::celsius_t RoboRioSim::GetCPUTemp() { + return wpi::units::celsius_t{HALSIM_GetRoboRioCPUTemp()}; } -void RoboRioSim::SetCPUTemp(units::celsius_t cpuTemp) { +void RoboRioSim::SetCPUTemp(wpi::units::celsius_t cpuTemp) { HALSIM_SetRoboRioCPUTemp(cpuTemp.value()); } @@ -151,26 +151,26 @@ void RoboRioSim::SetTeamNumber(int32_t teamNumber) { std::string RoboRioSim::GetSerialNumber() { WPI_String serialNum; HALSIM_GetRoboRioSerialNumber(&serialNum); - std::string serial{wpi::to_string_view(&serialNum)}; + std::string serial{wpi::util::to_string_view(&serialNum)}; WPI_FreeString(&serialNum); return serial; } void RoboRioSim::SetSerialNumber(std::string_view serialNumber) { - auto str = wpi::make_string(serialNumber); + auto str = wpi::util::make_string(serialNumber); HALSIM_SetRoboRioSerialNumber(&str); } std::string RoboRioSim::GetComments() { WPI_String comments; HALSIM_GetRoboRioComments(&comments); - std::string serial{wpi::to_string_view(&comments)}; + std::string serial{wpi::util::to_string_view(&comments)}; WPI_FreeString(&comments); return serial; } void RoboRioSim::SetComments(std::string_view comments) { - auto str = wpi::make_string(comments); + auto str = wpi::util::make_string(comments); HALSIM_SetRoboRioComments(&str); } diff --git a/wpilibc/src/main/native/cpp/simulation/SendableChooserSim.cpp b/wpilibc/src/main/native/cpp/simulation/SendableChooserSim.cpp index 89b42c14a6..a4d527647b 100644 --- a/wpilibc/src/main/native/cpp/simulation/SendableChooserSim.cpp +++ b/wpilibc/src/main/native/cpp/simulation/SendableChooserSim.cpp @@ -4,12 +4,12 @@ #include "wpi/simulation/SendableChooserSim.hpp" -using namespace frc::sim; +using namespace wpi::sim; SendableChooserSim::SendableChooserSim(std::string_view path) - : SendableChooserSim(nt::NetworkTableInstance::GetDefault(), path) {} + : SendableChooserSim(wpi::nt::NetworkTableInstance::GetDefault(), path) {} -SendableChooserSim::SendableChooserSim(nt::NetworkTableInstance inst, +SendableChooserSim::SendableChooserSim(wpi::nt::NetworkTableInstance inst, std::string_view path) { if constexpr (RobotBase::IsSimulation()) { m_publisher = diff --git a/wpilibc/src/main/native/cpp/simulation/SharpIRSim.cpp b/wpilibc/src/main/native/cpp/simulation/SharpIRSim.cpp index 9d3c052ecb..963149dadf 100644 --- a/wpilibc/src/main/native/cpp/simulation/SharpIRSim.cpp +++ b/wpilibc/src/main/native/cpp/simulation/SharpIRSim.cpp @@ -8,16 +8,16 @@ #include "wpi/simulation/SimDeviceSim.hpp" #include "wpi/units/length.hpp" -using namespace frc; +using namespace wpi; SharpIRSim::SharpIRSim(const SharpIR& sharpIR) : SharpIRSim(sharpIR.GetChannel()) {} SharpIRSim::SharpIRSim(int channel) { - frc::sim::SimDeviceSim deviceSim{"SharpIR", channel}; + wpi::sim::SimDeviceSim deviceSim{"SharpIR", channel}; m_simRange = deviceSim.GetDouble("Range (m)"); } -void SharpIRSim::SetRange(units::meter_t range) { +void SharpIRSim::SetRange(wpi::units::meter_t range) { m_simRange.Set(range.value()); } diff --git a/wpilibc/src/main/native/cpp/simulation/SimDeviceSim.cpp b/wpilibc/src/main/native/cpp/simulation/SimDeviceSim.cpp index 216a0af7da..dda970bf4b 100644 --- a/wpilibc/src/main/native/cpp/simulation/SimDeviceSim.cpp +++ b/wpilibc/src/main/native/cpp/simulation/SimDeviceSim.cpp @@ -12,8 +12,8 @@ #include "wpi/hal/SimDevice.h" #include "wpi/hal/simulation/SimDeviceData.h" -using namespace frc; -using namespace frc::sim; +using namespace wpi; +using namespace wpi::sim; SimDeviceSim::SimDeviceSim(const char* name) : m_handle{HALSIM_GetSimDeviceHandle(name)} {} diff --git a/wpilibc/src/main/native/cpp/simulation/SimHooks.cpp b/wpilibc/src/main/native/cpp/simulation/SimHooks.cpp index c7d5a36d22..03cf15e2b8 100644 --- a/wpilibc/src/main/native/cpp/simulation/SimHooks.cpp +++ b/wpilibc/src/main/native/cpp/simulation/SimHooks.cpp @@ -6,7 +6,7 @@ #include "wpi/hal/simulation/MockHooks.h" -namespace frc::sim { +namespace wpi::sim { void SetRuntimeType(HAL_RuntimeType type) { HALSIM_SetRuntimeType(type); @@ -40,12 +40,12 @@ bool IsTimingPaused() { return HALSIM_IsTimingPaused(); } -void StepTiming(units::second_t delta) { +void StepTiming(wpi::units::second_t delta) { HALSIM_StepTiming(static_cast(delta.value() * 1e6)); } -void StepTimingAsync(units::second_t delta) { +void StepTimingAsync(wpi::units::second_t delta) { HALSIM_StepTimingAsync(static_cast(delta.value() * 1e6)); } -} // namespace frc::sim +} // namespace wpi::sim diff --git a/wpilibc/src/main/native/cpp/simulation/SingleJointedArmSim.cpp b/wpilibc/src/main/native/cpp/simulation/SingleJointedArmSim.cpp index 7aaf77a6c5..abcf18b32f 100644 --- a/wpilibc/src/main/native/cpp/simulation/SingleJointedArmSim.cpp +++ b/wpilibc/src/main/native/cpp/simulation/SingleJointedArmSim.cpp @@ -12,14 +12,14 @@ #include "wpi/units/voltage.hpp" #include "wpi/util/MathExtras.hpp" -using namespace frc; -using namespace frc::sim; +using namespace wpi; +using namespace wpi::sim; SingleJointedArmSim::SingleJointedArmSim( - const LinearSystem<2, 1, 2>& system, const DCMotor& gearbox, double gearing, - units::meter_t armLength, units::radian_t minAngle, - units::radian_t maxAngle, bool simulateGravity, - units::radian_t startingAngle, + const wpi::math::LinearSystem<2, 1, 2>& system, const wpi::math::DCMotor& gearbox, double gearing, + wpi::units::meter_t armLength, wpi::units::radian_t minAngle, + wpi::units::radian_t maxAngle, bool simulateGravity, + wpi::units::radian_t startingAngle, const std::array& measurementStdDevs) : LinearSystemSim<2, 1, 2>(system, measurementStdDevs), m_armLen(armLength), @@ -32,61 +32,61 @@ SingleJointedArmSim::SingleJointedArmSim( } SingleJointedArmSim::SingleJointedArmSim( - const DCMotor& gearbox, double gearing, units::kilogram_square_meter_t moi, - units::meter_t armLength, units::radian_t minAngle, - units::radian_t maxAngle, bool simulateGravity, - units::radian_t startingAngle, + const wpi::math::DCMotor& gearbox, double gearing, wpi::units::kilogram_square_meter_t moi, + wpi::units::meter_t armLength, wpi::units::radian_t minAngle, + wpi::units::radian_t maxAngle, bool simulateGravity, + wpi::units::radian_t startingAngle, const std::array& measurementStdDevs) : SingleJointedArmSim( - LinearSystemId::SingleJointedArmSystem(gearbox, moi, gearing), + wpi::math::LinearSystemId::SingleJointedArmSystem(gearbox, moi, gearing), gearbox, gearing, armLength, minAngle, maxAngle, simulateGravity, startingAngle, measurementStdDevs) {} -void SingleJointedArmSim::SetState(units::radian_t angle, - units::radians_per_second_t velocity) { - SetState(Vectord<2>{std::clamp(angle, m_minAngle, m_maxAngle), velocity}); +void SingleJointedArmSim::SetState(wpi::units::radian_t angle, + wpi::units::radians_per_second_t velocity) { + SetState(wpi::math::Vectord<2>{std::clamp(angle, m_minAngle, m_maxAngle), velocity}); } -bool SingleJointedArmSim::WouldHitLowerLimit(units::radian_t armAngle) const { +bool SingleJointedArmSim::WouldHitLowerLimit(wpi::units::radian_t armAngle) const { return armAngle <= m_minAngle; } -bool SingleJointedArmSim::WouldHitUpperLimit(units::radian_t armAngle) const { +bool SingleJointedArmSim::WouldHitUpperLimit(wpi::units::radian_t armAngle) const { return armAngle >= m_maxAngle; } bool SingleJointedArmSim::HasHitLowerLimit() const { - return WouldHitLowerLimit(units::radian_t{m_y(0)}); + return WouldHitLowerLimit(wpi::units::radian_t{m_y(0)}); } bool SingleJointedArmSim::HasHitUpperLimit() const { - return WouldHitUpperLimit(units::radian_t{m_y(0)}); + return WouldHitUpperLimit(wpi::units::radian_t{m_y(0)}); } -units::radian_t SingleJointedArmSim::GetAngle() const { - return units::radian_t{m_y(0)}; +wpi::units::radian_t SingleJointedArmSim::GetAngle() const { + return wpi::units::radian_t{m_y(0)}; } -units::radians_per_second_t SingleJointedArmSim::GetVelocity() const { - return units::radians_per_second_t{m_x(1)}; +wpi::units::radians_per_second_t SingleJointedArmSim::GetVelocity() const { + return wpi::units::radians_per_second_t{m_x(1)}; } -units::ampere_t SingleJointedArmSim::GetCurrentDraw() const { +wpi::units::ampere_t SingleJointedArmSim::GetCurrentDraw() const { // Reductions are greater than 1, so a reduction of 10:1 would mean the motor // is spinning 10x faster than the output - units::radians_per_second_t motorVelocity{m_x(1) * m_gearing}; - return m_gearbox.Current(motorVelocity, units::volt_t{m_u(0)}) * - wpi::sgn(m_u(0)); + wpi::units::radians_per_second_t motorVelocity{m_x(1) * m_gearing}; + return m_gearbox.Current(motorVelocity, wpi::units::volt_t{m_u(0)}) * + wpi::util::sgn(m_u(0)); } -void SingleJointedArmSim::SetInputVoltage(units::volt_t voltage) { - SetInput(Vectord<1>{voltage.value()}); - ClampInput(frc::RobotController::GetBatteryVoltage().value()); +void SingleJointedArmSim::SetInputVoltage(wpi::units::volt_t voltage) { + SetInput(wpi::math::Vectord<1>{voltage.value()}); + ClampInput(wpi::RobotController::GetBatteryVoltage().value()); } -Vectord<2> SingleJointedArmSim::UpdateX(const Vectord<2>& currentXhat, - const Vectord<1>& u, - units::second_t dt) { +wpi::math::Vectord<2> SingleJointedArmSim::UpdateX(const wpi::math::Vectord<2>& currentXhat, + const wpi::math::Vectord<1>& u, + wpi::units::second_t dt) { // The torque on the arm is given by τ = F⋅r, where F is the force applied by // gravity and r the distance from pivot to center of mass. Recall from // dynamics that the sum of torques for a rigid body is τ = J⋅α, were τ is @@ -111,12 +111,12 @@ Vectord<2> SingleJointedArmSim::UpdateX(const Vectord<2>& currentXhat, // f(x, u) = Ax + Bu + [0 α]ᵀ // f(x, u) = Ax + Bu + [0 3/2⋅g⋅cos(θ)/L]ᵀ - Vectord<2> updatedXhat = RKDP( - [&](const auto& x, const auto& u) -> Vectord<2> { - Vectord<2> xdot = m_plant.A() * x + m_plant.B() * u; + wpi::math::Vectord<2> updatedXhat = wpi::math::RKDP( + [&](const auto& x, const auto& u) -> wpi::math::Vectord<2> { + wpi::math::Vectord<2> xdot = m_plant.A() * x + m_plant.B() * u; if (m_simulateGravity) { - xdot += Vectord<2>{ + xdot += wpi::math::Vectord<2>{ 0.0, (3.0 / 2.0 * -9.8 / m_armLen * std::cos(x(0))).value()}; } return xdot; @@ -124,10 +124,10 @@ Vectord<2> SingleJointedArmSim::UpdateX(const Vectord<2>& currentXhat, currentXhat, u, dt); // Check for collisions. - if (WouldHitLowerLimit(units::radian_t{updatedXhat(0)})) { - return Vectord<2>{m_minAngle.value(), 0.0}; - } else if (WouldHitUpperLimit(units::radian_t{updatedXhat(0)})) { - return Vectord<2>{m_maxAngle.value(), 0.0}; + if (WouldHitLowerLimit(wpi::units::radian_t{updatedXhat(0)})) { + return wpi::math::Vectord<2>{m_minAngle.value(), 0.0}; + } else if (WouldHitUpperLimit(wpi::units::radian_t{updatedXhat(0)})) { + return wpi::math::Vectord<2>{m_maxAngle.value(), 0.0}; } return updatedXhat; } diff --git a/wpilibc/src/main/native/cpp/simulation/SolenoidSim.cpp b/wpilibc/src/main/native/cpp/simulation/SolenoidSim.cpp index e0fa8c12e4..a1517479e7 100644 --- a/wpilibc/src/main/native/cpp/simulation/SolenoidSim.cpp +++ b/wpilibc/src/main/native/cpp/simulation/SolenoidSim.cpp @@ -9,8 +9,8 @@ #include "wpi/hardware/pneumatic/PneumaticsBase.hpp" -using namespace frc; -using namespace frc::sim; +using namespace wpi; +using namespace wpi::sim; SolenoidSim::SolenoidSim(std::shared_ptr moduleSim, int channel) diff --git a/wpilibc/src/main/native/cpp/smartdashboard/Field2d.cpp b/wpilibc/src/main/native/cpp/smartdashboard/Field2d.cpp index e9426ad730..31ac027715 100644 --- a/wpilibc/src/main/native/cpp/smartdashboard/Field2d.cpp +++ b/wpilibc/src/main/native/cpp/smartdashboard/Field2d.cpp @@ -11,13 +11,13 @@ #include "wpi/nt/NTSendableBuilder.hpp" #include "wpi/util/sendable/SendableRegistry.hpp" -using namespace frc; +using namespace wpi; Field2d::Field2d() { m_objects.emplace_back( std::make_unique("Robot", FieldObject2d::private_init{})); - m_objects[0]->SetPose(Pose2d{}); - wpi::SendableRegistry::Add(this, "Field"); + m_objects[0]->SetPose(wpi::math::Pose2d{}); + wpi::util::SendableRegistry::Add(this, "Field"); } Field2d::Field2d(Field2d&& rhs) : SendableHelper(std::move(rhs)) { @@ -34,18 +34,18 @@ Field2d& Field2d::operator=(Field2d&& rhs) { return *this; } -void Field2d::SetRobotPose(const Pose2d& pose) { +void Field2d::SetRobotPose(const wpi::math::Pose2d& pose) { std::scoped_lock lock(m_mutex); m_objects[0]->SetPose(pose); } -void Field2d::SetRobotPose(units::meter_t x, units::meter_t y, - Rotation2d rotation) { +void Field2d::SetRobotPose(wpi::units::meter_t x, wpi::units::meter_t y, + wpi::math::Rotation2d rotation) { std::scoped_lock lock(m_mutex); m_objects[0]->SetPose(x, y, rotation); } -Pose2d Field2d::GetRobotPose() const { +wpi::math::Pose2d Field2d::GetRobotPose() const { std::scoped_lock lock(m_mutex); return m_objects[0]->GetPose(); } @@ -71,7 +71,7 @@ FieldObject2d* Field2d::GetRobotObject() { return m_objects[0].get(); } -void Field2d::InitSendable(nt::NTSendableBuilder& builder) { +void Field2d::InitSendable(wpi::nt::NTSendableBuilder& builder) { builder.SetSmartDashboardType("Field2d"); std::scoped_lock lock(m_mutex); diff --git a/wpilibc/src/main/native/cpp/smartdashboard/FieldObject2d.cpp b/wpilibc/src/main/native/cpp/smartdashboard/FieldObject2d.cpp index 9ead0c0440..00fd89319e 100644 --- a/wpilibc/src/main/native/cpp/smartdashboard/FieldObject2d.cpp +++ b/wpilibc/src/main/native/cpp/smartdashboard/FieldObject2d.cpp @@ -9,7 +9,7 @@ #include "wpi/math/trajectory/Trajectory.hpp" -using namespace frc; +using namespace wpi; FieldObject2d::FieldObject2d(FieldObject2d&& rhs) { std::swap(m_name, rhs.m_name); @@ -25,16 +25,16 @@ FieldObject2d& FieldObject2d::operator=(FieldObject2d&& rhs) { return *this; } -void FieldObject2d::SetPose(const Pose2d& pose) { +void FieldObject2d::SetPose(const wpi::math::Pose2d& pose) { SetPoses({pose}); } -void FieldObject2d::SetPose(units::meter_t x, units::meter_t y, - Rotation2d rotation) { +void FieldObject2d::SetPose(wpi::units::meter_t x, wpi::units::meter_t y, + wpi::math::Rotation2d rotation) { SetPoses({{x, y, rotation}}); } -Pose2d FieldObject2d::GetPose() const { +wpi::math::Pose2d FieldObject2d::GetPose() const { std::scoped_lock lock(m_mutex); UpdateFromEntry(); if (m_poses.empty()) { @@ -43,17 +43,17 @@ Pose2d FieldObject2d::GetPose() const { return m_poses[0]; } -void FieldObject2d::SetPoses(std::span poses) { +void FieldObject2d::SetPoses(std::span poses) { std::scoped_lock lock(m_mutex); m_poses.assign(poses.begin(), poses.end()); UpdateEntry(); } -void FieldObject2d::SetPoses(std::initializer_list poses) { +void FieldObject2d::SetPoses(std::initializer_list poses) { SetPoses({poses.begin(), poses.end()}); } -void FieldObject2d::SetTrajectory(const Trajectory& trajectory) { +void FieldObject2d::SetTrajectory(const wpi::math::Trajectory& trajectory) { std::scoped_lock lock(m_mutex); m_poses.clear(); m_poses.reserve(trajectory.States().size()); @@ -63,14 +63,14 @@ void FieldObject2d::SetTrajectory(const Trajectory& trajectory) { UpdateEntry(); } -std::vector FieldObject2d::GetPoses() const { +std::vector FieldObject2d::GetPoses() const { std::scoped_lock lock(m_mutex); UpdateFromEntry(); - return std::vector(m_poses.begin(), m_poses.end()); + return std::vector(m_poses.begin(), m_poses.end()); } -std::span FieldObject2d::GetPoses( - wpi::SmallVectorImpl& out) const { +std::span FieldObject2d::GetPoses( + wpi::util::SmallVectorImpl& out) const { std::scoped_lock lock(m_mutex); UpdateFromEntry(); out.assign(m_poses.begin(), m_poses.end()); @@ -81,7 +81,7 @@ void FieldObject2d::UpdateEntry(bool setDefault) { if (!m_entry) { return; } - wpi::SmallVector arr; + wpi::util::SmallVector arr; for (auto&& pose : m_poses) { auto& translation = pose.Translation(); arr.push_back(translation.X().value()); @@ -107,7 +107,7 @@ void FieldObject2d::UpdateFromEntry() const { m_poses.resize(size / 3); for (size_t i = 0; i < size / 3; ++i) { m_poses[i] = - Pose2d{units::meter_t{arr[i * 3 + 0]}, units::meter_t{arr[i * 3 + 1]}, - units::degree_t{arr[i * 3 + 2]}}; + wpi::math::Pose2d{wpi::units::meter_t{arr[i * 3 + 0]}, wpi::units::meter_t{arr[i * 3 + 1]}, + wpi::units::degree_t{arr[i * 3 + 2]}}; } } diff --git a/wpilibc/src/main/native/cpp/smartdashboard/ListenerExecutor.cpp b/wpilibc/src/main/native/cpp/smartdashboard/ListenerExecutor.cpp index 3c603d11d0..d23d2b832a 100644 --- a/wpilibc/src/main/native/cpp/smartdashboard/ListenerExecutor.cpp +++ b/wpilibc/src/main/native/cpp/smartdashboard/ListenerExecutor.cpp @@ -6,7 +6,7 @@ #include -using namespace frc::detail; +using namespace wpi::detail; void ListenerExecutor::Execute(std::function task) { std::scoped_lock lock(m_lock); diff --git a/wpilibc/src/main/native/cpp/smartdashboard/Mechanism2d.cpp b/wpilibc/src/main/native/cpp/smartdashboard/Mechanism2d.cpp index d9fa636b4d..6de4b3cca0 100644 --- a/wpilibc/src/main/native/cpp/smartdashboard/Mechanism2d.cpp +++ b/wpilibc/src/main/native/cpp/smartdashboard/Mechanism2d.cpp @@ -9,7 +9,7 @@ #include "wpi/nt/NTSendableBuilder.hpp" -using namespace frc; +using namespace wpi; static constexpr std::string_view kBackgroundColor = "backgroundColor"; static constexpr std::string_view kDims = "dims"; @@ -37,7 +37,7 @@ void Mechanism2d::SetBackgroundColor(const Color8Bit& color) { } } -void Mechanism2d::InitSendable(nt::NTSendableBuilder& builder) { +void Mechanism2d::InitSendable(wpi::nt::NTSendableBuilder& builder) { builder.SetSmartDashboardType("Mechanism2d"); std::scoped_lock lock(m_mutex); diff --git a/wpilibc/src/main/native/cpp/smartdashboard/MechanismLigament2d.cpp b/wpilibc/src/main/native/cpp/smartdashboard/MechanismLigament2d.cpp index 2757058048..f44b664b89 100644 --- a/wpilibc/src/main/native/cpp/smartdashboard/MechanismLigament2d.cpp +++ b/wpilibc/src/main/native/cpp/smartdashboard/MechanismLigament2d.cpp @@ -10,14 +10,14 @@ #include "wpi/util/StringExtras.hpp" #include "wpi/util/json.hpp" -using namespace frc; +using namespace wpi; static constexpr std::string_view kSmartDashboardType = "line"; MechanismLigament2d::MechanismLigament2d(std::string_view name, double length, - units::degree_t angle, + wpi::units::degree_t angle, double lineWeight, - const frc::Color8Bit& color) + const wpi::Color8Bit& color) : MechanismObject2d{name}, m_length{length}, m_angle{angle.value()}, @@ -26,9 +26,9 @@ MechanismLigament2d::MechanismLigament2d(std::string_view name, double length, } void MechanismLigament2d::UpdateEntries( - std::shared_ptr table) { + std::shared_ptr table) { m_typePub = table->GetStringTopic(".type").PublishEx( - nt::StringTopic::kTypeString, {{"SmartDashboard", kSmartDashboardType}}); + wpi::nt::StringTopic::kTypeString, {{"SmartDashboard", kSmartDashboardType}}); m_typePub.Set(kSmartDashboardType); m_colorEntry = table->GetStringTopic("color").GetEntry(""); @@ -44,7 +44,7 @@ void MechanismLigament2d::UpdateEntries( void MechanismLigament2d::SetColor(const Color8Bit& color) { std::scoped_lock lock(m_mutex); - wpi::format_to_n_c_str(m_color, sizeof(m_color), "#{:02X}{:02X}{:02X}", + wpi::util::format_to_n_c_str(m_color, sizeof(m_color), "#{:02X}{:02X}{:02X}", color.red, color.green, color.blue); if (m_colorEntry) { @@ -52,7 +52,7 @@ void MechanismLigament2d::SetColor(const Color8Bit& color) { } } -void MechanismLigament2d::SetAngle(units::degree_t angle) { +void MechanismLigament2d::SetAngle(wpi::units::degree_t angle) { std::scoped_lock lock(m_mutex); m_angle = angle.value(); if (m_angleEntry) { diff --git a/wpilibc/src/main/native/cpp/smartdashboard/MechanismObject2d.cpp b/wpilibc/src/main/native/cpp/smartdashboard/MechanismObject2d.cpp index 139bd65fab..3dc485441c 100644 --- a/wpilibc/src/main/native/cpp/smartdashboard/MechanismObject2d.cpp +++ b/wpilibc/src/main/native/cpp/smartdashboard/MechanismObject2d.cpp @@ -6,7 +6,7 @@ #include -using namespace frc; +using namespace wpi; MechanismObject2d::MechanismObject2d(std::string_view name) : m_name{name} {} @@ -14,7 +14,7 @@ const std::string& MechanismObject2d::GetName() const { return m_name; } -void MechanismObject2d::Update(std::shared_ptr table) { +void MechanismObject2d::Update(std::shared_ptr table) { std::scoped_lock lock(m_mutex); m_table = table; UpdateEntries(m_table); diff --git a/wpilibc/src/main/native/cpp/smartdashboard/MechanismRoot2d.cpp b/wpilibc/src/main/native/cpp/smartdashboard/MechanismRoot2d.cpp index f2553f1a65..a86ef26a86 100644 --- a/wpilibc/src/main/native/cpp/smartdashboard/MechanismRoot2d.cpp +++ b/wpilibc/src/main/native/cpp/smartdashboard/MechanismRoot2d.cpp @@ -6,7 +6,7 @@ #include "wpi/util/Color8Bit.hpp" -using namespace frc; +using namespace wpi; MechanismRoot2d::MechanismRoot2d(std::string_view name, double x, double y, const private_init&) @@ -19,7 +19,7 @@ void MechanismRoot2d::SetPosition(double x, double y) { Flush(); } -void MechanismRoot2d::UpdateEntries(std::shared_ptr table) { +void MechanismRoot2d::UpdateEntries(std::shared_ptr table) { m_xPub = table->GetDoubleTopic("x").Publish(); m_yPub = table->GetDoubleTopic("y").Publish(); Flush(); diff --git a/wpilibc/src/main/native/cpp/smartdashboard/SendableBuilderImpl.cpp b/wpilibc/src/main/native/cpp/smartdashboard/SendableBuilderImpl.cpp index 7d7d652d43..48d26592b5 100644 --- a/wpilibc/src/main/native/cpp/smartdashboard/SendableBuilderImpl.cpp +++ b/wpilibc/src/main/native/cpp/smartdashboard/SendableBuilderImpl.cpp @@ -22,7 +22,7 @@ #include "wpi/util/SmallVector.hpp" #include "wpi/util/json.hpp" -using namespace frc; +using namespace wpi; template void SendableBuilderImpl::PropertyImpl::Update(bool controllable, @@ -35,13 +35,13 @@ void SendableBuilderImpl::PropertyImpl::Update(bool controllable, } } -void SendableBuilderImpl::SetTable(std::shared_ptr table) { +void SendableBuilderImpl::SetTable(std::shared_ptr table) { m_table = table; m_controllablePublisher = table->GetBooleanTopic(".controllable").Publish(); m_controllablePublisher.SetDefault(false); } -std::shared_ptr SendableBuilderImpl::GetTable() { +std::shared_ptr SendableBuilderImpl::GetTable() { return m_table; } @@ -54,7 +54,7 @@ bool SendableBuilderImpl::IsActuator() const { } void SendableBuilderImpl::Update() { - uint64_t time = nt::Now(); + uint64_t time = wpi::nt::Now(); for (auto& property : m_properties) { property->Update(m_controllable, time); } @@ -84,7 +84,7 @@ void SendableBuilderImpl::ClearProperties() { void SendableBuilderImpl::SetSmartDashboardType(std::string_view type) { if (!m_typePublisher) { m_typePublisher = m_table->GetStringTopic(".type").PublishEx( - nt::StringTopic::kTypeString, {{"SmartDashboard", type}}); + wpi::nt::StringTopic::kTypeString, {{"SmartDashboard", type}}); } m_typePublisher.Set(type); } @@ -97,11 +97,11 @@ void SendableBuilderImpl::SetActuator(bool value) { m_actuator = value; } -void SendableBuilderImpl::SetUpdateTable(wpi::unique_function func) { +void SendableBuilderImpl::SetUpdateTable(wpi::util::unique_function func) { m_updateTables.emplace_back(std::move(func)); } -nt::Topic SendableBuilderImpl::GetTopic(std::string_view key) { +wpi::nt::Topic SendableBuilderImpl::GetTopic(std::string_view key) { return m_table->GetTopic(key); } @@ -259,7 +259,7 @@ void SendableBuilderImpl::AddRawProperty( std::function()> getter, std::function)> setter) { auto topic = m_table->GetRawTopic(key); - auto prop = std::make_unique>(); + auto prop = std::make_unique>(); if (getter) { prop->pub = topic.Publish(typeString); prop->updateNetwork = [=](auto& pub, int64_t time) { @@ -282,7 +282,7 @@ void SendableBuilderImpl::PublishConstRaw(std::string_view key, std::string_view typeString, std::span value) { auto topic = m_table->GetRawTopic(key); - auto prop = std::make_unique>(); + auto prop = std::make_unique>(); prop->pub = topic.Publish(typeString); prop->pub.Set(value); m_properties.emplace_back(std::move(prop)); @@ -296,7 +296,7 @@ void SendableBuilderImpl::AddSmallPropertyImpl(Topic topic, Getter getter, if (getter) { prop->pub = topic.Publish(); prop->updateNetwork = [=](auto& pub, int64_t time) { - wpi::SmallVector buf; + wpi::util::SmallVector buf; pub.Set(getter(buf), time); }; } @@ -314,7 +314,7 @@ void SendableBuilderImpl::AddSmallPropertyImpl(Topic topic, Getter getter, void SendableBuilderImpl::AddSmallStringProperty( std::string_view key, - std::function& buf)> getter, + std::function& buf)> getter, std::function setter) { AddSmallPropertyImpl(m_table->GetStringTopic(key), std::move(getter), std::move(setter)); @@ -322,7 +322,7 @@ void SendableBuilderImpl::AddSmallStringProperty( void SendableBuilderImpl::AddSmallBooleanArrayProperty( std::string_view key, - std::function(wpi::SmallVectorImpl& buf)> getter, + std::function(wpi::util::SmallVectorImpl& buf)> getter, std::function)> setter) { AddSmallPropertyImpl(m_table->GetBooleanArrayTopic(key), std::move(getter), std::move(setter)); @@ -330,7 +330,7 @@ void SendableBuilderImpl::AddSmallBooleanArrayProperty( void SendableBuilderImpl::AddSmallIntegerArrayProperty( std::string_view key, - std::function(wpi::SmallVectorImpl& buf)> + std::function(wpi::util::SmallVectorImpl& buf)> getter, std::function)> setter) { AddSmallPropertyImpl(m_table->GetIntegerArrayTopic(key), @@ -339,7 +339,7 @@ void SendableBuilderImpl::AddSmallIntegerArrayProperty( void SendableBuilderImpl::AddSmallFloatArrayProperty( std::string_view key, - std::function(wpi::SmallVectorImpl& buf)> + std::function(wpi::util::SmallVectorImpl& buf)> getter, std::function)> setter) { AddSmallPropertyImpl(m_table->GetFloatArrayTopic(key), @@ -348,7 +348,7 @@ void SendableBuilderImpl::AddSmallFloatArrayProperty( void SendableBuilderImpl::AddSmallDoubleArrayProperty( std::string_view key, - std::function(wpi::SmallVectorImpl& buf)> + std::function(wpi::util::SmallVectorImpl& buf)> getter, std::function)> setter) { AddSmallPropertyImpl(m_table->GetDoubleArrayTopic(key), @@ -358,7 +358,7 @@ void SendableBuilderImpl::AddSmallDoubleArrayProperty( void SendableBuilderImpl::AddSmallStringArrayProperty( std::string_view key, std::function< - std::span(wpi::SmallVectorImpl& buf)> + std::span(wpi::util::SmallVectorImpl& buf)> getter, std::function)> setter) { AddSmallPropertyImpl(m_table->GetStringArrayTopic(key), @@ -367,15 +367,15 @@ void SendableBuilderImpl::AddSmallStringArrayProperty( void SendableBuilderImpl::AddSmallRawProperty( std::string_view key, std::string_view typeString, - std::function(wpi::SmallVectorImpl& buf)> + std::function(wpi::util::SmallVectorImpl& buf)> getter, std::function)> setter) { auto topic = m_table->GetRawTopic(key); - auto prop = std::make_unique>(); + auto prop = std::make_unique>(); if (getter) { prop->pub = topic.Publish(typeString); prop->updateNetwork = [=](auto& pub, int64_t time) { - wpi::SmallVector buf; + wpi::util::SmallVector buf; pub.Set(getter(buf), time); }; } diff --git a/wpilibc/src/main/native/cpp/smartdashboard/SendableChooserBase.cpp b/wpilibc/src/main/native/cpp/smartdashboard/SendableChooserBase.cpp index f7881ad9f1..f159956255 100644 --- a/wpilibc/src/main/native/cpp/smartdashboard/SendableChooserBase.cpp +++ b/wpilibc/src/main/native/cpp/smartdashboard/SendableChooserBase.cpp @@ -8,12 +8,12 @@ #include "wpi/util/sendable/SendableRegistry.hpp" -using namespace frc; +using namespace wpi; std::atomic_int SendableChooserBase::s_instances{0}; SendableChooserBase::SendableChooserBase() : m_instance{s_instances++} { - wpi::SendableRegistry::Add(this, "SendableChooser", m_instance); + wpi::util::SendableRegistry::Add(this, "SendableChooser", m_instance); } SendableChooserBase::SendableChooserBase(SendableChooserBase&& oth) diff --git a/wpilibc/src/main/native/cpp/smartdashboard/SmartDashboard.cpp b/wpilibc/src/main/native/cpp/smartdashboard/SmartDashboard.cpp index 7070fc82e6..47d0d7c8ab 100644 --- a/wpilibc/src/main/native/cpp/smartdashboard/SmartDashboard.cpp +++ b/wpilibc/src/main/native/cpp/smartdashboard/SmartDashboard.cpp @@ -19,15 +19,15 @@ #include "wpi/util/mutex.hpp" #include "wpi/util/sendable/SendableRegistry.hpp" -using namespace frc; +using namespace wpi; namespace { struct Instance { detail::ListenerExecutor listenerExecutor; - std::shared_ptr table = - nt::NetworkTableInstance::GetDefault().GetTable("SmartDashboard"); - wpi::StringMap tablesToData; - wpi::mutex tablesToDataMutex; + std::shared_ptr table = + wpi::nt::NetworkTableInstance::GetDefault().GetTable("SmartDashboard"); + wpi::util::StringMap tablesToData; + wpi::util::mutex tablesToDataMutex; }; } // namespace @@ -41,11 +41,11 @@ static Instance& GetInstance() { } #ifndef __FRC_SYSTEMCORE__ -namespace frc::impl { +namespace wpi::impl { void ResetSmartDashboardInstance() { std::make_unique().swap(GetInstanceHolder()); } -} // namespace frc::impl +} // namespace wpi::impl #endif static bool gReported = false; @@ -74,7 +74,7 @@ bool SmartDashboard::IsPersistent(std::string_view key) { return GetEntry(key).IsPersistent(); } -nt::NetworkTableEntry SmartDashboard::GetEntry(std::string_view key) { +wpi::nt::NetworkTableEntry SmartDashboard::GetEntry(std::string_view key) { if (!gReported) { HAL_ReportUsage("SmartDashboard", ""); gReported = true; @@ -82,7 +82,7 @@ nt::NetworkTableEntry SmartDashboard::GetEntry(std::string_view key) { return GetInstance().table->GetEntry(key); } -void SmartDashboard::PutData(std::string_view key, wpi::Sendable* data) { +void SmartDashboard::PutData(std::string_view key, wpi::util::Sendable* data) { if (!data) { throw FRC_MakeError(err::NullParameter, "value"); } @@ -93,37 +93,37 @@ void SmartDashboard::PutData(std::string_view key, wpi::Sendable* data) { auto& inst = GetInstance(); std::scoped_lock lock(inst.tablesToDataMutex); auto& uid = inst.tablesToData[key]; - wpi::Sendable* sddata = wpi::SendableRegistry::GetSendable(uid); + wpi::util::Sendable* sddata = wpi::util::SendableRegistry::GetSendable(uid); if (sddata != data) { - uid = wpi::SendableRegistry::GetUniqueId(data); + uid = wpi::util::SendableRegistry::GetUniqueId(data); auto dataTable = inst.table->GetSubTable(key); auto builder = std::make_unique(); auto builderPtr = builder.get(); builderPtr->SetTable(dataTable); - wpi::SendableRegistry::Publish(uid, std::move(builder)); + wpi::util::SendableRegistry::Publish(uid, std::move(builder)); builderPtr->StartListeners(); dataTable->GetEntry(".name").SetString(key); } } -void SmartDashboard::PutData(wpi::Sendable* value) { +void SmartDashboard::PutData(wpi::util::Sendable* value) { if (!value) { throw FRC_MakeError(err::NullParameter, "value"); } - auto name = wpi::SendableRegistry::GetName(value); + auto name = wpi::util::SendableRegistry::GetName(value); if (!name.empty()) { PutData(name, value); } } -wpi::Sendable* SmartDashboard::GetData(std::string_view key) { +wpi::util::Sendable* SmartDashboard::GetData(std::string_view key) { auto& inst = GetInstance(); std::scoped_lock lock(inst.tablesToDataMutex); auto it = inst.tablesToData.find(key); if (it == inst.tablesToData.end()) { throw FRC_MakeError(err::SmartDashboardMissingKey, "{}", key); } - return wpi::SendableRegistry::GetSendable(it->second); + return wpi::util::SendableRegistry::GetSendable(it->second); } bool SmartDashboard::PutBoolean(std::string_view keyName, bool value) { @@ -229,16 +229,16 @@ std::vector SmartDashboard::GetRaw( } bool SmartDashboard::PutValue(std::string_view keyName, - const nt::Value& value) { + const wpi::nt::Value& value) { return GetInstance().table->GetEntry(keyName).SetValue(value); } bool SmartDashboard::SetDefaultValue(std::string_view key, - const nt::Value& defaultValue) { + const wpi::nt::Value& defaultValue) { return GetEntry(key).SetDefaultValue(defaultValue); } -nt::Value SmartDashboard::GetValue(std::string_view keyName) { +wpi::nt::Value SmartDashboard::GetValue(std::string_view keyName) { return GetInstance().table->GetEntry(keyName).GetValue(); } @@ -251,6 +251,6 @@ void SmartDashboard::UpdateValues() { inst.listenerExecutor.RunListenerTasks(); std::scoped_lock lock(inst.tablesToDataMutex); for (auto& i : inst.tablesToData) { - wpi::SendableRegistry::Update(i.second); + wpi::util::SendableRegistry::Update(i.second); } } diff --git a/wpilibc/src/main/native/cpp/sysid/SysIdRoutineLog.cpp b/wpilibc/src/main/native/cpp/sysid/SysIdRoutineLog.cpp index 5ab7facf20..ce94a94c6f 100644 --- a/wpilibc/src/main/native/cpp/sysid/SysIdRoutineLog.cpp +++ b/wpilibc/src/main/native/cpp/sysid/SysIdRoutineLog.cpp @@ -10,7 +10,7 @@ #include "wpi/system/DataLogManager.hpp" -using namespace frc::sysid; +using namespace wpi::sysid; SysIdRoutineLog::SysIdRoutineLog(std::string_view logName) : m_logName(logName) {} @@ -27,7 +27,7 @@ SysIdRoutineLog::MotorLog& SysIdRoutineLog::MotorLog::value( auto& motorEntries = (*m_logEntries)[m_motorName]; if (!motorEntries.contains(name)) { - wpi::log::DataLog& log = frc::DataLogManager::GetLog(); + wpi::log::DataLog& log = wpi::DataLogManager::GetLog(); motorEntries[name] = wpi::log::DoubleLogEntry( log, fmt::format("{}-{}-{}", name, m_motorName, m_logName), unit); @@ -44,7 +44,7 @@ SysIdRoutineLog::MotorLog SysIdRoutineLog::Motor(std::string_view motorName) { void SysIdRoutineLog::RecordState(State state) { if (!m_stateInitialized) { m_state = - wpi::log::StringLogEntry{frc::DataLogManager::GetLog(), + wpi::log::StringLogEntry{wpi::DataLogManager::GetLog(), fmt::format("sysid-test-state-{}", m_logName)}; m_stateInitialized = true; } diff --git a/wpilibc/src/main/native/cpp/system/DataLogManager.cpp b/wpilibc/src/main/native/cpp/system/DataLogManager.cpp index 95c0eeca61..ccddad91fc 100644 --- a/wpilibc/src/main/native/cpp/system/DataLogManager.cpp +++ b/wpilibc/src/main/native/cpp/system/DataLogManager.cpp @@ -28,11 +28,11 @@ #include "wpi/util/print.hpp" #include "wpi/util/timestamp.h" -using namespace frc; +using namespace wpi; namespace { -struct Thread final : public wpi::SafeThread { +struct Thread final : public wpi::util::SafeThread { Thread(std::string_view dir, std::string_view filename, double period); ~Thread() override; @@ -56,7 +56,7 @@ struct Thread final : public wpi::SafeThread { struct Instance { Instance(std::string_view dir, std::string_view filename, double period); - wpi::SafeThreadOwner owner; + wpi::util::SafeThreadOwner owner; }; } // namespace @@ -138,9 +138,9 @@ void Thread::Main() { std::vector entries; for (auto&& entry : fs::directory_iterator{m_logDir, ec}) { auto stem = entry.path().stem().string(); - if (wpi::starts_with(stem, "FRC_") && + if (wpi::util::starts_with(stem, "FRC_") && entry.path().extension() == ".wpilog" && - !wpi::starts_with(stem, "FRC_TBD_")) { + !wpi::util::starts_with(stem, "FRC_TBD_")) { entries.emplace_back(entry); } } @@ -164,7 +164,7 @@ void Thread::Main() { break; } } else { - wpi::print(stderr, "DataLogManager: could not delete {}\n", + wpi::util::print(stderr, "DataLogManager: could not delete {}\n", entry.path().string()); } } @@ -189,13 +189,13 @@ void Thread::Main() { m_log, "systemTime", "{\"source\":\"DataLogManager\",\"format\":\"time_t_us\"}"}; - wpi::Event newDataEvent; + wpi::util::Event newDataEvent; DriverStation::ProvideRefreshedDataEventHandle(newDataEvent.GetHandle()); for (;;) { bool timedOut = false; bool newData = - wpi::WaitForObject(newDataEvent.GetHandle(), 0.25, &timedOut); + wpi::util::WaitForObject(newDataEvent.GetHandle(), 0.25, &timedOut); if (!m_active) { break; } @@ -279,7 +279,7 @@ void Thread::Main() { if (sysTimeCount >= 250) { sysTimeCount = 0; if (RobotController::IsSystemTimeValid()) { - sysTimeEntry.Append(wpi::GetSystemTime(), wpi::Now()); + sysTimeEntry.Append(wpi::util::GetSystemTime(), wpi::util::Now()); } } } @@ -289,7 +289,7 @@ void Thread::Main() { void Thread::StartNTLog() { if (!m_ntLoggerEnabled) { m_ntLoggerEnabled = true; - auto inst = nt::NetworkTableInstance::GetDefault(); + auto inst = wpi::nt::NetworkTableInstance::GetDefault(); m_ntEntryLogger = inst.StartEntryDataLog(m_log, "", "NT:"); m_ntConnLogger = inst.StartConnectionDataLog(m_log, "NTConnection"); } @@ -298,8 +298,8 @@ void Thread::StartNTLog() { void Thread::StopNTLog() { if (m_ntLoggerEnabled) { m_ntLoggerEnabled = false; - nt::NetworkTableInstance::StopEntryDataLog(m_ntEntryLogger); - nt::NetworkTableInstance::StopConnectionDataLog(m_ntConnLogger); + wpi::nt::NetworkTableInstance::StopEntryDataLog(m_ntEntryLogger); + wpi::nt::NetworkTableInstance::StopConnectionDataLog(m_ntConnLogger); } } @@ -326,10 +326,10 @@ Instance::Instance(std::string_view dir, std::string_view filename, auto logDir = MakeLogDir(dir); std::error_code ec; for (auto&& entry : fs::directory_iterator{logDir, ec}) { - if (wpi::starts_with(entry.path().stem().string(), "FRC_TBD_") && + if (wpi::util::starts_with(entry.path().stem().string(), "FRC_TBD_") && entry.path().extension() == ".wpilog") { if (!fs::remove(entry, ec)) { - wpi::print(stderr, "DataLogManager: could not delete {}\n", + wpi::util::print(stderr, "DataLogManager: could not delete {}\n", entry.path().string()); } } @@ -361,7 +361,7 @@ void DataLogManager::Stop() { void DataLogManager::Log(std::string_view message) { GetInstance().owner.GetThread()->m_messageLog.Append(message); - wpi::print("{}\n", message); + wpi::util::print("{}\n", message); } wpi::log::DataLog& DataLogManager::GetLog() { diff --git a/wpilibc/src/main/native/cpp/system/Errors.cpp b/wpilibc/src/main/native/cpp/system/Errors.cpp index 083e457967..2678a1d5ea 100644 --- a/wpilibc/src/main/native/cpp/system/Errors.cpp +++ b/wpilibc/src/main/native/cpp/system/Errors.cpp @@ -12,7 +12,7 @@ #include "wpi/util/StackTrace.hpp" #include "wpi/util/fs.hpp" -using namespace frc; +using namespace wpi; RuntimeError::RuntimeError(int32_t code, std::string&& loc, std::string&& stack, std::string&& message) @@ -36,7 +36,7 @@ void RuntimeError::Report() const { m_data->stack.c_str(), 1); } -const char* frc::GetErrorMessage(int32_t* code) { +const char* wpi::GetErrorMessage(int32_t* code) { switch (*code) { #define S(label, offset, message) \ case err::label: \ @@ -53,7 +53,7 @@ const char* frc::GetErrorMessage(int32_t* code) { } } -void frc::ReportErrorV(int32_t status, const char* fileName, int lineNumber, +void wpi::ReportErrorV(int32_t status, const char* fileName, int lineNumber, const char* funcName, fmt::string_view format, fmt::format_args args) { if (status == 0) { @@ -64,10 +64,10 @@ void frc::ReportErrorV(int32_t status, const char* fileName, int lineNumber, fmt::vformat_to(fmt::appender{out}, format, args); out.push_back('\0'); HAL_SendError(status < 0, status, 0, out.data(), funcName, - wpi::GetStackTrace(2).c_str(), 1); + wpi::util::GetStackTrace(2).c_str(), 1); } -RuntimeError frc::MakeErrorV(int32_t status, const char* fileName, +RuntimeError wpi::MakeErrorV(int32_t status, const char* fileName, int lineNumber, const char* funcName, fmt::string_view format, fmt::format_args args) { fmt::memory_buffer out; @@ -77,6 +77,6 @@ RuntimeError frc::MakeErrorV(int32_t status, const char* fileName, fileName, lineNumber, funcName, - wpi::GetStackTrace(2), + wpi::util::GetStackTrace(2), fmt::to_string(out)}; } diff --git a/wpilibc/src/main/native/cpp/system/Filesystem.cpp b/wpilibc/src/main/native/cpp/system/Filesystem.cpp index eb73b5481a..62c49a6822 100644 --- a/wpilibc/src/main/native/cpp/system/Filesystem.cpp +++ b/wpilibc/src/main/native/cpp/system/Filesystem.cpp @@ -9,19 +9,19 @@ #include "wpi/opmode/RobotBase.hpp" #include "wpi/util/fs.hpp" -std::string frc::filesystem::GetLaunchDirectory() { +std::string wpi::filesystem::GetLaunchDirectory() { return fs::current_path().string(); } -std::string frc::filesystem::GetOperatingDirectory() { +std::string wpi::filesystem::GetOperatingDirectory() { if constexpr (!RobotBase::IsSimulation()) { return "/home/systemcore"; } else { - return frc::filesystem::GetLaunchDirectory(); + return wpi::filesystem::GetLaunchDirectory(); } } -std::string frc::filesystem::GetDeployDirectory() { +std::string wpi::filesystem::GetDeployDirectory() { if constexpr (!RobotBase::IsSimulation()) { return "/home/systemcore/deploy"; } else { diff --git a/wpilibc/src/main/native/cpp/system/Notifier.cpp b/wpilibc/src/main/native/cpp/system/Notifier.cpp index 1c01c5c7fb..71ba570557 100644 --- a/wpilibc/src/main/native/cpp/system/Notifier.cpp +++ b/wpilibc/src/main/native/cpp/system/Notifier.cpp @@ -14,7 +14,7 @@ #include "wpi/system/Errors.hpp" #include "wpi/system/Timer.hpp" -using namespace frc; +using namespace wpi; Notifier::Notifier(std::function callback) { if (!callback) { @@ -97,7 +97,7 @@ Notifier::Notifier(int priority, std::function callback) { if (callback) { try { callback(); - } catch (const frc::RuntimeError& e) { + } catch (const wpi::RuntimeError& e) { e.Report(); FRC_ReportError( err::Error, @@ -165,7 +165,7 @@ void Notifier::SetCallback(std::function callback) { m_callback = callback; } -void Notifier::StartSingle(units::second_t delay) { +void Notifier::StartSingle(wpi::units::second_t delay) { std::scoped_lock lock(m_processMutex); m_periodic = false; m_period = delay; @@ -173,7 +173,7 @@ void Notifier::StartSingle(units::second_t delay) { UpdateAlarm(); } -void Notifier::StartPeriodic(units::second_t period) { +void Notifier::StartPeriodic(wpi::units::second_t period) { std::scoped_lock lock(m_processMutex); m_periodic = true; m_period = period; @@ -181,7 +181,7 @@ void Notifier::StartPeriodic(units::second_t period) { UpdateAlarm(); } -void Notifier::StartPeriodic(units::hertz_t frequency) { +void Notifier::StartPeriodic(wpi::units::hertz_t frequency) { StartPeriodic(1 / frequency); } diff --git a/wpilibc/src/main/native/cpp/system/Resource.cpp b/wpilibc/src/main/native/cpp/system/Resource.cpp index feafdc4c21..bc4e3aa17f 100644 --- a/wpilibc/src/main/native/cpp/system/Resource.cpp +++ b/wpilibc/src/main/native/cpp/system/Resource.cpp @@ -13,9 +13,9 @@ #include "wpi/util/deprecated.hpp" WPI_IGNORE_DEPRECATED -using namespace frc; +using namespace wpi; -wpi::mutex Resource::m_createMutex; +wpi::util::mutex Resource::m_createMutex; void Resource::CreateResourceObject(std::unique_ptr& r, uint32_t elements) { diff --git a/wpilibc/src/main/native/cpp/system/RobotController.cpp b/wpilibc/src/main/native/cpp/system/RobotController.cpp index 3b60c64d0d..ca73275e09 100644 --- a/wpilibc/src/main/native/cpp/system/RobotController.cpp +++ b/wpilibc/src/main/native/cpp/system/RobotController.cpp @@ -12,7 +12,7 @@ #include "wpi/hal/Power.h" #include "wpi/system/Errors.hpp" -using namespace frc; +using namespace wpi; std::function RobotController::m_timeSource = [] { return RobotController::GetFPGATime(); @@ -21,7 +21,7 @@ std::function RobotController::m_timeSource = [] { std::string RobotController::GetSerialNumber() { WPI_String serialNum; HAL_GetSerialNumber(&serialNum); - std::string ret{wpi::to_string_view(&serialNum)}; + std::string ret{wpi::util::to_string_view(&serialNum)}; WPI_FreeString(&serialNum); return ret; } @@ -29,7 +29,7 @@ std::string RobotController::GetSerialNumber() { std::string RobotController::GetComments() { WPI_String comments; HAL_GetComments(&comments); - std::string ret{wpi::to_string_view(&comments)}; + std::string ret{wpi::util::to_string_view(&comments)}; WPI_FreeString(&comments); return ret; } @@ -53,11 +53,11 @@ uint64_t RobotController::GetFPGATime() { return time; } -units::volt_t RobotController::GetBatteryVoltage() { +wpi::units::volt_t RobotController::GetBatteryVoltage() { int32_t status = 0; double retVal = HAL_GetVinVoltage(&status); FRC_CheckErrorStatus(status, "GetBatteryVoltage"); - return units::volt_t{retVal}; + return wpi::units::volt_t{retVal}; } bool RobotController::IsSysActive() { @@ -142,24 +142,24 @@ void RobotController::ResetRailFaultCounts() { FRC_CheckErrorStatus(status, "ResetRailFaultCounts"); } -units::volt_t RobotController::GetBrownoutVoltage() { +wpi::units::volt_t RobotController::GetBrownoutVoltage() { int32_t status = 0; double retVal = HAL_GetBrownoutVoltage(&status); FRC_CheckErrorStatus(status, "GetBrownoutVoltage"); - return units::volt_t{retVal}; + return wpi::units::volt_t{retVal}; } -void RobotController::SetBrownoutVoltage(units::volt_t brownoutVoltage) { +void RobotController::SetBrownoutVoltage(wpi::units::volt_t brownoutVoltage) { int32_t status = 0; HAL_SetBrownoutVoltage(brownoutVoltage.value(), &status); FRC_CheckErrorStatus(status, "SetBrownoutVoltage"); } -units::celsius_t RobotController::GetCPUTemp() { +wpi::units::celsius_t RobotController::GetCPUTemp() { int32_t status = 0; double retVal = HAL_GetCPUTemp(&status); FRC_CheckErrorStatus(status, "GetCPUTemp"); - return units::celsius_t{retVal}; + return wpi::units::celsius_t{retVal}; } CANStatus RobotController::GetCANStatus(int busId) { diff --git a/wpilibc/src/main/native/cpp/system/ScopedTracer.cpp b/wpilibc/src/main/native/cpp/system/ScopedTracer.cpp index b8bd88c2db..39d50b17bb 100644 --- a/wpilibc/src/main/native/cpp/system/ScopedTracer.cpp +++ b/wpilibc/src/main/native/cpp/system/ScopedTracer.cpp @@ -6,9 +6,9 @@ #include "wpi/util/raw_ostream.hpp" -using namespace frc; +using namespace wpi; -ScopedTracer::ScopedTracer(std::string_view name, wpi::raw_ostream& os) +ScopedTracer::ScopedTracer(std::string_view name, wpi::util::raw_ostream& os) : m_name(name), m_os(os) { m_tracer.ResetTimer(); } diff --git a/wpilibc/src/main/native/cpp/system/SystemServer.cpp b/wpilibc/src/main/native/cpp/system/SystemServer.cpp index 892b23d9ec..6edf9ff865 100644 --- a/wpilibc/src/main/native/cpp/system/SystemServer.cpp +++ b/wpilibc/src/main/native/cpp/system/SystemServer.cpp @@ -5,10 +5,10 @@ #include "wpi/hal/SystemServer.h" #include "wpi/system/SystemServer.hpp" -namespace frc { +namespace wpi { -nt::NetworkTableInstance SystemServer::GetSystemServer() { - return nt::NetworkTableInstance{HAL_GetSystemServerHandle()}; +wpi::nt::NetworkTableInstance SystemServer::GetSystemServer() { + return wpi::nt::NetworkTableInstance{HAL_GetSystemServerHandle()}; } -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/cpp/system/Threads.cpp b/wpilibc/src/main/native/cpp/system/Threads.cpp index 8f4e11c28c..8a73c0c9f0 100644 --- a/wpilibc/src/main/native/cpp/system/Threads.cpp +++ b/wpilibc/src/main/native/cpp/system/Threads.cpp @@ -7,7 +7,7 @@ #include "wpi/system/Errors.hpp" -namespace frc { +namespace wpi { int GetThreadPriority(std::thread& thread, bool* isRealTime) { int32_t status = 0; @@ -43,4 +43,4 @@ bool SetCurrentThreadPriority(bool realTime, int priority) { return ret; } -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/cpp/system/Timer.cpp b/wpilibc/src/main/native/cpp/system/Timer.cpp index b7d20e8668..fd1e7b58f9 100644 --- a/wpilibc/src/main/native/cpp/system/Timer.cpp +++ b/wpilibc/src/main/native/cpp/system/Timer.cpp @@ -10,31 +10,31 @@ #include "wpi/driverstation/DriverStation.hpp" #include "wpi/system/RobotController.hpp" -namespace frc { +namespace wpi { -void Wait(units::second_t seconds) { +void Wait(wpi::units::second_t seconds) { std::this_thread::sleep_for(std::chrono::duration(seconds.value())); } -units::second_t GetTime() { +wpi::units::second_t GetTime() { using std::chrono::duration; using std::chrono::duration_cast; using std::chrono::system_clock; - return units::second_t{ + return wpi::units::second_t{ duration_cast>(system_clock::now().time_since_epoch()) .count()}; } -} // namespace frc +} // namespace wpi -using namespace frc; +using namespace wpi; Timer::Timer() { Reset(); } -units::second_t Timer::Get() const { +wpi::units::second_t Timer::Get() const { if (m_running) { return (GetTimestamp() - m_startTime) + m_accumulatedTime; } else { @@ -69,11 +69,11 @@ void Timer::Stop() { } } -bool Timer::HasElapsed(units::second_t period) const { +bool Timer::HasElapsed(wpi::units::second_t period) const { return Get() >= period; } -bool Timer::AdvanceIfElapsed(units::second_t period) { +bool Timer::AdvanceIfElapsed(wpi::units::second_t period) { if (Get() >= period) { // Advance the start time by the period. m_startTime += period; @@ -88,15 +88,15 @@ bool Timer::IsRunning() const { return m_running; } -units::second_t Timer::GetTimestamp() { - return units::second_t{frc::RobotController::GetTime() * 1.0e-6}; +wpi::units::second_t Timer::GetTimestamp() { + return wpi::units::second_t{wpi::RobotController::GetTime() * 1.0e-6}; } -units::second_t Timer::GetFPGATimestamp() { +wpi::units::second_t Timer::GetFPGATimestamp() { // FPGA returns the timestamp in microseconds - return units::second_t{frc::RobotController::GetFPGATime() * 1.0e-6}; + return wpi::units::second_t{wpi::RobotController::GetFPGATime() * 1.0e-6}; } -units::second_t Timer::GetMatchTime() { - return frc::DriverStation::GetMatchTime(); +wpi::units::second_t Timer::GetMatchTime() { + return wpi::DriverStation::GetMatchTime(); } diff --git a/wpilibc/src/main/native/cpp/system/Tracer.cpp b/wpilibc/src/main/native/cpp/system/Tracer.cpp index c3db2b8482..feefa21056 100644 --- a/wpilibc/src/main/native/cpp/system/Tracer.cpp +++ b/wpilibc/src/main/native/cpp/system/Tracer.cpp @@ -10,14 +10,14 @@ #include "wpi/util/SmallString.hpp" #include "wpi/util/raw_ostream.hpp" -using namespace frc; +using namespace wpi; Tracer::Tracer() { ResetTimer(); } void Tracer::ResetTimer() { - m_startTime = hal::fpga_clock::now(); + m_startTime = wpi::hal::fpga_clock::now(); } void Tracer::ClearEpochs() { @@ -26,25 +26,25 @@ void Tracer::ClearEpochs() { } void Tracer::AddEpoch(std::string_view epochName) { - auto currentTime = hal::fpga_clock::now(); + auto currentTime = wpi::hal::fpga_clock::now(); m_epochs[epochName] = currentTime - m_startTime; m_startTime = currentTime; } void Tracer::PrintEpochs() { - wpi::SmallString<128> buf; - wpi::raw_svector_ostream os(buf); + wpi::util::SmallString<128> buf; + wpi::util::raw_svector_ostream os(buf); PrintEpochs(os); if (!buf.empty()) { FRC_ReportWarning("{}", buf.c_str()); } } -void Tracer::PrintEpochs(wpi::raw_ostream& os) { +void Tracer::PrintEpochs(wpi::util::raw_ostream& os) { using std::chrono::duration_cast; using std::chrono::microseconds; - auto now = hal::fpga_clock::now(); + auto now = wpi::hal::fpga_clock::now(); if (now - m_lastEpochsPrintTime > kMinPrintPeriod) { m_lastEpochsPrintTime = now; for (const auto& epoch : m_epochs) { diff --git a/wpilibc/src/main/native/cpp/system/Watchdog.cpp b/wpilibc/src/main/native/cpp/system/Watchdog.cpp index a7f66d2d16..d83ce6e45b 100644 --- a/wpilibc/src/main/native/cpp/system/Watchdog.cpp +++ b/wpilibc/src/main/native/cpp/system/Watchdog.cpp @@ -17,7 +17,7 @@ #include "wpi/util/mutex.hpp" #include "wpi/util/priority_queue.hpp" -using namespace frc; +using namespace wpi; class Watchdog::Impl { public: @@ -31,9 +31,9 @@ class Watchdog::Impl { } }; - wpi::mutex m_mutex; + wpi::util::mutex m_mutex; std::atomic m_notifier; - wpi::priority_queue, + wpi::util::priority_queue, DerefGreater> m_watchdogs; @@ -110,7 +110,7 @@ void Watchdog::Impl::Main() { // has occurred, so call its timeout function. auto watchdog = m_watchdogs.pop(); - units::second_t now{curTime * 1e-6}; + wpi::units::second_t now{curTime * 1e-6}; if (now - watchdog->m_lastTimeoutPrintTime > kMinPrintPeriod) { watchdog->m_lastTimeoutPrintTime = now; if (!watchdog->m_suppressTimeoutMessage) { @@ -132,7 +132,7 @@ void Watchdog::Impl::Main() { } } -Watchdog::Watchdog(units::second_t timeout, std::function callback) +Watchdog::Watchdog(wpi::units::second_t timeout, std::function callback) : m_timeout(timeout), m_callback(std::move(callback)), m_impl(GetImpl()) {} Watchdog::~Watchdog() { @@ -165,11 +165,11 @@ Watchdog& Watchdog::operator=(Watchdog&& rhs) { return *this; } -units::second_t Watchdog::GetTime() const { +wpi::units::second_t Watchdog::GetTime() const { return Timer::GetFPGATimestamp() - m_startTime; } -void Watchdog::SetTimeout(units::second_t timeout) { +void Watchdog::SetTimeout(wpi::units::second_t timeout) { m_startTime = Timer::GetFPGATimestamp(); m_tracer.ClearEpochs(); @@ -183,7 +183,7 @@ void Watchdog::SetTimeout(units::second_t timeout) { m_impl->UpdateAlarm(); } -units::second_t Watchdog::GetTimeout() const { +wpi::units::second_t Watchdog::GetTimeout() const { std::scoped_lock lock(m_impl->m_mutex); return m_timeout; } diff --git a/wpilibc/src/main/native/cpp/util/Alert.cpp b/wpilibc/src/main/native/cpp/util/Alert.cpp index 6cf7d7f434..a1e4b4a07f 100644 --- a/wpilibc/src/main/native/cpp/util/Alert.cpp +++ b/wpilibc/src/main/native/cpp/util/Alert.cpp @@ -20,7 +20,7 @@ #include "wpi/util/sendable/SendableHelper.hpp" #include "wpi/util/sendable/SendableRegistry.hpp" -using namespace frc; +using namespace wpi; class Alert::PublishedAlert { public: @@ -37,12 +37,12 @@ class Alert::PublishedAlert { } }; -class Alert::SendableAlerts : public nt::NTSendable, - public wpi::SendableHelper { +class Alert::SendableAlerts : public wpi::nt::NTSendable, + public wpi::util::SendableHelper { public: SendableAlerts() { m_alerts.fill({}); } - void InitSendable(nt::NTSendableBuilder& builder) override { + void InitSendable(wpi::nt::NTSendableBuilder& builder) override { builder.SetSmartDashboardType("Alerts"); builder.AddStringArrayProperty( "errors", [this]() { return GetStrings(AlertType::kError); }, nullptr); @@ -70,7 +70,7 @@ class Alert::SendableAlerts : public nt::NTSendable, case AlertType::kError: return m_alerts[static_cast(type)]; default: - throw FRC_MakeError(frc::err::InvalidParameter, + throw FRC_MakeError(wpi::err::InvalidParameter, "Invalid Alert Type: {}", type); } } @@ -84,14 +84,14 @@ class Alert::SendableAlerts : public nt::NTSendable, static SendableAlerts& ForGroup(std::string_view group) { SendableAlerts* salert = nullptr; try { - auto* sendable = frc::SmartDashboard::GetData(group); + auto* sendable = wpi::SmartDashboard::GetData(group); salert = dynamic_cast(sendable); - } catch (frc::RuntimeError&) { + } catch (wpi::RuntimeError&) { } if (!salert) { // this leaks if ResetSmartDashboardInstance is called, but that's fine salert = new Alert::SendableAlerts; - frc::SmartDashboard::PutData(group, salert); + wpi::SmartDashboard::PutData(group, salert); } return *salert; } @@ -150,7 +150,7 @@ void Alert::Set(bool active) { } if (active) { - m_activeStartTime = frc::RobotController::GetTime(); + m_activeStartTime = wpi::RobotController::GetTime(); m_activeAlerts->emplace(m_activeStartTime, m_text); } else { m_activeAlerts->erase({m_activeStartTime, m_text}); @@ -173,7 +173,7 @@ void Alert::SetText(std::string_view text) { } } -std::string frc::format_as(Alert::AlertType type) { +std::string wpi::format_as(Alert::AlertType type) { switch (type) { case Alert::AlertType::kInfo: return "kInfo"; diff --git a/wpilibc/src/main/native/cpp/util/Preferences.cpp b/wpilibc/src/main/native/cpp/util/Preferences.cpp index 4cba8c2e59..2d78a02ed8 100644 --- a/wpilibc/src/main/native/cpp/util/Preferences.cpp +++ b/wpilibc/src/main/native/cpp/util/Preferences.cpp @@ -18,7 +18,7 @@ #include "wpi/nt/StringTopic.hpp" #include "wpi/util/json.hpp" -using namespace frc; +using namespace wpi; // The Preferences table name static constexpr std::string_view kTableName{"Preferences"}; @@ -27,13 +27,13 @@ namespace { struct Instance { Instance(); - std::shared_ptr table{ - nt::NetworkTableInstance::GetDefault().GetTable(kTableName)}; - nt::StringPublisher typePublisher{table->GetStringTopic(".type").PublishEx( - nt::StringTopic::kTypeString, {{"SmartDashboard", kSmartDashboardType}})}; - nt::MultiSubscriber tableSubscriber{nt::NetworkTableInstance::GetDefault(), + std::shared_ptr table{ + wpi::nt::NetworkTableInstance::GetDefault().GetTable(kTableName)}; + wpi::nt::StringPublisher typePublisher{table->GetStringTopic(".type").PublishEx( + wpi::nt::StringTopic::kTypeString, {{"SmartDashboard", kSmartDashboardType}})}; + wpi::nt::MultiSubscriber tableSubscriber{wpi::nt::NetworkTableInstance::GetDefault(), {{fmt::format("{}/", table->GetPath())}}}; - nt::NetworkTableListener listener; + wpi::nt::NetworkTableListener listener; }; } // namespace @@ -43,11 +43,11 @@ static Instance& GetInstance() { } #ifndef __FRC_SYSTEMCORE__ -namespace frc::impl { +namespace wpi::impl { void ResetPreferencesInstance() { GetInstance() = Instance(); } -} // namespace frc::impl +} // namespace wpi::impl #endif std::vector Preferences::GetKeys() { @@ -171,12 +171,12 @@ void Preferences::RemoveAll() { Instance::Instance() { typePublisher.Set(kSmartDashboardType); - listener = nt::NetworkTableListener::CreateListener( + listener = wpi::nt::NetworkTableListener::CreateListener( tableSubscriber, NT_EVENT_PUBLISH | NT_EVENT_IMMEDIATE, [typeTopic = typePublisher.GetTopic().GetHandle()](auto& event) { if (auto topicInfo = event.GetTopicInfo()) { if (topicInfo->topic != typeTopic) { - nt::SetTopicPersistent(topicInfo->topic, true); + wpi::nt::SetTopicPersistent(topicInfo->topic, true); } } }); diff --git a/wpilibc/src/main/native/cpp/util/SensorUtil.cpp b/wpilibc/src/main/native/cpp/util/SensorUtil.cpp index 67ffe9d039..bfc317aa38 100644 --- a/wpilibc/src/main/native/cpp/util/SensorUtil.cpp +++ b/wpilibc/src/main/native/cpp/util/SensorUtil.cpp @@ -9,7 +9,7 @@ #include "wpi/hal/PWM.h" #include "wpi/hal/Ports.h" -using namespace frc; +using namespace wpi; int SensorUtil::GetDefaultCTREPCMModule() { return 0; diff --git a/wpilibc/src/main/native/cppcs/RobotBase.cpp b/wpilibc/src/main/native/cppcs/RobotBase.cpp index 529ba00ce9..48651220f9 100644 --- a/wpilibc/src/main/native/cppcs/RobotBase.cpp +++ b/wpilibc/src/main/native/cppcs/RobotBase.cpp @@ -27,20 +27,20 @@ #include "wpi/util/print.hpp" #include "wpi/util/timestamp.h" -static_assert(frc::RuntimeType::kRoboRIO == - static_cast(HAL_Runtime_RoboRIO)); -static_assert(frc::RuntimeType::kRoboRIO2 == - static_cast(HAL_Runtime_RoboRIO2)); -static_assert(frc::RuntimeType::kSimulation == - static_cast(HAL_Runtime_Simulation)); -static_assert(frc::RuntimeType::kSystemCore == - static_cast(HAL_Runtime_SystemCore)); +static_assert(wpi::RuntimeType::kRoboRIO == + static_cast(HAL_Runtime_RoboRIO)); +static_assert(wpi::RuntimeType::kRoboRIO2 == + static_cast(HAL_Runtime_RoboRIO2)); +static_assert(wpi::RuntimeType::kSimulation == + static_cast(HAL_Runtime_Simulation)); +static_assert(wpi::RuntimeType::kSystemCore == + static_cast(HAL_Runtime_SystemCore)); -using SetCameraServerSharedFP = void (*)(frc::CameraServerShared*); +using SetCameraServerSharedFP = void (*)(wpi::CameraServerShared*); -using namespace frc; +using namespace wpi; -int frc::RunHALInitialization() { +int wpi::RunHALInitialization() { if (!HAL_Initialize(500, 0)) { std::puts("FATAL ERROR: HAL could not be initialized"); return -1; @@ -49,7 +49,7 @@ int frc::RunHALInitialization() { HAL_ReportUsage("Language", "C++"); HAL_ReportUsage("WPILibVersion", GetWPILibVersion()); - if (!frc::Notifier::SetHALThreadPriority(true, 40)) { + if (!wpi::Notifier::SetHALThreadPriority(true, 40)) { FRC_ReportWarning("Setting HAL Notifier RT priority to 40 failed\n"); } @@ -60,7 +60,7 @@ int frc::RunHALInitialization() { std::thread::id RobotBase::m_threadId; namespace { -class WPILibCameraServerShared : public frc::CameraServerShared { +class WPILibCameraServerShared : public wpi::CameraServerShared { public: void ReportUsage(std::string_view resource, std::string_view data) override { HAL_ReportUsage(resource, data); @@ -85,12 +85,12 @@ class WPILibCameraServerShared : public frc::CameraServerShared { class WPILibMathShared : public wpi::math::MathShared { public: void ReportErrorV(fmt::string_view format, fmt::format_args args) override { - frc::ReportErrorV(err::Error, __FILE__, __LINE__, __FUNCTION__, format, + wpi::ReportErrorV(err::Error, __FILE__, __LINE__, __FUNCTION__, format, args); } void ReportWarningV(fmt::string_view format, fmt::format_args args) override { - frc::ReportErrorV(warn::Warning, __FILE__, __LINE__, __FUNCTION__, format, + wpi::ReportErrorV(warn::Warning, __FILE__, __LINE__, __FUNCTION__, format, args); } @@ -98,8 +98,8 @@ class WPILibMathShared : public wpi::math::MathShared { HAL_ReportUsage(resource, data); } - units::second_t GetTimestamp() override { - return units::second_t{wpi::Now() * 1.0e-6}; + wpi::units::second_t GetTimestamp() override { + return wpi::units::second_t{wpi::util::Now() * 1.0e-6}; } }; } // namespace @@ -186,9 +186,9 @@ RobotBase::RobotBase() { SetupCameraServerShared(); SetupMathShared(); - auto inst = nt::NetworkTableInstance::GetDefault(); + auto inst = wpi::nt::NetworkTableInstance::GetDefault(); // subscribe to "" to force persistent values to propagate to local - nt::SubscribeMultiple(inst.GetHandle(), {{std::string_view{}}}); + wpi::nt::SubscribeMultiple(inst.GetHandle(), {{std::string_view{}}}); if constexpr (!IsSimulation()) { inst.StartServer("/home/systemcore/networktables.json"); } else { @@ -202,14 +202,14 @@ RobotBase::RobotBase() { std::this_thread::sleep_for(10ms); ++count; if (count > 100) { - wpi::print(stderr, "timed out while waiting for NT server to start\n"); + wpi::util::print(stderr, "timed out while waiting for NT server to start\n"); break; } } connListenerHandle = - inst.AddConnectionListener(false, [&](const nt::Event& event) { - if (event.Is(nt::EventFlags::kConnected)) { + inst.AddConnectionListener(false, [&](const wpi::nt::Event& event) { + if (event.Is(wpi::nt::EventFlags::kConnected)) { auto connInfo = event.GetConnectionInfo(); HAL_ReportUsage(fmt::format("NT/{}", connInfo->remote_id), ""); } diff --git a/wpilibc/src/main/native/include/wpi/ExpansionHub.hpp b/wpilibc/src/main/native/include/wpi/ExpansionHub.hpp index 37a245e32c..9079bbfe4a 100644 --- a/wpilibc/src/main/native/include/wpi/ExpansionHub.hpp +++ b/wpilibc/src/main/native/include/wpi/ExpansionHub.hpp @@ -9,7 +9,7 @@ #include "wpi/util/mutex.hpp" -namespace frc { +namespace wpi { class ExpansionHubServo; class ExpansionHubMotor; @@ -83,10 +83,10 @@ class ExpansionHub { std::shared_ptr m_dataStore; int m_usbId; - static wpi::mutex m_handleLock; + static wpi::util::mutex m_handleLock; static std::weak_ptr m_storeMap[4]; static std::shared_ptr GetForUsbId(int usbId); }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/ExpansionHubMotor.hpp b/wpilibc/src/main/native/include/wpi/ExpansionHubMotor.hpp index df123430a9..6c42dc3723 100644 --- a/wpilibc/src/main/native/include/wpi/ExpansionHubMotor.hpp +++ b/wpilibc/src/main/native/include/wpi/ExpansionHubMotor.hpp @@ -16,7 +16,7 @@ #include "wpi/units/time.hpp" #include "wpi/units/voltage.hpp" -namespace frc { +namespace wpi { /** This class controls a specific motor and encoder hooked up to an * ExpansionHub. */ @@ -44,7 +44,7 @@ class ExpansionHubMotor { * * @param voltage The voltage to drive the motor at */ - void SetVoltage(units::volt_t voltage); + void SetVoltage(wpi::units::volt_t voltage); /** * Command the motor to drive to a specific position setpoint. This value will @@ -82,7 +82,7 @@ class ExpansionHubMotor { * * @return Motor current */ - units::ampere_t GetCurrent() const; + wpi::units::ampere_t GetCurrent() const; /** * Sets the distance per count of the encoder. Used to scale encoder readings. @@ -152,22 +152,22 @@ class ExpansionHubMotor { ExpansionHub m_hub; int m_channel; - nt::DoubleSubscriber m_encoderSubscriber; - nt::DoubleSubscriber m_encoderVelocitySubscriber; - nt::DoubleSubscriber m_currentSubscriber; + wpi::nt::DoubleSubscriber m_encoderSubscriber; + wpi::nt::DoubleSubscriber m_encoderVelocitySubscriber; + wpi::nt::DoubleSubscriber m_currentSubscriber; - nt::DoublePublisher m_setpointPublisher; - nt::BooleanPublisher m_floatOn0Publisher; - nt::BooleanPublisher m_enabledPublisher; + wpi::nt::DoublePublisher m_setpointPublisher; + wpi::nt::BooleanPublisher m_floatOn0Publisher; + wpi::nt::BooleanPublisher m_enabledPublisher; - nt::IntegerPublisher m_modePublisher; + wpi::nt::IntegerPublisher m_modePublisher; - nt::BooleanPublisher m_reversedPublisher; - nt::BooleanPublisher m_resetEncoderPublisher; + wpi::nt::BooleanPublisher m_reversedPublisher; + wpi::nt::BooleanPublisher m_resetEncoderPublisher; - nt::DoublePublisher m_distancePerCountPublisher; + wpi::nt::DoublePublisher m_distancePerCountPublisher; ExpansionHubPidConstants m_velocityPidConstants; ExpansionHubPidConstants m_positionPidConstants; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/ExpansionHubPidConstants.hpp b/wpilibc/src/main/native/include/wpi/ExpansionHubPidConstants.hpp index 4873619fa9..629dac9b48 100644 --- a/wpilibc/src/main/native/include/wpi/ExpansionHubPidConstants.hpp +++ b/wpilibc/src/main/native/include/wpi/ExpansionHubPidConstants.hpp @@ -8,7 +8,7 @@ #include "wpi/nt/DoubleTopic.hpp" #include "wpi/nt/IntegerTopic.hpp" -namespace frc { +namespace wpi { class ExpansionHubMotor; /** This class contains PID constants for an ExpansionHub motor. */ @@ -67,15 +67,15 @@ class ExpansionHubPidConstants { private: ExpansionHubPidConstants(int usbId, int channel, bool isVelocityPid); - nt::DoublePublisher m_pPublisher; - nt::DoublePublisher m_iPublisher; - nt::DoublePublisher m_dPublisher; - nt::DoublePublisher m_sPublisher; - nt::DoublePublisher m_vPublisher; - nt::DoublePublisher m_aPublisher; + wpi::nt::DoublePublisher m_pPublisher; + wpi::nt::DoublePublisher m_iPublisher; + wpi::nt::DoublePublisher m_dPublisher; + wpi::nt::DoublePublisher m_sPublisher; + wpi::nt::DoublePublisher m_vPublisher; + wpi::nt::DoublePublisher m_aPublisher; - nt::BooleanPublisher m_continuousPublisher; - nt::DoublePublisher m_continuousMinimumPublisher; - nt::DoublePublisher m_continuousMaximumPublisher; + wpi::nt::BooleanPublisher m_continuousPublisher; + wpi::nt::DoublePublisher m_continuousMinimumPublisher; + wpi::nt::DoublePublisher m_continuousMaximumPublisher; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/ExpansionHubServo.hpp b/wpilibc/src/main/native/include/wpi/ExpansionHubServo.hpp index 1f9c7956fe..7c955d4928 100644 --- a/wpilibc/src/main/native/include/wpi/ExpansionHubServo.hpp +++ b/wpilibc/src/main/native/include/wpi/ExpansionHubServo.hpp @@ -12,7 +12,7 @@ #include "wpi/units/angle.hpp" #include "wpi/units/time.hpp" -namespace frc { +namespace wpi { /** This class controls a specific servo hooked up to an ExpansionHub. */ class ExpansionHubServo { @@ -45,14 +45,14 @@ class ExpansionHubServo { * @param angle Position in angle units. Will be scaled between 0 and 180 * degrees */ - void SetAngle(units::degree_t angle); + void SetAngle(wpi::units::degree_t angle); /** * Sets the raw pulse width output on the servo. * * @param pulseWidth Pulse width */ - void SetPulseWidth(units::microsecond_t pulseWidth); + void SetPulseWidth(wpi::units::microsecond_t pulseWidth); /** * Sets if the servo output is enabled or not. Defaults to false. @@ -66,7 +66,7 @@ class ExpansionHubServo { * * @param framePeriod The frame period */ - void SetFramePeriod(units::microsecond_t framePeriod); + void SetFramePeriod(wpi::units::microsecond_t framePeriod); /** * Gets if the underlying ExpansionHub is connected. @@ -84,7 +84,7 @@ class ExpansionHubServo { * @param minAngle Minimum angle * @param maxAngle Maximum angle */ - void SetAngleRange(units::degree_t minAngle, units::degree_t maxAngle); + void SetAngleRange(wpi::units::degree_t minAngle, wpi::units::degree_t maxAngle); /** * Sets the PWM range for the servo. @@ -95,7 +95,7 @@ class ExpansionHubServo { * @param minPwm Minimum PWM * @param maxPwm Maximum PWM */ - void SetPWMRange(units::microsecond_t minPwm, units::microsecond_t maxPwm); + void SetPWMRange(wpi::units::microsecond_t minPwm, wpi::units::microsecond_t maxPwm); /** * Sets whether the servo is reversed. @@ -117,23 +117,23 @@ class ExpansionHubServo { void SetContinousRotationMode(bool enable); private: - units::microsecond_t GetFullRangeScaleFactor(); - units::degree_t GetServoAngleRange(); + wpi::units::microsecond_t GetFullRangeScaleFactor(); + wpi::units::degree_t GetServoAngleRange(); ExpansionHub m_hub; int m_channel; - units::degree_t m_maxServoAngle = 180.0_deg; - units::degree_t m_minServoAngle = 0.0_deg; + wpi::units::degree_t m_maxServoAngle = 180.0_deg; + wpi::units::degree_t m_minServoAngle = 0.0_deg; - units::microsecond_t m_minPwm = 600_us; - units::microsecond_t m_maxPwm = 2400_us; + wpi::units::microsecond_t m_minPwm = 600_us; + wpi::units::microsecond_t m_maxPwm = 2400_us; bool m_reversed = false; bool m_continousMode = false; - nt::IntegerPublisher m_pulseWidthPublisher; - nt::IntegerPublisher m_framePeriodPublisher; - nt::BooleanPublisher m_enabledPublisher; + wpi::nt::IntegerPublisher m_pulseWidthPublisher; + wpi::nt::IntegerPublisher m_framePeriodPublisher; + wpi::nt::BooleanPublisher m_enabledPublisher; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/counter/EdgeConfiguration.hpp b/wpilibc/src/main/native/include/wpi/counter/EdgeConfiguration.hpp index 988edc3f2d..8954cc0ae9 100644 --- a/wpilibc/src/main/native/include/wpi/counter/EdgeConfiguration.hpp +++ b/wpilibc/src/main/native/include/wpi/counter/EdgeConfiguration.hpp @@ -4,7 +4,7 @@ #pragma once -namespace frc { +namespace wpi { /** * Edge configuration. */ @@ -14,4 +14,4 @@ enum class EdgeConfiguration { /// Falling edge configuration. kFallingEdge = 1, }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/counter/Tachometer.hpp b/wpilibc/src/main/native/include/wpi/counter/Tachometer.hpp index a7b3a9c6d9..4b321d67a8 100644 --- a/wpilibc/src/main/native/include/wpi/counter/Tachometer.hpp +++ b/wpilibc/src/main/native/include/wpi/counter/Tachometer.hpp @@ -15,7 +15,7 @@ #include "wpi/util/sendable/Sendable.hpp" #include "wpi/util/sendable/SendableHelper.hpp" -namespace frc { +namespace wpi { /** * Tachometer for getting rotational speed from a device. * @@ -25,8 +25,8 @@ namespace frc { * sensor, or optical sensor detecting tape on a shooter wheel. Unlike * encoders, this class only needs a single digital input. */ -class Tachometer : public wpi::Sendable, - public wpi::SendableHelper { +class Tachometer : public wpi::util::Sendable, + public wpi::util::SendableHelper { public: /** * Constructs a new tachometer. @@ -53,14 +53,14 @@ class Tachometer : public wpi::Sendable, * * @return Current frequency. */ - units::hertz_t GetFrequency() const; + wpi::units::hertz_t GetFrequency() const; /** * Gets the tachometer period. * * @return Current period. */ - units::second_t GetPeriod() const; + wpi::units::second_t GetPeriod() const; /** * Gets the number of edges per revolution. @@ -83,7 +83,7 @@ class Tachometer : public wpi::Sendable, * * @return Current RPS. */ - units::turns_per_second_t GetRevolutionsPerSecond() const; + wpi::units::turns_per_second_t GetRevolutionsPerSecond() const; /** * Gets the current tachometer revolutions per minute. @@ -92,7 +92,7 @@ class Tachometer : public wpi::Sendable, * * @return Current RPM. */ - units::revolutions_per_minute_t GetRevolutionsPerMinute() const; + wpi::units::revolutions_per_minute_t GetRevolutionsPerMinute() const; /** * Gets if the tachometer is stopped. @@ -106,14 +106,14 @@ class Tachometer : public wpi::Sendable, * * @param maxPeriod The max period. */ - void SetMaxPeriod(units::second_t maxPeriod); + void SetMaxPeriod(wpi::units::second_t maxPeriod); protected: - void InitSendable(wpi::SendableBuilder& builder) override; + void InitSendable(wpi::util::SendableBuilder& builder) override; private: - hal::Handle m_handle; + wpi::hal::Handle m_handle; int m_edgesPerRevolution; int32_t m_channel; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/counter/UpDownCounter.hpp b/wpilibc/src/main/native/include/wpi/counter/UpDownCounter.hpp index 297f51e2ef..4a2b1339bd 100644 --- a/wpilibc/src/main/native/include/wpi/counter/UpDownCounter.hpp +++ b/wpilibc/src/main/native/include/wpi/counter/UpDownCounter.hpp @@ -12,15 +12,15 @@ #include "wpi/util/sendable/Sendable.hpp" #include "wpi/util/sendable/SendableHelper.hpp" -namespace frc { +namespace wpi { /** Up Down Counter. * * This class can count edges on a single digital input or count up based on an * edge from one digital input and down on an edge from another digital input. * */ -class UpDownCounter : public wpi::Sendable, - public wpi::SendableHelper { +class UpDownCounter : public wpi::util::Sendable, + public wpi::util::SendableHelper { public: /** * Constructs a new UpDown Counter. @@ -53,10 +53,10 @@ class UpDownCounter : public wpi::Sendable, void SetEdgeConfiguration(EdgeConfiguration configuration); protected: - void InitSendable(wpi::SendableBuilder& builder) override; + void InitSendable(wpi::util::SendableBuilder& builder) override; private: - hal::Handle m_handle; + wpi::hal::Handle m_handle; int32_t m_channel; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/drive/DifferentialDrive.hpp b/wpilibc/src/main/native/include/wpi/drive/DifferentialDrive.hpp index 073ca32472..4446698dd4 100644 --- a/wpilibc/src/main/native/include/wpi/drive/DifferentialDrive.hpp +++ b/wpilibc/src/main/native/include/wpi/drive/DifferentialDrive.hpp @@ -12,7 +12,7 @@ #include "wpi/util/sendable/Sendable.hpp" #include "wpi/util/sendable/SendableHelper.hpp" -namespace frc { +namespace wpi { class MotorController; @@ -55,8 +55,8 @@ class MotorController; * Safety timeouts. */ class DifferentialDrive : public RobotDriveBase, - public wpi::Sendable, - public wpi::SendableHelper { + public wpi::util::Sendable, + public wpi::util::SendableHelper { public: /** * Wheel speeds for a differential drive. @@ -197,7 +197,7 @@ class DifferentialDrive : public RobotDriveBase, void StopMotor() override; std::string GetDescription() const override; - void InitSendable(wpi::SendableBuilder& builder) override; + void InitSendable(wpi::util::SendableBuilder& builder) override; private: std::function m_leftMotor; @@ -208,4 +208,4 @@ class DifferentialDrive : public RobotDriveBase, double m_rightOutput = 0.0; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/drive/MecanumDrive.hpp b/wpilibc/src/main/native/include/wpi/drive/MecanumDrive.hpp index 8c54eee311..104246db7e 100644 --- a/wpilibc/src/main/native/include/wpi/drive/MecanumDrive.hpp +++ b/wpilibc/src/main/native/include/wpi/drive/MecanumDrive.hpp @@ -15,7 +15,7 @@ #include "wpi/util/sendable/Sendable.hpp" #include "wpi/util/sendable/SendableHelper.hpp" -namespace frc { +namespace wpi { class MotorController; @@ -52,8 +52,8 @@ class MotorController; * methods should be called periodically to avoid Motor Safety timeouts. */ class MecanumDrive : public RobotDriveBase, - public wpi::Sendable, - public wpi::SendableHelper { + public wpi::util::Sendable, + public wpi::util::SendableHelper { public: /** * Wheel speeds for a mecanum drive. @@ -125,7 +125,7 @@ class MecanumDrive : public RobotDriveBase, * field-oriented controls. */ void DriveCartesian(double xSpeed, double ySpeed, double zRotation, - Rotation2d gyroAngle = 0_rad); + wpi::math::Rotation2d gyroAngle = 0_rad); /** * Drive method for Mecanum platform. @@ -139,7 +139,7 @@ class MecanumDrive : public RobotDriveBase, * @param zRotation The robot's rotation rate around the Z axis [-1.0..1.0]. * Counterclockwise is positive. */ - void DrivePolar(double magnitude, Rotation2d angle, double zRotation); + void DrivePolar(double magnitude, wpi::math::Rotation2d angle, double zRotation); /** * Cartesian inverse kinematics for Mecanum platform. @@ -159,12 +159,12 @@ class MecanumDrive : public RobotDriveBase, */ static WheelSpeeds DriveCartesianIK(double xSpeed, double ySpeed, double zRotation, - Rotation2d gyroAngle = 0_rad); + wpi::math::Rotation2d gyroAngle = 0_rad); void StopMotor() override; std::string GetDescription() const override; - void InitSendable(wpi::SendableBuilder& builder) override; + void InitSendable(wpi::util::SendableBuilder& builder) override; private: std::function m_frontLeftMotor; @@ -181,4 +181,4 @@ class MecanumDrive : public RobotDriveBase, bool reported = false; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/drive/RobotDriveBase.hpp b/wpilibc/src/main/native/include/wpi/drive/RobotDriveBase.hpp index f3790e1c2a..cc7158118a 100644 --- a/wpilibc/src/main/native/include/wpi/drive/RobotDriveBase.hpp +++ b/wpilibc/src/main/native/include/wpi/drive/RobotDriveBase.hpp @@ -10,7 +10,7 @@ #include "wpi/hardware/motor/MotorSafety.hpp" -namespace frc { +namespace wpi { /** * Common base class for drive platforms. @@ -50,7 +50,7 @@ class RobotDriveBase : public MotorSafety { * * The default value is 0.02. Inputs smaller than the deadband are set to 0.0 * while inputs larger than the deadband are scaled from 0.0 to 1.0. See - * frc::ApplyDeadband(). + * wpi::math::ApplyDeadband(). * * @param deadband The deadband to set. */ @@ -96,4 +96,4 @@ class RobotDriveBase : public MotorSafety { double m_maxOutput = kDefaultMaxOutput; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/driverstation/DSControlWord.hpp b/wpilibc/src/main/native/include/wpi/driverstation/DSControlWord.hpp index 799e6116dc..4e5b00881f 100644 --- a/wpilibc/src/main/native/include/wpi/driverstation/DSControlWord.hpp +++ b/wpilibc/src/main/native/include/wpi/driverstation/DSControlWord.hpp @@ -6,7 +6,7 @@ #include "wpi/hal/DriverStationTypes.h" -namespace frc { +namespace wpi { /** * A wrapper around Driver Station control word. @@ -99,4 +99,4 @@ class DSControlWord { HAL_ControlWord m_controlWord; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/driverstation/DriverStation.hpp b/wpilibc/src/main/native/include/wpi/driverstation/DriverStation.hpp index 1255b11d5c..fb4579f6c2 100644 --- a/wpilibc/src/main/native/include/wpi/driverstation/DriverStation.hpp +++ b/wpilibc/src/main/native/include/wpi/driverstation/DriverStation.hpp @@ -16,7 +16,7 @@ namespace wpi::log { class DataLog; } // namespace wpi::log -namespace frc { +namespace wpi { /** * Provide access to the network communication data to / from the Driver @@ -79,26 +79,26 @@ class DriverStation final { * @return The angle clockwise from straight up, or std::nullopt if the * POVDirection is kCenter. */ - static constexpr std::optional GetAngle(POVDirection angle) { + static constexpr std::optional GetAngle(POVDirection angle) { switch (angle) { case kCenter: return std::nullopt; case kUp: - return Rotation2d{0_deg}; + return wpi::math::Rotation2d{0_deg}; case kUpRight: - return Rotation2d{45_deg}; + return wpi::math::Rotation2d{45_deg}; case kRight: - return Rotation2d{90_deg}; + return wpi::math::Rotation2d{90_deg}; case kDownRight: - return Rotation2d{135_deg}; + return wpi::math::Rotation2d{135_deg}; case kDown: - return Rotation2d{180_deg}; + return wpi::math::Rotation2d{180_deg}; case kDownLeft: - return Rotation2d{225_deg}; + return wpi::math::Rotation2d{225_deg}; case kLeft: - return Rotation2d{270_deg}; + return wpi::math::Rotation2d{270_deg}; case kUpLeft: - return Rotation2d{315_deg}; + return wpi::math::Rotation2d{315_deg}; default: return std::nullopt; } @@ -433,7 +433,7 @@ class DriverStation final { * * @return Time remaining in current match period (auto or teleop) in seconds */ - static units::second_t GetMatchTime(); + static wpi::units::second_t GetMatchTime(); /** * Read the battery voltage. @@ -492,4 +492,4 @@ class DriverStation final { DriverStation() = default; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/driverstation/Gamepad.hpp b/wpilibc/src/main/native/include/wpi/driverstation/Gamepad.hpp index 9d25ca3e17..3ab751c264 100644 --- a/wpilibc/src/main/native/include/wpi/driverstation/Gamepad.hpp +++ b/wpilibc/src/main/native/include/wpi/driverstation/Gamepad.hpp @@ -8,7 +8,7 @@ #include "wpi/util/sendable/Sendable.hpp" #include "wpi/util/sendable/SendableHelper.hpp" -namespace frc { +namespace wpi { /** * Handle input from Gamepad controllers connected to the Driver Station. @@ -23,8 +23,8 @@ namespace frc { * to have the same mapping, as well as any 3rd party controllers. */ class Gamepad : public GenericHID, - public wpi::Sendable, - public wpi::SendableHelper { + public wpi::util::Sendable, + public wpi::util::SendableHelper { public: /** * Construct an instance of a controller. @@ -1007,11 +1007,11 @@ class Gamepad : public GenericHID, static constexpr int kRightTrigger = 5; }; - void InitSendable(wpi::SendableBuilder& builder) override; + void InitSendable(wpi::util::SendableBuilder& builder) override; private: double GetAxisForSendable(int axis) const; bool GetButtonForSendable(int button) const; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/driverstation/GenericHID.hpp b/wpilibc/src/main/native/include/wpi/driverstation/GenericHID.hpp index a3896716e0..f658651e89 100644 --- a/wpilibc/src/main/native/include/wpi/driverstation/GenericHID.hpp +++ b/wpilibc/src/main/native/include/wpi/driverstation/GenericHID.hpp @@ -10,7 +10,7 @@ #include "wpi/driverstation/DriverStation.hpp" -namespace frc { +namespace wpi { class BooleanEvent; class EventLoop; @@ -367,4 +367,4 @@ class GenericHID { uint16_t m_rightRumble = 0; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/driverstation/Joystick.hpp b/wpilibc/src/main/native/include/wpi/driverstation/Joystick.hpp index 53908fb013..5260cddbe5 100644 --- a/wpilibc/src/main/native/include/wpi/driverstation/Joystick.hpp +++ b/wpilibc/src/main/native/include/wpi/driverstation/Joystick.hpp @@ -9,7 +9,7 @@ #include "wpi/driverstation/GenericHID.hpp" #include "wpi/units/angle.hpp" -namespace frc { +namespace wpi { /** * Handle input from standard Joysticks connected to the Driver Station. @@ -259,7 +259,7 @@ class Joystick : public GenericHID { * * @return The direction of the vector. */ - units::radian_t GetDirection() const; + wpi::units::radian_t GetDirection() const; private: enum Axis { kX, kY, kZ, kTwist, kThrottle, kNumAxes }; @@ -268,4 +268,4 @@ class Joystick : public GenericHID { std::array m_axes; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/event/BooleanEvent.hpp b/wpilibc/src/main/native/include/wpi/event/BooleanEvent.hpp index f548048ee3..65d9260d99 100644 --- a/wpilibc/src/main/native/include/wpi/event/BooleanEvent.hpp +++ b/wpilibc/src/main/native/include/wpi/event/BooleanEvent.hpp @@ -12,7 +12,7 @@ #include "wpi/units/time.hpp" #include "wpi/util/FunctionExtras.hpp" -namespace frc { +namespace wpi { /** * This class provides an easy way to link actions to active high logic signals. @@ -122,9 +122,9 @@ class BooleanEvent { * @param type The debounce type. * @return The debounced event. */ - BooleanEvent Debounce(units::second_t debounceTime, - frc::Debouncer::DebounceType type = - frc::Debouncer::DebounceType::kRising); + BooleanEvent Debounce(wpi::units::second_t debounceTime, + wpi::math::Debouncer::DebounceType type = + wpi::math::Debouncer::DebounceType::kRising); private: /// Poller loop. @@ -135,4 +135,4 @@ class BooleanEvent { /// The state of the condition in the current loop poll. std::shared_ptr m_state; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/event/EventLoop.hpp b/wpilibc/src/main/native/include/wpi/event/EventLoop.hpp index 3f5f2aca27..b67cc40aea 100644 --- a/wpilibc/src/main/native/include/wpi/event/EventLoop.hpp +++ b/wpilibc/src/main/native/include/wpi/event/EventLoop.hpp @@ -9,7 +9,7 @@ #include "wpi/util/FunctionExtras.hpp" -namespace frc { +namespace wpi { /** A declarative way to bind a set of actions to a loop and execute them when * the loop is polled. */ class EventLoop { @@ -24,7 +24,7 @@ class EventLoop { * * @param action the action to run. */ - void Bind(wpi::unique_function action); + void Bind(wpi::util::unique_function action); /** * Poll all bindings. @@ -37,7 +37,7 @@ class EventLoop { void Clear(); private: - std::vector> m_bindings; + std::vector> m_bindings; bool m_running{false}; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/event/NetworkBooleanEvent.hpp b/wpilibc/src/main/native/include/wpi/event/NetworkBooleanEvent.hpp index ac3b5e1f99..6c938e1adc 100644 --- a/wpilibc/src/main/native/include/wpi/event/NetworkBooleanEvent.hpp +++ b/wpilibc/src/main/native/include/wpi/event/NetworkBooleanEvent.hpp @@ -16,7 +16,7 @@ class NetworkTable; class NetworkTableInstance; } // namespace nt -namespace frc { +namespace wpi { /** * A Button that uses a NetworkTable boolean field. * @@ -31,7 +31,7 @@ class NetworkBooleanEvent : public BooleanEvent { * @param loop the loop that polls this event * @param topic The boolean topic that contains the value */ - NetworkBooleanEvent(EventLoop* loop, nt::BooleanTopic topic); + NetworkBooleanEvent(EventLoop* loop, wpi::nt::BooleanTopic topic); /** * Creates a new event with the given boolean subscriber determining whether @@ -40,7 +40,7 @@ class NetworkBooleanEvent : public BooleanEvent { * @param loop the loop that polls this event * @param sub The boolean subscriber that provides the value */ - NetworkBooleanEvent(EventLoop* loop, nt::BooleanSubscriber sub); + NetworkBooleanEvent(EventLoop* loop, wpi::nt::BooleanSubscriber sub); /** * Creates a new event with the given boolean topic determining whether it is @@ -50,7 +50,7 @@ class NetworkBooleanEvent : public BooleanEvent { * @param table The NetworkTable that contains the topic * @param topicName The topic name within the table that contains the value */ - NetworkBooleanEvent(EventLoop* loop, std::shared_ptr table, + NetworkBooleanEvent(EventLoop* loop, std::shared_ptr table, std::string_view topicName); /** @@ -73,7 +73,7 @@ class NetworkBooleanEvent : public BooleanEvent { * @param tableName The NetworkTable that contains the topic * @param topicName The topic name within the table that contains the value */ - NetworkBooleanEvent(EventLoop* loop, nt::NetworkTableInstance inst, + NetworkBooleanEvent(EventLoop* loop, wpi::nt::NetworkTableInstance inst, std::string_view tableName, std::string_view topicName); }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/hardware/accelerometer/ADXL345_I2C.hpp b/wpilibc/src/main/native/include/wpi/hardware/accelerometer/ADXL345_I2C.hpp index 09c31fcec8..197b5872ec 100644 --- a/wpilibc/src/main/native/include/wpi/hardware/accelerometer/ADXL345_I2C.hpp +++ b/wpilibc/src/main/native/include/wpi/hardware/accelerometer/ADXL345_I2C.hpp @@ -9,7 +9,7 @@ #include "wpi/nt/NTSendable.hpp" #include "wpi/util/sendable/SendableHelper.hpp" -namespace frc { +namespace wpi { /** * ADXL345 Accelerometer on I2C. @@ -18,8 +18,8 @@ namespace frc { * an I2C bus. This class assumes the default (not alternate) sensor address of * 0x1D (7-bit address). */ -class ADXL345_I2C : public nt::NTSendable, - public wpi::SendableHelper { +class ADXL345_I2C : public wpi::nt::NTSendable, + public wpi::util::SendableHelper { public: /** * Accelerometer range. @@ -124,16 +124,16 @@ class ADXL345_I2C : public nt::NTSendable, */ virtual AllAxes GetAccelerations(); - void InitSendable(nt::NTSendableBuilder& builder) override; + void InitSendable(wpi::nt::NTSendableBuilder& builder) override; private: I2C m_i2c; - hal::SimDevice m_simDevice; - hal::SimEnum m_simRange; - hal::SimDouble m_simX; - hal::SimDouble m_simY; - hal::SimDouble m_simZ; + wpi::hal::SimDevice m_simDevice; + wpi::hal::SimEnum m_simRange; + wpi::hal::SimDouble m_simX; + wpi::hal::SimDouble m_simY; + wpi::hal::SimDouble m_simZ; static constexpr int kPowerCtlRegister = 0x2D; static constexpr int kDataFormatRegister = 0x31; @@ -156,4 +156,4 @@ class ADXL345_I2C : public nt::NTSendable, }; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/hardware/accelerometer/AnalogAccelerometer.hpp b/wpilibc/src/main/native/include/wpi/hardware/accelerometer/AnalogAccelerometer.hpp index 637c1080e1..2c0f59b06e 100644 --- a/wpilibc/src/main/native/include/wpi/hardware/accelerometer/AnalogAccelerometer.hpp +++ b/wpilibc/src/main/native/include/wpi/hardware/accelerometer/AnalogAccelerometer.hpp @@ -10,7 +10,7 @@ #include "wpi/util/sendable/Sendable.hpp" #include "wpi/util/sendable/SendableHelper.hpp" -namespace frc { +namespace wpi { /** * Handle operation of an analog accelerometer. @@ -19,8 +19,8 @@ namespace frc { * sensors have multiple axis and can be treated as multiple devices. Each is * calibrated by finding the center value over a period of time. */ -class AnalogAccelerometer : public wpi::Sendable, - public wpi::SendableHelper { +class AnalogAccelerometer : public wpi::util::Sendable, + public wpi::util::SendableHelper { public: /** * Create a new instance of an accelerometer. @@ -89,7 +89,7 @@ class AnalogAccelerometer : public wpi::Sendable, */ void SetZero(double zero); - void InitSendable(wpi::SendableBuilder& builder) override; + void InitSendable(wpi::util::SendableBuilder& builder) override; private: /** @@ -102,4 +102,4 @@ class AnalogAccelerometer : public wpi::Sendable, double m_zeroGVoltage = 2.5; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/hardware/bus/CAN.hpp b/wpilibc/src/main/native/include/wpi/hardware/bus/CAN.hpp index 78cf6ebb11..f8723f8585 100644 --- a/wpilibc/src/main/native/include/wpi/hardware/bus/CAN.hpp +++ b/wpilibc/src/main/native/include/wpi/hardware/bus/CAN.hpp @@ -8,7 +8,7 @@ #include "wpi/hal/CANAPI.h" -namespace frc { +namespace wpi { /** * High level class for interfacing with CAN devices conforming to @@ -154,6 +154,6 @@ class CAN { HAL_CAN_Dev_kMiscellaneous; private: - hal::Handle m_handle; + wpi::hal::Handle m_handle; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/hardware/bus/I2C.hpp b/wpilibc/src/main/native/include/wpi/hardware/bus/I2C.hpp index ca8acb942e..0a5ce53389 100644 --- a/wpilibc/src/main/native/include/wpi/hardware/bus/I2C.hpp +++ b/wpilibc/src/main/native/include/wpi/hardware/bus/I2C.hpp @@ -9,7 +9,7 @@ #include "wpi/hal/I2C.h" #include "wpi/hal/I2CTypes.h" -namespace frc { +namespace wpi { /** * I2C bus interface class. @@ -153,8 +153,8 @@ class I2C { bool VerifySensor(int registerAddress, int count, const uint8_t* expected); private: - hal::Handle m_port; + wpi::hal::Handle m_port; int m_deviceAddress; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/hardware/bus/SerialPort.hpp b/wpilibc/src/main/native/include/wpi/hardware/bus/SerialPort.hpp index 0bd8ee2183..e19b318b37 100644 --- a/wpilibc/src/main/native/include/wpi/hardware/bus/SerialPort.hpp +++ b/wpilibc/src/main/native/include/wpi/hardware/bus/SerialPort.hpp @@ -11,7 +11,7 @@ #include "wpi/hal/Types.h" #include "wpi/units/time.hpp" -namespace frc { +namespace wpi { /** * Driver for the RS-232 serial port on the roboRIO. @@ -199,7 +199,7 @@ class SerialPort { * * @param timeout The time to wait for I/O. */ - void SetTimeout(units::second_t timeout); + void SetTimeout(wpi::units::second_t timeout); /** * Specify the size of the input buffer. @@ -254,7 +254,7 @@ class SerialPort { void Reset(); private: - hal::Handle m_portHandle; + wpi::hal::Handle m_portHandle; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/hardware/discrete/AnalogInput.hpp b/wpilibc/src/main/native/include/wpi/hardware/discrete/AnalogInput.hpp index 01196dec25..aa48471641 100644 --- a/wpilibc/src/main/native/include/wpi/hardware/discrete/AnalogInput.hpp +++ b/wpilibc/src/main/native/include/wpi/hardware/discrete/AnalogInput.hpp @@ -11,7 +11,7 @@ #include "wpi/util/sendable/Sendable.hpp" #include "wpi/util/sendable/SendableHelper.hpp" -namespace frc { +namespace wpi { /** * Analog input class. @@ -25,8 +25,8 @@ namespace frc { * are divided by the number of samples to retain the resolution, but get more * stable values. */ -class AnalogInput : public wpi::Sendable, - public wpi::SendableHelper { +class AnalogInput : public wpi::util::Sendable, + public wpi::util::SendableHelper { public: /** * Construct an analog input. @@ -194,11 +194,11 @@ class AnalogInput : public wpi::Sendable, */ void SetSimDevice(HAL_SimDeviceHandle device); - void InitSendable(wpi::SendableBuilder& builder) override; + void InitSendable(wpi::util::SendableBuilder& builder) override; private: int m_channel; - hal::Handle m_port; + wpi::hal::Handle m_port; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/hardware/discrete/CounterBase.hpp b/wpilibc/src/main/native/include/wpi/hardware/discrete/CounterBase.hpp index 4cee9ad4e0..bff31f59de 100644 --- a/wpilibc/src/main/native/include/wpi/hardware/discrete/CounterBase.hpp +++ b/wpilibc/src/main/native/include/wpi/hardware/discrete/CounterBase.hpp @@ -6,7 +6,7 @@ #include "wpi/units/time.hpp" -namespace frc { +namespace wpi { /** * Interface for counting the number of ticks on a digital input channel. @@ -29,10 +29,10 @@ class CounterBase { virtual int Get() const = 0; virtual void Reset() = 0; - virtual units::second_t GetPeriod() const = 0; - virtual void SetMaxPeriod(units::second_t maxPeriod) = 0; + virtual wpi::units::second_t GetPeriod() const = 0; + virtual void SetMaxPeriod(wpi::units::second_t maxPeriod) = 0; virtual bool GetStopped() const = 0; virtual bool GetDirection() const = 0; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/hardware/discrete/DigitalInput.hpp b/wpilibc/src/main/native/include/wpi/hardware/discrete/DigitalInput.hpp index 96727924d2..fef8a3a7dd 100644 --- a/wpilibc/src/main/native/include/wpi/hardware/discrete/DigitalInput.hpp +++ b/wpilibc/src/main/native/include/wpi/hardware/discrete/DigitalInput.hpp @@ -8,7 +8,7 @@ #include "wpi/util/sendable/Sendable.hpp" #include "wpi/util/sendable/SendableHelper.hpp" -namespace frc { +namespace wpi { /** * Class to read a digital input. @@ -19,8 +19,8 @@ namespace frc { * as required. This class is only for devices like switches etc. that aren't * implemented anywhere else. */ -class DigitalInput : public wpi::Sendable, - public wpi::SendableHelper { +class DigitalInput : public wpi::util::Sendable, + public wpi::util::SendableHelper { public: /** * Create an instance of a Digital Input class. @@ -55,11 +55,11 @@ class DigitalInput : public wpi::Sendable, */ void SetSimDevice(HAL_SimDeviceHandle device); - void InitSendable(wpi::SendableBuilder& builder) override; + void InitSendable(wpi::util::SendableBuilder& builder) override; private: int m_channel; - hal::Handle m_handle; + wpi::hal::Handle m_handle; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/hardware/discrete/DigitalOutput.hpp b/wpilibc/src/main/native/include/wpi/hardware/discrete/DigitalOutput.hpp index 1294d678ac..3377855b18 100644 --- a/wpilibc/src/main/native/include/wpi/hardware/discrete/DigitalOutput.hpp +++ b/wpilibc/src/main/native/include/wpi/hardware/discrete/DigitalOutput.hpp @@ -10,7 +10,7 @@ #include "wpi/util/sendable/Sendable.hpp" #include "wpi/util/sendable/SendableHelper.hpp" -namespace frc { +namespace wpi { /** * Class to write to digital outputs. @@ -19,8 +19,8 @@ namespace frc { * elsewhere will allocate channels automatically so for those devices it * shouldn't be done here. */ -class DigitalOutput : public wpi::Sendable, - public wpi::SendableHelper { +class DigitalOutput : public wpi::util::Sendable, + public wpi::util::SendableHelper { public: /** * Create an instance of a digital output. @@ -66,7 +66,7 @@ class DigitalOutput : public wpi::Sendable, * * @param pulseLength The pulse length in seconds */ - void Pulse(units::second_t pulseLength); + void Pulse(wpi::units::second_t pulseLength); /** * Determine if the pulse is still going. @@ -139,12 +139,12 @@ class DigitalOutput : public wpi::Sendable, */ void SetSimDevice(HAL_SimDeviceHandle device); - void InitSendable(wpi::SendableBuilder& builder) override; + void InitSendable(wpi::util::SendableBuilder& builder) override; private: int m_channel; - hal::Handle m_handle; - hal::Handle m_pwmGenerator; + wpi::hal::Handle m_handle; + wpi::hal::Handle m_pwmGenerator; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/hardware/discrete/PWM.hpp b/wpilibc/src/main/native/include/wpi/hardware/discrete/PWM.hpp index 710b09bf57..ec14892fda 100644 --- a/wpilibc/src/main/native/include/wpi/hardware/discrete/PWM.hpp +++ b/wpilibc/src/main/native/include/wpi/hardware/discrete/PWM.hpp @@ -12,7 +12,7 @@ #include "wpi/util/sendable/Sendable.hpp" #include "wpi/util/sendable/SendableHelper.hpp" -namespace frc { +namespace wpi { class AddressableLED; /** @@ -23,7 +23,7 @@ class AddressableLED; * (off) to 4096. Changes are immediately sent to the FPGA, and the update * occurs at the next FPGA cycle (5.05ms). There is no delay. */ -class PWM : public wpi::Sendable, public wpi::SendableHelper { +class PWM : public wpi::util::Sendable, public wpi::util::SendableHelper { public: friend class AddressableLED; /** @@ -74,7 +74,7 @@ class PWM : public wpi::Sendable, public wpi::SendableHelper { * * @param time Microsecond PWM value. */ - void SetPulseTime(units::microsecond_t time); + void SetPulseTime(wpi::units::microsecond_t time); /** * Get the PWM pulse time directly from the hardware. @@ -83,7 +83,7 @@ class PWM : public wpi::Sendable, public wpi::SendableHelper { * * @return Microsecond PWM control value. */ - units::microsecond_t GetPulseTime() const; + wpi::units::microsecond_t GetPulseTime() const; /** * Temporarily disables the PWM output. The next set call will re-enable @@ -108,11 +108,11 @@ class PWM : public wpi::Sendable, public wpi::SendableHelper { void SetSimDevice(HAL_SimDeviceHandle device); protected: - void InitSendable(wpi::SendableBuilder& builder) override; + void InitSendable(wpi::util::SendableBuilder& builder) override; private: int m_channel; - hal::Handle m_handle; + wpi::hal::Handle m_handle; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/hardware/imu/OnboardIMU.hpp b/wpilibc/src/main/native/include/wpi/hardware/imu/OnboardIMU.hpp index b456938716..94143fad90 100644 --- a/wpilibc/src/main/native/include/wpi/hardware/imu/OnboardIMU.hpp +++ b/wpilibc/src/main/native/include/wpi/hardware/imu/OnboardIMU.hpp @@ -10,7 +10,7 @@ #include "wpi/units/angle.hpp" #include "wpi/units/angular_velocity.hpp" -namespace frc { +namespace wpi { /** * SystemCore onboard IMU @@ -42,7 +42,7 @@ class OnboardIMU { * Get the yaw value * @return yaw value */ - units::radian_t GetYaw(); + wpi::units::radian_t GetYaw(); /** * Reset the current yaw value to 0. Future reads of the yaw value will be @@ -51,80 +51,80 @@ class OnboardIMU { void ResetYaw(); /** - * Get the yaw as a Rotation2d. + * Get the yaw as a wpi::math::Rotation2d. * @return yaw */ - Rotation2d GetRotation2d(); + wpi::math::Rotation2d GetRotation2d(); /** - * Get the 3D orientation as a Rotation3d. + * Get the 3D orientation as a wpi::math::Rotation3d. * @return 3D orientation */ - Rotation3d GetRotation3d(); + wpi::math::Rotation3d GetRotation3d(); /** - * Get the 3D orientation as a Quaternion. + * Get the 3D orientation as a wpi::math::Quaternion. * @return 3D orientation */ - Quaternion GetQuaternion(); + wpi::math::Quaternion GetQuaternion(); /** * Get the angle about the X axis of the IMU. * @return angle about the X axis */ - units::radian_t GetAngleX(); + wpi::units::radian_t GetAngleX(); /** * Get the angle about the Y axis of the IMU. * @return angle about the Y axis */ - units::radian_t GetAngleY(); + wpi::units::radian_t GetAngleY(); /** * Get the angle about the Z axis of the IMU. * @return angle about the Z axis */ - units::radian_t GetAngleZ(); + wpi::units::radian_t GetAngleZ(); /** * Get the angular rate about the X axis of the IMU. * @return angular rate about the X axis */ - units::radians_per_second_t GetGyroRateX(); + wpi::units::radians_per_second_t GetGyroRateX(); /** * Get the angular rate about the Y axis of the IMU. * @return angular rate about the Y axis */ - units::radians_per_second_t GetGyroRateY(); + wpi::units::radians_per_second_t GetGyroRateY(); /** * Get the angular rate about the Z axis of the IMU. * @return angular rate about the Z axis */ - units::radians_per_second_t GetGyroRateZ(); + wpi::units::radians_per_second_t GetGyroRateZ(); /** * Get the acceleration along the X axis of the IMU. * @return acceleration along the X axis */ - units::meters_per_second_squared_t GetAccelX(); + wpi::units::meters_per_second_squared_t GetAccelX(); /** * Get the acceleration along the Z axis of the IMU. * @return acceleration along the Z axis */ - units::meters_per_second_squared_t GetAccelY(); + wpi::units::meters_per_second_squared_t GetAccelY(); /** * Get the acceleration along the Z axis of the IMU. * @return acceleration along the Z axis */ - units::meters_per_second_squared_t GetAccelZ(); + wpi::units::meters_per_second_squared_t GetAccelZ(); private: - units::radian_t GetYawNoOffset(); + wpi::units::radian_t GetYawNoOffset(); MountOrientation m_mountOrientation; - units::radian_t m_yawOffset{0}; + wpi::units::radian_t m_yawOffset{0}; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/hardware/led/AddressableLED.hpp b/wpilibc/src/main/native/include/wpi/hardware/led/AddressableLED.hpp index 0b711344c9..f616294b99 100644 --- a/wpilibc/src/main/native/include/wpi/hardware/led/AddressableLED.hpp +++ b/wpilibc/src/main/native/include/wpi/hardware/led/AddressableLED.hpp @@ -14,7 +14,7 @@ #include "wpi/util/Color.hpp" #include "wpi/util/Color8Bit.hpp" -namespace frc { +namespace wpi { /** * A class for driving addressable LEDs, such as WS2812B, WS2815, and NeoPixels. @@ -171,7 +171,7 @@ class AddressableLED { std::span ledData); private: - hal::Handle m_handle; + wpi::hal::Handle m_handle; int m_channel; int m_start{0}; int m_length{0}; @@ -182,4 +182,4 @@ constexpr auto format_as(AddressableLED::ColorOrder order) { return static_cast(order); } -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/hardware/led/LEDPattern.hpp b/wpilibc/src/main/native/include/wpi/hardware/led/LEDPattern.hpp index 5594f87d06..f898802b79 100644 --- a/wpilibc/src/main/native/include/wpi/hardware/led/LEDPattern.hpp +++ b/wpilibc/src/main/native/include/wpi/hardware/led/LEDPattern.hpp @@ -15,7 +15,7 @@ #include "wpi/units/velocity.hpp" #include "wpi/util/Color.hpp" -namespace frc { +namespace wpi { class LEDPattern { public: @@ -26,27 +26,27 @@ class LEDPattern { */ class LEDReader { public: - LEDReader(std::function impl, + LEDReader(std::function impl, size_t size) : m_impl{std::move(impl)}, m_size{size} {} - frc::AddressableLED::LEDData operator[](size_t index) const { + wpi::AddressableLED::LEDData operator[](size_t index) const { return m_impl(index); } size_t size() const { return m_size; } private: - std::function m_impl; + std::function m_impl; size_t m_size; }; - explicit LEDPattern(std::function)> + explicit LEDPattern(std::function)> impl); void ApplyTo(LEDReader reader, - std::function writer) const; + std::function writer) const; /** * Writes the pattern to an LED buffer. Dynamic animations should be called @@ -61,8 +61,8 @@ class LEDPattern { * @param data the current data of the LED strip * @param writer data writer for setting new LED colors on the LED strip */ - void ApplyTo(std::span data, - std::function writer) const; + void ApplyTo(std::span data, + std::function writer) const; /** * Writes the pattern to an LED buffer. Dynamic animations should be called @@ -76,7 +76,7 @@ class LEDPattern { * * @param data the current data of the LED strip */ - void ApplyTo(std::span data) const; + void ApplyTo(std::span data) const; /** * Creates a pattern with remapped indices. @@ -120,7 +120,7 @@ class LEDPattern { * long (assuming equal LED density on both segments). */ [[nodiscard]] - LEDPattern ScrollAtRelativeSpeed(units::hertz_t velocity); + LEDPattern ScrollAtRelativeSpeed(wpi::units::hertz_t velocity); /** * Creates a pattern that plays this one scrolling up an LED strip. A negative @@ -131,11 +131,11 @@ class LEDPattern { * *

    *   // LEDs per meter, a known value taken from the spec sheet of our
-   * particular LED strip units::meter_t LED_SPACING = units::meter_t{1 /60.0};
+   * particular LED strip wpi::units::meter_t LED_SPACING = wpi::units::meter_t{1 /60.0};
    *
-   *   frc::LEDPattern rainbow = frc::LEDPattern::Rainbow();
-   *   frc::LEDPattern scrollingRainbow =
-   *     rainbow.ScrollAtAbsoluteSpeed(units::feet_per_second_t{1 / 3.0},
+   *   wpi::LEDPattern rainbow = wpi::LEDPattern::Rainbow();
+   *   wpi::LEDPattern scrollingRainbow =
+   *     rainbow.ScrollAtAbsoluteSpeed(wpi::units::feet_per_second_t{1 / 3.0},
    * LED_SPACING);
    * 
* @@ -149,8 +149,8 @@ class LEDPattern { * @return the scrolling pattern */ [[nodiscard]] - LEDPattern ScrollAtAbsoluteSpeed(units::meters_per_second_t velocity, - units::meter_t ledSpacing); + LEDPattern ScrollAtAbsoluteSpeed(wpi::units::meters_per_second_t velocity, + wpi::units::meter_t ledSpacing); /** * Creates a pattern that switches between playing this pattern and turning @@ -161,10 +161,10 @@ class LEDPattern { * @return the blinking pattern */ [[nodiscard]] - LEDPattern Blink(units::second_t onTime, units::second_t offTime); + LEDPattern Blink(wpi::units::second_t onTime, wpi::units::second_t offTime); /** - * Like {@link LEDPattern::Blink(units::second_t)}, but where the + * Like {@link LEDPattern::Blink(wpi::units::second_t)}, but where the * "off" time is exactly equal to the "on" time. * * @param onTime how long the pattern should play for (and be turned off for), @@ -172,7 +172,7 @@ class LEDPattern { * @return the blinking pattern */ [[nodiscard]] - LEDPattern Blink(units::second_t onTime); + LEDPattern Blink(wpi::units::second_t onTime); /** * Creates a pattern that blinks this one on and off in sync with a true/false @@ -194,11 +194,11 @@ class LEDPattern { * @return the breathing pattern */ [[nodiscard]] - LEDPattern Breathe(units::second_t period); + LEDPattern Breathe(wpi::units::second_t period); /** * Creates a pattern that plays this pattern overlaid on another. Anywhere - * this pattern sets an LED to off (or {@link frc::Color::kBlack}), the base + * this pattern sets an LED to off (or {@link wpi::Color::kBlack}), the base * pattern will be displayed instead. * * @param base the base pattern to overlay on top of @@ -255,10 +255,10 @@ class LEDPattern { * *
    *   // Solid red, but at 50% brightness
-   *   frc::LEDPattern::Solid(frc::Color::kRed).AtBrightness(0.5);
+   *   wpi::LEDPattern::Solid(wpi::Color::kRed).AtBrightness(0.5);
    *
    *   // Solid white, but at only 10% (i.e. ~0.5V)
-   *   frc::LEDPattern::Solid(frc:Color::kWhite).AtBrightness(0.1);
+   *   wpi::LEDPattern::Solid(frc:Color::kWhite).AtBrightness(0.1);
    * 
* * @param relativeBrightness the multiplier to apply to all channels to modify @@ -294,10 +294,10 @@ class LEDPattern { * travel. * *
-   * frc::LEDPattern basePattern =
-   *   frc::LEDPattern::Gradient(frc::Color::kRed, frc::Color::kBlue);
-   * frc::LEDPattern progressPattern =
-   *   basePattern.Mask(frc::LEDPattern::ProgressMaskLayer([&]() {
+   * wpi::LEDPattern basePattern =
+   *   wpi::LEDPattern::Gradient(wpi::Color::kRed, wpi::Color::kBlue);
+   * wpi::LEDPattern progressPattern =
+   *   basePattern.Mask(wpi::LEDPattern::ProgressMaskLayer([&]() {
    *     return elevator.GetHeight() / elevator.MaxHeight();
    *   });
    * 
@@ -396,8 +396,8 @@ class LEDPattern { static LEDPattern Rainbow(int saturation, int value); private: - std::function)> + std::function)> m_impl; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/hardware/motor/MotorController.hpp b/wpilibc/src/main/native/include/wpi/hardware/motor/MotorController.hpp index bae338ef9f..4bd1ed9097 100644 --- a/wpilibc/src/main/native/include/wpi/hardware/motor/MotorController.hpp +++ b/wpilibc/src/main/native/include/wpi/hardware/motor/MotorController.hpp @@ -6,7 +6,7 @@ #include "wpi/units/voltage.hpp" -namespace frc { +namespace wpi { /** * Interface for motor controlling devices. @@ -34,7 +34,7 @@ class MotorController { * * @param output The voltage to output. */ - virtual void SetVoltage(units::volt_t output); + virtual void SetVoltage(wpi::units::volt_t output); /** * Common interface for getting the current set speed of a motor controller. @@ -68,4 +68,4 @@ class MotorController { virtual void StopMotor() = 0; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/hardware/motor/MotorControllerGroup.hpp b/wpilibc/src/main/native/include/wpi/hardware/motor/MotorControllerGroup.hpp index 4118ff332e..ca53987181 100644 --- a/wpilibc/src/main/native/include/wpi/hardware/motor/MotorControllerGroup.hpp +++ b/wpilibc/src/main/native/include/wpi/hardware/motor/MotorControllerGroup.hpp @@ -14,7 +14,7 @@ WPI_IGNORE_DEPRECATED -namespace frc { +namespace wpi { /** * Allows multiple MotorController objects to be linked together. @@ -22,9 +22,9 @@ namespace frc { class [[deprecated( "Use PWMMotorController::AddFollower() or if using CAN motor controllers," "use their method of following.")]] MotorControllerGroup - : public wpi::Sendable, + : public wpi::util::Sendable, public MotorController, - public wpi::SendableHelper { + public wpi::util::SendableHelper { public: /** * Create a new MotorControllerGroup with the provided MotorControllers. @@ -53,14 +53,14 @@ class [[deprecated( MotorControllerGroup& operator=(MotorControllerGroup&&) = default; void Set(double speed) override; - void SetVoltage(units::volt_t output) override; + void SetVoltage(wpi::units::volt_t output) override; double Get() const override; void SetInverted(bool isInverted) override; bool GetInverted() const override; void Disable() override; void StopMotor() override; - void InitSendable(wpi::SendableBuilder& builder) override; + void InitSendable(wpi::util::SendableBuilder& builder) override; private: bool m_isInverted = false; @@ -69,6 +69,6 @@ class [[deprecated( void Initialize(); }; -} // namespace frc +} // namespace wpi WPI_UNIGNORE_DEPRECATED diff --git a/wpilibc/src/main/native/include/wpi/hardware/motor/MotorSafety.hpp b/wpilibc/src/main/native/include/wpi/hardware/motor/MotorSafety.hpp index 0a7278c7e3..78f981ce7a 100644 --- a/wpilibc/src/main/native/include/wpi/hardware/motor/MotorSafety.hpp +++ b/wpilibc/src/main/native/include/wpi/hardware/motor/MotorSafety.hpp @@ -10,7 +10,7 @@ #include "wpi/units/time.hpp" #include "wpi/util/mutex.hpp" -namespace frc { +namespace wpi { /** * The Motor Safety feature acts as a watchdog timer for an individual motor. It @@ -41,14 +41,14 @@ class MotorSafety { * * @param expirationTime The timeout value. */ - void SetExpiration(units::second_t expirationTime); + void SetExpiration(wpi::units::second_t expirationTime); /** * Retrieve the timeout value for the corresponding motor safety object. * * @return the timeout value. */ - units::second_t GetExpiration() const; + wpi::units::second_t GetExpiration() const; /** * Determine if the motor is still operating or has timed out. @@ -108,15 +108,15 @@ class MotorSafety { static constexpr auto kDefaultSafetyExpiration = 100_ms; // The expiration time for this object - units::second_t m_expiration = kDefaultSafetyExpiration; + wpi::units::second_t m_expiration = kDefaultSafetyExpiration; // True if motor safety is enabled for this motor bool m_enabled = false; // The FPGA clock value when the motor has expired - units::second_t m_stopTime = Timer::GetFPGATimestamp(); + wpi::units::second_t m_stopTime = Timer::GetFPGATimestamp(); - mutable wpi::mutex m_thisMutex; + mutable wpi::util::mutex m_thisMutex; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/hardware/motor/PWMMotorController.hpp b/wpilibc/src/main/native/include/wpi/hardware/motor/PWMMotorController.hpp index c4182bad2e..6f8eeac7cf 100644 --- a/wpilibc/src/main/native/include/wpi/hardware/motor/PWMMotorController.hpp +++ b/wpilibc/src/main/native/include/wpi/hardware/motor/PWMMotorController.hpp @@ -21,7 +21,7 @@ #include "wpi/util/sendable/Sendable.hpp" #include "wpi/util/sendable/SendableHelper.hpp" -namespace frc { +namespace wpi { WPI_IGNORE_DEPRECATED @@ -30,8 +30,8 @@ WPI_IGNORE_DEPRECATED */ class PWMMotorController : public MotorController, public MotorSafety, - public wpi::Sendable, - public wpi::SendableHelper { + public wpi::util::Sendable, + public wpi::util::SendableHelper { public: PWMMotorController(PWMMotorController&&) = default; PWMMotorController& operator=(PWMMotorController&&) = default; @@ -58,7 +58,7 @@ class PWMMotorController : public MotorController, * * @param output The voltage to output. */ - void SetVoltage(units::volt_t output) override; + void SetVoltage(wpi::units::volt_t output) override; /** * Get the recently set value of the PWM. This value is affected by the @@ -76,7 +76,7 @@ class PWMMotorController : public MotorController, * @return The voltage of the motor controller, nominally between -12 V and 12 * V. */ - virtual units::volt_t GetVoltage() const; + virtual wpi::units::volt_t GetVoltage() const; void SetInverted(bool isInverted) override; @@ -128,7 +128,7 @@ class PWMMotorController : public MotorController, */ PWMMotorController(std::string_view name, int channel); - void InitSendable(wpi::SendableBuilder& builder) override; + void InitSendable(wpi::util::SendableBuilder& builder) override; /// PWM instances for motor controller. PWM m_pwm; @@ -136,35 +136,35 @@ class PWMMotorController : public MotorController, void SetSpeed(double speed); double GetSpeed() const; - void SetBounds(units::microsecond_t maxPwm, - units::microsecond_t deadbandMaxPwm, - units::microsecond_t centerPwm, - units::microsecond_t deadbandMinPwm, - units::microsecond_t minPwm); + void SetBounds(wpi::units::microsecond_t maxPwm, + wpi::units::microsecond_t deadbandMaxPwm, + wpi::units::microsecond_t centerPwm, + wpi::units::microsecond_t deadbandMinPwm, + wpi::units::microsecond_t minPwm); private: bool m_isInverted = false; std::vector m_nonowningFollowers; std::vector> m_owningFollowers; - hal::SimDevice m_simDevice; - hal::SimDouble m_simSpeed; + wpi::hal::SimDevice m_simDevice; + wpi::hal::SimDouble m_simSpeed; bool m_eliminateDeadband{0}; - units::microsecond_t m_minPwm{0}; - units::microsecond_t m_deadbandMinPwm{0}; - units::microsecond_t m_centerPwm{0}; - units::microsecond_t m_deadbandMaxPwm{0}; - units::microsecond_t m_maxPwm{0}; + wpi::units::microsecond_t m_minPwm{0}; + wpi::units::microsecond_t m_deadbandMinPwm{0}; + wpi::units::microsecond_t m_centerPwm{0}; + wpi::units::microsecond_t m_deadbandMaxPwm{0}; + wpi::units::microsecond_t m_maxPwm{0}; - units::microsecond_t GetMinPositivePwm() const; - units::microsecond_t GetMaxNegativePwm() const; - units::microsecond_t GetPositiveScaleFactor() const; - units::microsecond_t GetNegativeScaleFactor() const; + wpi::units::microsecond_t GetMinPositivePwm() const; + wpi::units::microsecond_t GetMaxNegativePwm() const; + wpi::units::microsecond_t GetPositiveScaleFactor() const; + wpi::units::microsecond_t GetNegativeScaleFactor() const; PWM* GetPwm() { return &m_pwm; } }; WPI_UNIGNORE_DEPRECATED -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/hardware/pneumatic/Compressor.hpp b/wpilibc/src/main/native/include/wpi/hardware/pneumatic/Compressor.hpp index f103df7bce..8a783313a8 100644 --- a/wpilibc/src/main/native/include/wpi/hardware/pneumatic/Compressor.hpp +++ b/wpilibc/src/main/native/include/wpi/hardware/pneumatic/Compressor.hpp @@ -14,7 +14,7 @@ #include "wpi/util/sendable/Sendable.hpp" #include "wpi/util/sendable/SendableHelper.hpp" -namespace frc { +namespace wpi { /** * Class for operating a compressor connected to a pneumatics module. @@ -30,8 +30,8 @@ namespace frc { * loop control. You can only turn off closed loop control, thereby stopping * the compressor from operating. */ -class Compressor : public wpi::Sendable, - public wpi::SendableHelper { +class Compressor : public wpi::util::Sendable, + public wpi::util::SendableHelper { public: /** * Constructs a compressor for a specified module and type. @@ -78,7 +78,7 @@ class Compressor : public wpi::Sendable, * * @return Current drawn by the compressor. */ - units::ampere_t GetCurrent() const; + wpi::units::ampere_t GetCurrent() const; /** * If supported by the device, returns the analog input voltage (on channel @@ -89,7 +89,7 @@ class Compressor : public wpi::Sendable, * * @return The analog input voltage, in volts. */ - units::volt_t GetAnalogVoltage() const; + wpi::units::volt_t GetAnalogVoltage() const; /** * If supported by the device, returns the pressure read by the analog @@ -100,7 +100,7 @@ class Compressor : public wpi::Sendable, * * @return The pressure read by the analog pressure sensor. */ - units::pounds_per_square_inch_t GetPressure() const; + wpi::units::pounds_per_square_inch_t GetPressure() const; /** * Disable the compressor. @@ -130,8 +130,8 @@ class Compressor : public wpi::Sendable, * @param maxPressure The maximum pressure. The compressor will turn off when * the pressure reaches this value. */ - void EnableAnalog(units::pounds_per_square_inch_t minPressure, - units::pounds_per_square_inch_t maxPressure); + void EnableAnalog(wpi::units::pounds_per_square_inch_t minPressure, + wpi::units::pounds_per_square_inch_t maxPressure); /** * If supported by the device, enables the compressor in hybrid mode. This @@ -162,8 +162,8 @@ class Compressor : public wpi::Sendable, * off when the pressure reaches this value or the pressure switch is * disconnected or indicates that the system is full. */ - void EnableHybrid(units::pounds_per_square_inch_t minPressure, - units::pounds_per_square_inch_t maxPressure); + void EnableHybrid(wpi::units::pounds_per_square_inch_t minPressure, + wpi::units::pounds_per_square_inch_t maxPressure); /** * Returns the active compressor configuration. @@ -172,11 +172,11 @@ class Compressor : public wpi::Sendable, */ CompressorConfigType GetConfigType() const; - void InitSendable(wpi::SendableBuilder& builder) override; + void InitSendable(wpi::util::SendableBuilder& builder) override; private: std::shared_ptr m_module; PneumaticsModuleType m_moduleType; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/hardware/pneumatic/CompressorConfigType.hpp b/wpilibc/src/main/native/include/wpi/hardware/pneumatic/CompressorConfigType.hpp index b9338042b6..29ff0b5cb2 100644 --- a/wpilibc/src/main/native/include/wpi/hardware/pneumatic/CompressorConfigType.hpp +++ b/wpilibc/src/main/native/include/wpi/hardware/pneumatic/CompressorConfigType.hpp @@ -4,7 +4,7 @@ #pragma once -namespace frc { +namespace wpi { /** * Compressor config type. */ @@ -19,4 +19,4 @@ enum class CompressorConfigType { Hybrid = 3 }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/hardware/pneumatic/DoubleSolenoid.hpp b/wpilibc/src/main/native/include/wpi/hardware/pneumatic/DoubleSolenoid.hpp index b0c25e2b46..3152dbb3c9 100644 --- a/wpilibc/src/main/native/include/wpi/hardware/pneumatic/DoubleSolenoid.hpp +++ b/wpilibc/src/main/native/include/wpi/hardware/pneumatic/DoubleSolenoid.hpp @@ -12,7 +12,7 @@ #include "wpi/util/sendable/Sendable.hpp" #include "wpi/util/sendable/SendableHelper.hpp" -namespace frc { +namespace wpi { /** * DoubleSolenoid class for running 2 channels of high voltage Digital Output @@ -21,8 +21,8 @@ namespace frc { * The DoubleSolenoid class is typically used for pneumatics solenoids that * have two positions controlled by two separate channels. */ -class DoubleSolenoid : public wpi::Sendable, - public wpi::SendableHelper { +class DoubleSolenoid : public wpi::util::Sendable, + public wpi::util::SendableHelper { public: /** * Possible values for a DoubleSolenoid. @@ -125,7 +125,7 @@ class DoubleSolenoid : public wpi::Sendable, */ bool IsRevSolenoidDisabled() const; - void InitSendable(wpi::SendableBuilder& builder) override; + void InitSendable(wpi::util::SendableBuilder& builder) override; private: std::shared_ptr m_module; @@ -136,4 +136,4 @@ class DoubleSolenoid : public wpi::Sendable, int m_mask; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/hardware/pneumatic/PneumaticHub.hpp b/wpilibc/src/main/native/include/wpi/hardware/pneumatic/PneumaticHub.hpp index ca66425911..67e9cbd054 100644 --- a/wpilibc/src/main/native/include/wpi/hardware/pneumatic/PneumaticHub.hpp +++ b/wpilibc/src/main/native/include/wpi/hardware/pneumatic/PneumaticHub.hpp @@ -12,7 +12,7 @@ #include "wpi/util/DenseMap.hpp" #include "wpi/util/mutex.hpp" -namespace frc { +namespace wpi { /** Module class for controlling a REV Robotics Pneumatic Hub. */ class PneumaticHub : public PneumaticsBase { public: @@ -57,8 +57,8 @@ class PneumaticHub : public PneumaticsBase { * minPressure. */ void EnableCompressorAnalog( - units::pounds_per_square_inch_t minPressure, - units::pounds_per_square_inch_t maxPressure) override; + wpi::units::pounds_per_square_inch_t minPressure, + wpi::units::pounds_per_square_inch_t maxPressure) override; /** * Enables the compressor in hybrid mode. This mode uses both a digital @@ -87,14 +87,14 @@ class PneumaticHub : public PneumaticsBase { * minPressure. */ void EnableCompressorHybrid( - units::pounds_per_square_inch_t minPressure, - units::pounds_per_square_inch_t maxPressure) override; + wpi::units::pounds_per_square_inch_t minPressure, + wpi::units::pounds_per_square_inch_t maxPressure) override; CompressorConfigType GetCompressorConfigType() const override; bool GetPressureSwitch() const override; - units::ampere_t GetCompressorCurrent() const override; + wpi::units::ampere_t GetCompressorCurrent() const override; void SetSolenoids(int mask, int values) override; @@ -106,7 +106,7 @@ class PneumaticHub : public PneumaticsBase { void FireOneShot(int index) override; - void SetOneShotDuration(int index, units::second_t duration) override; + void SetOneShotDuration(int index, wpi::units::second_t duration) override; bool CheckSolenoidChannel(int channel) const override; @@ -255,28 +255,28 @@ class PneumaticHub : public PneumaticsBase { * * @return The input voltage. */ - units::volt_t GetInputVoltage() const; + wpi::units::volt_t GetInputVoltage() const; /** * Returns the current voltage of the regulated 5v supply. * * @return The current voltage of the 5v supply. */ - units::volt_t Get5VRegulatedVoltage() const; + wpi::units::volt_t Get5VRegulatedVoltage() const; /** * Returns the total current drawn by all solenoids. * * @return Total current drawn by all solenoids. */ - units::ampere_t GetSolenoidsTotalCurrent() const; + wpi::units::ampere_t GetSolenoidsTotalCurrent() const; /** * Returns the current voltage of the solenoid power supply. * * @return The current voltage of the solenoid power supply. */ - units::volt_t GetSolenoidsVoltage() const; + wpi::units::volt_t GetSolenoidsVoltage() const; /** * Returns the raw voltage of the specified analog input channel. @@ -284,7 +284,7 @@ class PneumaticHub : public PneumaticsBase { * @param channel The analog input channel to read voltage from. * @return The voltage of the specified analog input channel. */ - units::volt_t GetAnalogVoltage(int channel) const override; + wpi::units::volt_t GetAnalogVoltage(int channel) const override; /** * Returns the pressure read by an analog pressure sensor on the specified @@ -294,7 +294,7 @@ class PneumaticHub : public PneumaticsBase { * @return The pressure read by an analog pressure sensor on the specified * analog input channel. */ - units::pounds_per_square_inch_t GetPressure(int channel) const override; + wpi::units::pounds_per_square_inch_t GetPressure(int channel) const override; private: class DataStore; @@ -308,9 +308,9 @@ class PneumaticHub : public PneumaticsBase { HAL_REVPHHandle m_handle; int m_module; - static wpi::mutex m_handleLock; - static std::unique_ptr>[]> + static wpi::util::mutex m_handleLock; + static std::unique_ptr>[]> m_handleMaps; static std::weak_ptr& GetDataStore(int busId, int module); }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/hardware/pneumatic/PneumaticsBase.hpp b/wpilibc/src/main/native/include/wpi/hardware/pneumatic/PneumaticsBase.hpp index b6c839e348..00a0e638f3 100644 --- a/wpilibc/src/main/native/include/wpi/hardware/pneumatic/PneumaticsBase.hpp +++ b/wpilibc/src/main/native/include/wpi/hardware/pneumatic/PneumaticsBase.hpp @@ -14,7 +14,7 @@ #include "wpi/units/time.hpp" #include "wpi/units/voltage.hpp" -namespace frc { +namespace wpi { class Solenoid; class DoubleSolenoid; class Compressor; @@ -46,7 +46,7 @@ class PneumaticsBase { * * @return The current drawn by the compressor. */ - virtual units::ampere_t GetCompressorCurrent() const = 0; + virtual wpi::units::ampere_t GetCompressorCurrent() const = 0; /** Disables the compressor. */ virtual void DisableCompressor() = 0; @@ -75,8 +75,8 @@ class PneumaticsBase { * off when the pressure reaches this value. */ virtual void EnableCompressorAnalog( - units::pounds_per_square_inch_t minPressure, - units::pounds_per_square_inch_t maxPressure) = 0; + wpi::units::pounds_per_square_inch_t minPressure, + wpi::units::pounds_per_square_inch_t maxPressure) = 0; /** * If supported by the device, enables the compressor in hybrid mode. This @@ -108,8 +108,8 @@ class PneumaticsBase { * disconnected or indicates that the system is full. */ virtual void EnableCompressorHybrid( - units::pounds_per_square_inch_t minPressure, - units::pounds_per_square_inch_t maxPressure) = 0; + wpi::units::pounds_per_square_inch_t minPressure, + wpi::units::pounds_per_square_inch_t maxPressure) = 0; /** * Returns the active compressor configuration. @@ -164,7 +164,7 @@ class PneumaticsBase { * @param index solenoid index * @param duration shot duration */ - virtual void SetOneShotDuration(int index, units::second_t duration) = 0; + virtual void SetOneShotDuration(int index, wpi::units::second_t duration) = 0; /** * Check if a solenoid channel is valid. @@ -215,7 +215,7 @@ class PneumaticsBase { * @param channel The analog input channel to read voltage from. * @return The voltage of the specified analog input channel. */ - virtual units::volt_t GetAnalogVoltage(int channel) const = 0; + virtual wpi::units::volt_t GetAnalogVoltage(int channel) const = 0; /** * If supported by the device, returns the pressure read by an analog @@ -228,7 +228,7 @@ class PneumaticsBase { * @return The pressure read by an analog pressure sensor on the * specified analog input channel. */ - virtual units::pounds_per_square_inch_t GetPressure(int channel) const = 0; + virtual wpi::units::pounds_per_square_inch_t GetPressure(int channel) const = 0; /** * Create a solenoid object for the specified channel. @@ -282,4 +282,4 @@ class PneumaticsBase { */ static int GetDefaultForType(PneumaticsModuleType moduleType); }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/hardware/pneumatic/PneumaticsControlModule.hpp b/wpilibc/src/main/native/include/wpi/hardware/pneumatic/PneumaticsControlModule.hpp index b940918834..c0285dd1de 100644 --- a/wpilibc/src/main/native/include/wpi/hardware/pneumatic/PneumaticsControlModule.hpp +++ b/wpilibc/src/main/native/include/wpi/hardware/pneumatic/PneumaticsControlModule.hpp @@ -11,7 +11,7 @@ #include "wpi/util/DenseMap.hpp" #include "wpi/util/mutex.hpp" -namespace frc { +namespace wpi { /** Module class for controlling a Cross The Road Electronics Pneumatics Control * Module. */ class PneumaticsControlModule : public PneumaticsBase { @@ -52,8 +52,8 @@ class PneumaticsControlModule : public PneumaticsBase { * @see EnableCompressorDigital() */ void EnableCompressorAnalog( - units::pounds_per_square_inch_t minPressure, - units::pounds_per_square_inch_t maxPressure) override; + wpi::units::pounds_per_square_inch_t minPressure, + wpi::units::pounds_per_square_inch_t maxPressure) override; /** * Enables the compressor in digital mode. Hybrid mode is unsupported by the @@ -64,14 +64,14 @@ class PneumaticsControlModule : public PneumaticsBase { * @see EnableCompressorDigital() */ void EnableCompressorHybrid( - units::pounds_per_square_inch_t minPressure, - units::pounds_per_square_inch_t maxPressure) override; + wpi::units::pounds_per_square_inch_t minPressure, + wpi::units::pounds_per_square_inch_t maxPressure) override; CompressorConfigType GetCompressorConfigType() const override; bool GetPressureSwitch() const override; - units::ampere_t GetCompressorCurrent() const override; + wpi::units::ampere_t GetCompressorCurrent() const override; /** * Return whether the compressor current is currently too high. @@ -161,7 +161,7 @@ class PneumaticsControlModule : public PneumaticsBase { void FireOneShot(int index) override; - void SetOneShotDuration(int index, units::second_t duration) override; + void SetOneShotDuration(int index, wpi::units::second_t duration) override; bool CheckSolenoidChannel(int channel) const override; @@ -179,7 +179,7 @@ class PneumaticsControlModule : public PneumaticsBase { * @param channel Unsupported. * @return 0 */ - units::volt_t GetAnalogVoltage(int channel) const override; + wpi::units::volt_t GetAnalogVoltage(int channel) const override; /** * Unsupported by the CTRE PCM. @@ -187,7 +187,7 @@ class PneumaticsControlModule : public PneumaticsBase { * @param channel Unsupported. * @return 0 */ - units::pounds_per_square_inch_t GetPressure(int channel) const override; + wpi::units::pounds_per_square_inch_t GetPressure(int channel) const override; Solenoid MakeSolenoid(int channel) override; DoubleSolenoid MakeDoubleSolenoid(int forwardChannel, @@ -208,9 +208,9 @@ class PneumaticsControlModule : public PneumaticsBase { HAL_CTREPCMHandle m_handle; int m_module; - static wpi::mutex m_handleLock; - static std::unique_ptr>[]> + static wpi::util::mutex m_handleLock; + static std::unique_ptr>[]> m_handleMaps; static std::weak_ptr& GetDataStore(int busId, int module); }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/hardware/pneumatic/PneumaticsModuleType.hpp b/wpilibc/src/main/native/include/wpi/hardware/pneumatic/PneumaticsModuleType.hpp index 4fb225a217..39b5e6cc97 100644 --- a/wpilibc/src/main/native/include/wpi/hardware/pneumatic/PneumaticsModuleType.hpp +++ b/wpilibc/src/main/native/include/wpi/hardware/pneumatic/PneumaticsModuleType.hpp @@ -4,7 +4,7 @@ #pragma once -namespace frc { +namespace wpi { /** * Pneumatics module type. */ @@ -14,4 +14,4 @@ enum class PneumaticsModuleType { /// REV PH. REVPH }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/hardware/pneumatic/Solenoid.hpp b/wpilibc/src/main/native/include/wpi/hardware/pneumatic/Solenoid.hpp index 8f641ff780..1dec147af9 100644 --- a/wpilibc/src/main/native/include/wpi/hardware/pneumatic/Solenoid.hpp +++ b/wpilibc/src/main/native/include/wpi/hardware/pneumatic/Solenoid.hpp @@ -13,7 +13,7 @@ #include "wpi/util/sendable/Sendable.hpp" #include "wpi/util/sendable/SendableHelper.hpp" -namespace frc { +namespace wpi { /** * Solenoid class for running high voltage Digital Output on a pneumatics @@ -22,7 +22,7 @@ namespace frc { * The Solenoid class is typically used for pneumatics solenoids, but could be * used for any device within the current spec of the module. */ -class Solenoid : public wpi::Sendable, public wpi::SendableHelper { +class Solenoid : public wpi::util::Sendable, public wpi::util::SendableHelper { public: /** * Constructs a solenoid for a specified module and type. @@ -100,7 +100,7 @@ class Solenoid : public wpi::Sendable, public wpi::SendableHelper { * * @see startPulse() */ - void SetPulseDuration(units::second_t duration); + void SetPulseDuration(wpi::units::second_t duration); /** * %Trigger the pneumatics module to generate a pulse of the duration set in @@ -110,7 +110,7 @@ class Solenoid : public wpi::Sendable, public wpi::SendableHelper { */ void StartPulse(); - void InitSendable(wpi::SendableBuilder& builder) override; + void InitSendable(wpi::util::SendableBuilder& builder) override; private: std::shared_ptr m_module; @@ -118,4 +118,4 @@ class Solenoid : public wpi::Sendable, public wpi::SendableHelper { int m_channel; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/hardware/power/PowerDistribution.hpp b/wpilibc/src/main/native/include/wpi/hardware/power/PowerDistribution.hpp index df86fd227e..f6f704860b 100644 --- a/wpilibc/src/main/native/include/wpi/hardware/power/PowerDistribution.hpp +++ b/wpilibc/src/main/native/include/wpi/hardware/power/PowerDistribution.hpp @@ -11,14 +11,14 @@ #include "wpi/util/sendable/Sendable.hpp" #include "wpi/util/sendable/SendableHelper.hpp" -namespace frc { +namespace wpi { /** * Class for getting voltage, current, temperature, power and energy from the * CTRE Power Distribution Panel (PDP) or REV Power Distribution Hub (PDH). */ -class PowerDistribution : public wpi::Sendable, - public wpi::SendableHelper { +class PowerDistribution : public wpi::util::Sendable, + public wpi::util::SendableHelper { public: /// Default module number. static constexpr int kDefaultModule = -1; @@ -343,11 +343,11 @@ class PowerDistribution : public wpi::Sendable, */ StickyFaults GetStickyFaults() const; - void InitSendable(wpi::SendableBuilder& builder) override; + void InitSendable(wpi::util::SendableBuilder& builder) override; private: - hal::Handle m_handle; + wpi::hal::Handle m_handle; int m_module; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/hardware/range/SharpIR.hpp b/wpilibc/src/main/native/include/wpi/hardware/range/SharpIR.hpp index db2610a467..972a048c36 100644 --- a/wpilibc/src/main/native/include/wpi/hardware/range/SharpIR.hpp +++ b/wpilibc/src/main/native/include/wpi/hardware/range/SharpIR.hpp @@ -10,9 +10,9 @@ #include "wpi/util/sendable/Sendable.hpp" #include "wpi/util/sendable/SendableHelper.hpp" -namespace frc { +namespace wpi { -class SharpIR : public wpi::Sendable, public wpi::SendableHelper { +class SharpIR : public wpi::util::Sendable, public wpi::util::SendableHelper { public: /** * Sharp GP2Y0A02YK0F is an analog IR sensor capable of measuring @@ -65,8 +65,8 @@ class SharpIR : public wpi::Sendable, public wpi::SendableHelper { * @param min Minimum distance to report * @param max Maximum distance to report */ - SharpIR(int channel, double a, double b, units::meter_t min, - units::meter_t max); + SharpIR(int channel, double a, double b, wpi::units::meter_t min, + wpi::units::meter_t max); /** * Get the analog input channel number. @@ -80,20 +80,20 @@ class SharpIR : public wpi::Sendable, public wpi::SendableHelper { * * @return range of the target returned by the sensor */ - units::meter_t GetRange() const; + wpi::units::meter_t GetRange() const; - void InitSendable(wpi::SendableBuilder& builder) override; + void InitSendable(wpi::util::SendableBuilder& builder) override; private: AnalogInput m_sensor; - hal::SimDevice m_simDevice; - hal::SimDouble m_simRange; + wpi::hal::SimDevice m_simDevice; + wpi::hal::SimDouble m_simRange; double m_A; double m_B; - units::meter_t m_min; - units::meter_t m_max; + wpi::units::meter_t m_min; + wpi::units::meter_t m_max; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/hardware/rotation/AnalogEncoder.hpp b/wpilibc/src/main/native/include/wpi/hardware/rotation/AnalogEncoder.hpp index 323f28323e..4ced3908d3 100644 --- a/wpilibc/src/main/native/include/wpi/hardware/rotation/AnalogEncoder.hpp +++ b/wpilibc/src/main/native/include/wpi/hardware/rotation/AnalogEncoder.hpp @@ -11,14 +11,14 @@ #include "wpi/util/sendable/Sendable.hpp" #include "wpi/util/sendable/SendableHelper.hpp" -namespace frc { +namespace wpi { class AnalogInput; /** * Class for supporting continuous analog encoders, such as the US Digital MA3. */ -class AnalogEncoder : public wpi::Sendable, - public wpi::SendableHelper { +class AnalogEncoder : public wpi::util::Sendable, + public wpi::util::SendableHelper { public: /** * Construct a new AnalogEncoder attached to a specific AnalogIn channel. @@ -131,7 +131,7 @@ class AnalogEncoder : public wpi::Sendable, */ int GetChannel() const; - void InitSendable(wpi::SendableBuilder& builder) override; + void InitSendable(wpi::util::SendableBuilder& builder) override; private: void Init(double fullRange, double expectedZero); @@ -144,7 +144,7 @@ class AnalogEncoder : public wpi::Sendable, double m_sensorMax{1.0}; bool m_isInverted{false}; - hal::SimDevice m_simDevice; - hal::SimDouble m_simPosition; + wpi::hal::SimDevice m_simDevice; + wpi::hal::SimDouble m_simPosition; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/hardware/rotation/AnalogPotentiometer.hpp b/wpilibc/src/main/native/include/wpi/hardware/rotation/AnalogPotentiometer.hpp index d42dd4baa8..5421f664d8 100644 --- a/wpilibc/src/main/native/include/wpi/hardware/rotation/AnalogPotentiometer.hpp +++ b/wpilibc/src/main/native/include/wpi/hardware/rotation/AnalogPotentiometer.hpp @@ -10,7 +10,7 @@ #include "wpi/util/sendable/Sendable.hpp" #include "wpi/util/sendable/SendableHelper.hpp" -namespace frc { +namespace wpi { /** * Class for reading analog potentiometers. Analog potentiometers read in an @@ -18,8 +18,8 @@ namespace frc { * units you choose, by way of the scaling and offset constants passed to the * constructor. */ -class AnalogPotentiometer : public wpi::Sendable, - public wpi::SendableHelper { +class AnalogPotentiometer : public wpi::util::Sendable, + public wpi::util::SendableHelper { public: /** * Construct an Analog Potentiometer object from a channel number. @@ -101,11 +101,11 @@ class AnalogPotentiometer : public wpi::Sendable, */ double Get() const; - void InitSendable(wpi::SendableBuilder& builder) override; + void InitSendable(wpi::util::SendableBuilder& builder) override; private: std::shared_ptr m_analog_input; double m_fullRange, m_offset; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/hardware/rotation/DutyCycle.hpp b/wpilibc/src/main/native/include/wpi/hardware/rotation/DutyCycle.hpp index 6191a3cccb..7707e45c40 100644 --- a/wpilibc/src/main/native/include/wpi/hardware/rotation/DutyCycle.hpp +++ b/wpilibc/src/main/native/include/wpi/hardware/rotation/DutyCycle.hpp @@ -13,7 +13,7 @@ #include "wpi/util/sendable/Sendable.hpp" #include "wpi/util/sendable/SendableHelper.hpp" -namespace frc { +namespace wpi { /** * Class to read a duty cycle PWM input. * @@ -21,7 +21,7 @@ namespace frc { * low in that frequency. These can be attached to any SmartIO. * */ -class DutyCycle : public wpi::Sendable, public wpi::SendableHelper { +class DutyCycle : public wpi::util::Sendable, public wpi::util::SendableHelper { public: /** * Constructs a DutyCycle input from a smartio channel. @@ -43,7 +43,7 @@ class DutyCycle : public wpi::Sendable, public wpi::SendableHelper { * * @return frequency */ - units::hertz_t GetFrequency() const; + wpi::units::hertz_t GetFrequency() const; /** * Get the output ratio of the duty cycle signal. @@ -59,7 +59,7 @@ class DutyCycle : public wpi::Sendable, public wpi::SendableHelper { * * @return high time of last pulse */ - units::second_t GetHighTime() const; + wpi::units::second_t GetHighTime() const; /** * Get the channel of the source. @@ -69,11 +69,11 @@ class DutyCycle : public wpi::Sendable, public wpi::SendableHelper { int GetSourceChannel() const; protected: - void InitSendable(wpi::SendableBuilder& builder) override; + void InitSendable(wpi::util::SendableBuilder& builder) override; private: void InitDutyCycle(); int m_channel; - hal::Handle m_handle; + wpi::hal::Handle m_handle; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/hardware/rotation/DutyCycleEncoder.hpp b/wpilibc/src/main/native/include/wpi/hardware/rotation/DutyCycleEncoder.hpp index 9b99273f3a..2a23f86411 100644 --- a/wpilibc/src/main/native/include/wpi/hardware/rotation/DutyCycleEncoder.hpp +++ b/wpilibc/src/main/native/include/wpi/hardware/rotation/DutyCycleEncoder.hpp @@ -13,7 +13,7 @@ #include "wpi/util/sendable/Sendable.hpp" #include "wpi/util/sendable/SendableHelper.hpp" -namespace frc { +namespace wpi { class DutyCycle; /** @@ -21,8 +21,8 @@ class DutyCycle; * PWM Output, the CTRE Mag Encoder, the Rev Hex Encoder, and the AM Mag * Encoder. */ -class DutyCycleEncoder : public wpi::Sendable, - public wpi::SendableHelper { +class DutyCycleEncoder : public wpi::util::Sendable, + public wpi::util::SendableHelper { public: /** * Construct a new DutyCycleEncoder on a specific channel. @@ -107,7 +107,7 @@ class DutyCycleEncoder : public wpi::Sendable, * * @return duty cycle frequency */ - units::hertz_t GetFrequency() const; + wpi::units::hertz_t GetFrequency() const; /** * Get if the sensor is connected @@ -126,7 +126,7 @@ class DutyCycleEncoder : public wpi::Sendable, * * @param frequency the minimum frequency. */ - void SetConnectedFrequencyThreshold(units::hertz_t frequency); + void SetConnectedFrequencyThreshold(wpi::units::hertz_t frequency); /** * Get the encoder value. @@ -161,7 +161,7 @@ class DutyCycleEncoder : public wpi::Sendable, * * @param frequency the assumed frequency of the sensor */ - void SetAssumedFrequency(units::hertz_t frequency); + void SetAssumedFrequency(wpi::units::hertz_t frequency); /** * Set if this encoder is inverted. @@ -177,23 +177,23 @@ class DutyCycleEncoder : public wpi::Sendable, */ int GetSourceChannel() const; - void InitSendable(wpi::SendableBuilder& builder) override; + void InitSendable(wpi::util::SendableBuilder& builder) override; private: void Init(double fullRange, double expectedZero); double MapSensorRange(double pos) const; std::shared_ptr m_dutyCycle; - units::hertz_t m_frequencyThreshold = {100_Hz}; + wpi::units::hertz_t m_frequencyThreshold = {100_Hz}; double m_fullRange; double m_expectedZero; - units::second_t m_period{0_s}; + wpi::units::second_t m_period{0_s}; double m_sensorMin{0.0}; double m_sensorMax{1.0}; bool m_isInverted{false}; - hal::SimDevice m_simDevice; - hal::SimDouble m_simPosition; - hal::SimBoolean m_simIsConnected; + wpi::hal::SimDevice m_simDevice; + wpi::hal::SimDouble m_simPosition; + wpi::hal::SimBoolean m_simIsConnected; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/hardware/rotation/Encoder.hpp b/wpilibc/src/main/native/include/wpi/hardware/rotation/Encoder.hpp index a8a7516636..27f91cdf52 100644 --- a/wpilibc/src/main/native/include/wpi/hardware/rotation/Encoder.hpp +++ b/wpilibc/src/main/native/include/wpi/hardware/rotation/Encoder.hpp @@ -12,7 +12,7 @@ #include "wpi/util/sendable/Sendable.hpp" #include "wpi/util/sendable/SendableHelper.hpp" -namespace frc { +namespace wpi { /** * Class to read quad encoders. * @@ -29,8 +29,8 @@ namespace frc { * to be zeroed before use. */ class Encoder : public CounterBase, - public wpi::Sendable, - public wpi::SendableHelper { + public wpi::util::Sendable, + public wpi::util::SendableHelper { public: /** * Encoder constructor. @@ -95,7 +95,7 @@ class Encoder : public CounterBase, * @deprecated Use getRate() in favor of this method. */ [[deprecated("Use GetRate() in favor of this method")]] - units::second_t GetPeriod() const override; + wpi::units::second_t GetPeriod() const override; /** * Sets the maximum period for stopped detection. @@ -115,7 +115,7 @@ class Encoder : public CounterBase, [[deprecated( "Use SetMinRate() in favor of this method. This takes unscaled periods " "and SetMinRate() scales using value from SetDistancePerPulse().")]] - void SetMaxPeriod(units::second_t maxPeriod) override; + void SetMaxPeriod(wpi::units::second_t maxPeriod) override; /** * Determine if the encoder is stopped. @@ -246,7 +246,7 @@ class Encoder : public CounterBase, int GetFPGAIndex() const; - void InitSendable(wpi::SendableBuilder& builder) override; + void InitSendable(wpi::util::SendableBuilder& builder) override; private: /** @@ -276,7 +276,7 @@ class Encoder : public CounterBase, */ double DecodingScaleFactor() const; - hal::Handle m_encoder; + wpi::hal::Handle m_encoder; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/internal/DriverStationModeThread.hpp b/wpilibc/src/main/native/include/wpi/internal/DriverStationModeThread.hpp index e646e15b66..1df5c707b9 100644 --- a/wpilibc/src/main/native/include/wpi/internal/DriverStationModeThread.hpp +++ b/wpilibc/src/main/native/include/wpi/internal/DriverStationModeThread.hpp @@ -7,7 +7,7 @@ #include #include -namespace frc::internal { +namespace wpi::internal { /** * For internal use only. */ @@ -70,4 +70,4 @@ class DriverStationModeThread { bool m_userInTeleop{false}; bool m_userInTest{false}; }; -} // namespace frc::internal +} // namespace wpi::internal diff --git a/wpilibc/src/main/native/include/wpi/opmode/IterativeRobotBase.hpp b/wpilibc/src/main/native/include/wpi/opmode/IterativeRobotBase.hpp index 0d3618a0f4..ab0fccc86b 100644 --- a/wpilibc/src/main/native/include/wpi/opmode/IterativeRobotBase.hpp +++ b/wpilibc/src/main/native/include/wpi/opmode/IterativeRobotBase.hpp @@ -8,7 +8,7 @@ #include "wpi/system/Watchdog.hpp" #include "wpi/units/time.hpp" -namespace frc { +namespace wpi { /** * IterativeRobotBase implements a specific type of robot program framework, @@ -200,7 +200,7 @@ class IterativeRobotBase : public RobotBase { /** * Gets time period between calls to Periodic() functions. */ - units::second_t GetPeriod() const; + wpi::units::second_t GetPeriod() const; /** * Prints list of epochs added so far and their times. @@ -212,7 +212,7 @@ class IterativeRobotBase : public RobotBase { * * @param period Period. */ - explicit IterativeRobotBase(units::second_t period); + explicit IterativeRobotBase(wpi::units::second_t period); ~IterativeRobotBase() override = default; @@ -229,7 +229,7 @@ class IterativeRobotBase : public RobotBase { enum class Mode { kNone, kDisabled, kAutonomous, kTeleop, kTest }; Mode m_lastMode = Mode::kNone; - units::second_t m_period; + wpi::units::second_t m_period; Watchdog m_watchdog; bool m_ntFlushEnabled = true; bool m_calledDsConnected = false; @@ -237,4 +237,4 @@ class IterativeRobotBase : public RobotBase { void PrintLoopOverrunMessage(); }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/opmode/RobotBase.hpp b/wpilibc/src/main/native/include/wpi/opmode/RobotBase.hpp index cb83c551ce..2068118bf1 100644 --- a/wpilibc/src/main/native/include/wpi/opmode/RobotBase.hpp +++ b/wpilibc/src/main/native/include/wpi/opmode/RobotBase.hpp @@ -18,7 +18,7 @@ #include "wpi/util/mutex.hpp" #include "wpi/util/string.h" -namespace frc { +namespace wpi { int RunHALInitialization(); @@ -28,7 +28,7 @@ void ResetMotorSafety(); #endif template -void RunRobot(wpi::mutex& m, Robot** robot) { +void RunRobot(wpi::util::mutex& m, Robot** robot) { try { static Robot theRobot; { @@ -36,7 +36,7 @@ void RunRobot(wpi::mutex& m, Robot** robot) { *robot = &theRobot; } theRobot.StartCompetition(); - } catch (const frc::RuntimeError& e) { + } catch (const wpi::RuntimeError& e) { e.Report(); FRC_ReportError( err::Error, @@ -75,8 +75,8 @@ int StartRobot() { return halInit; } - static wpi::mutex m; - static wpi::condition_variable cv; + static wpi::util::mutex m; + static wpi::util::condition_variable cv; static Robot* robot = nullptr; static bool exited = false; @@ -124,7 +124,7 @@ int StartRobot() { } #ifndef __FRC_SYSTEMCORE__ - frc::impl::ResetMotorSafety(); + wpi::impl::ResetMotorSafety(); #endif HAL_Shutdown(); @@ -277,4 +277,4 @@ class RobotBase { NT_Listener connListenerHandle; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/opmode/RobotState.hpp b/wpilibc/src/main/native/include/wpi/opmode/RobotState.hpp index ec8700e34a..a3d4669222 100644 --- a/wpilibc/src/main/native/include/wpi/opmode/RobotState.hpp +++ b/wpilibc/src/main/native/include/wpi/opmode/RobotState.hpp @@ -4,7 +4,7 @@ #pragma once -namespace frc { +namespace wpi { /** * Robot state utility functions. @@ -56,4 +56,4 @@ class RobotState { static bool IsTest(); }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/opmode/TimedRobot.hpp b/wpilibc/src/main/native/include/wpi/opmode/TimedRobot.hpp index cb652320ef..b3e570ed36 100644 --- a/wpilibc/src/main/native/include/wpi/opmode/TimedRobot.hpp +++ b/wpilibc/src/main/native/include/wpi/opmode/TimedRobot.hpp @@ -18,7 +18,7 @@ #include "wpi/units/time.hpp" #include "wpi/util/priority_queue.hpp" -namespace frc { +namespace wpi { /** * TimedRobot implements the IterativeRobotBase robot program framework. @@ -49,14 +49,14 @@ class TimedRobot : public IterativeRobotBase { * * @param period The period of the robot loop function. */ - explicit TimedRobot(units::second_t period = kDefaultPeriod); + explicit TimedRobot(wpi::units::second_t period = kDefaultPeriod); /** * Constructor for TimedRobot. * * @param frequency The frequency of the robot loop function. */ - explicit TimedRobot(units::hertz_t frequency); + explicit TimedRobot(wpi::units::hertz_t frequency); TimedRobot(TimedRobot&&) = default; TimedRobot& operator=(TimedRobot&&) = default; @@ -86,8 +86,8 @@ class TimedRobot : public IterativeRobotBase { * for scheduling a callback in a different timeslot relative * to TimedRobot. */ - void AddPeriodic(std::function callback, units::second_t period, - units::second_t offset = 0_s); + void AddPeriodic(std::function callback, wpi::units::second_t period, + wpi::units::second_t offset = 0_s); private: class Callback { @@ -110,7 +110,7 @@ class TimedRobot : public IterativeRobotBase { period{period}, expirationTime( startTime + offset + period + - (std::chrono::microseconds{frc::RobotController::GetFPGATime()} - + (std::chrono::microseconds{wpi::RobotController::GetFPGATime()} - startTime) / period * period) {} @@ -119,12 +119,12 @@ class TimedRobot : public IterativeRobotBase { } }; - hal::Handle m_notifier; + wpi::hal::Handle m_notifier; std::chrono::microseconds m_startTime; uint64_t m_loopStartTimeUs = 0; - wpi::priority_queue, std::greater> + wpi::util::priority_queue, std::greater> m_callbacks; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/opmode/TimesliceRobot.hpp b/wpilibc/src/main/native/include/wpi/opmode/TimesliceRobot.hpp index 6488dd3cd5..3147dffc8d 100644 --- a/wpilibc/src/main/native/include/wpi/opmode/TimesliceRobot.hpp +++ b/wpilibc/src/main/native/include/wpi/opmode/TimesliceRobot.hpp @@ -9,7 +9,7 @@ #include "wpi/opmode/TimedRobot.hpp" #include "wpi/units/time.hpp" -namespace frc { +namespace wpi { /** * TimesliceRobot extends the TimedRobot robot program framework to provide @@ -75,7 +75,7 @@ namespace frc { * If the robot periodic functions and the controller periodic functions have a * lot of scheduling jitter that cause them to occasionally overlap with later * timeslices, consider giving the main robot thread a real-time priority using - * frc::SetCurrentThreadPriority(). An RT priority of 15 is a reasonable choice. + * wpi::SetCurrentThreadPriority(). An RT priority of 15 is a reasonable choice. * * If you do enable RT though, make sure your periodic functions do not * block. If they do, the operating system will lock up, and you'll have to @@ -92,8 +92,8 @@ class TimesliceRobot : public TimedRobot { * allocations should be less than or equal to this * value. */ - explicit TimesliceRobot(units::second_t robotPeriodicAllocation, - units::second_t controllerPeriod); + explicit TimesliceRobot(wpi::units::second_t robotPeriodicAllocation, + wpi::units::second_t controllerPeriod); /** * Schedule a periodic function with the constructor's controller period and @@ -109,11 +109,11 @@ class TimesliceRobot : public TimedRobot { * @param allocation The function's runtime allocation out of the controller * period. */ - void Schedule(std::function func, units::second_t allocation); + void Schedule(std::function func, wpi::units::second_t allocation); private: - units::second_t m_nextOffset; - units::second_t m_controllerPeriod; + wpi::units::second_t m_nextOffset; + wpi::units::second_t m_controllerPeriod; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/simulation/ADXL345Sim.hpp b/wpilibc/src/main/native/include/wpi/simulation/ADXL345Sim.hpp index 6fd529a2f3..1a6f8beb0d 100644 --- a/wpilibc/src/main/native/include/wpi/simulation/ADXL345Sim.hpp +++ b/wpilibc/src/main/native/include/wpi/simulation/ADXL345Sim.hpp @@ -6,7 +6,7 @@ #include "wpi/hal/SimDevice.h" -namespace frc { +namespace wpi { class ADXL345_I2C; @@ -46,10 +46,10 @@ class ADXL345Sim { void SetZ(double accel); private: - hal::SimDouble m_simX; - hal::SimDouble m_simY; - hal::SimDouble m_simZ; + wpi::hal::SimDouble m_simX; + wpi::hal::SimDouble m_simY; + wpi::hal::SimDouble m_simZ; }; } // namespace sim -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/simulation/AddressableLEDSim.hpp b/wpilibc/src/main/native/include/wpi/simulation/AddressableLEDSim.hpp index 320e93d0c3..18962ec89c 100644 --- a/wpilibc/src/main/native/include/wpi/simulation/AddressableLEDSim.hpp +++ b/wpilibc/src/main/native/include/wpi/simulation/AddressableLEDSim.hpp @@ -10,7 +10,7 @@ struct HAL_AddressableLEDData; -namespace frc { +namespace wpi { class AddressableLED; @@ -165,4 +165,4 @@ class AddressableLEDSim { int m_channel; }; } // namespace sim -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/simulation/AnalogEncoderSim.hpp b/wpilibc/src/main/native/include/wpi/simulation/AnalogEncoderSim.hpp index 199f1fb865..96565d6772 100644 --- a/wpilibc/src/main/native/include/wpi/simulation/AnalogEncoderSim.hpp +++ b/wpilibc/src/main/native/include/wpi/simulation/AnalogEncoderSim.hpp @@ -8,7 +8,7 @@ #include "wpi/math/geometry/Rotation2d.hpp" #include "wpi/units/angle.hpp" -namespace frc { +namespace wpi { class AnalogEncoder; @@ -39,7 +39,7 @@ class AnalogEncoderSim { double Get(); private: - hal::SimDouble m_positionSim; + wpi::hal::SimDouble m_positionSim; }; } // namespace sim -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/simulation/AnalogInputSim.hpp b/wpilibc/src/main/native/include/wpi/simulation/AnalogInputSim.hpp index 50af588306..b35d13bf55 100644 --- a/wpilibc/src/main/native/include/wpi/simulation/AnalogInputSim.hpp +++ b/wpilibc/src/main/native/include/wpi/simulation/AnalogInputSim.hpp @@ -8,7 +8,7 @@ #include "wpi/simulation/CallbackStore.hpp" -namespace frc { +namespace wpi { class AnalogInput; @@ -146,4 +146,4 @@ class AnalogInputSim { int m_index; }; } // namespace sim -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/simulation/BatterySim.hpp b/wpilibc/src/main/native/include/wpi/simulation/BatterySim.hpp index 62c6722b54..8341d9c34d 100644 --- a/wpilibc/src/main/native/include/wpi/simulation/BatterySim.hpp +++ b/wpilibc/src/main/native/include/wpi/simulation/BatterySim.hpp @@ -12,7 +12,7 @@ #include "wpi/units/impedance.hpp" #include "wpi/units/voltage.hpp" -namespace frc::sim { +namespace wpi::sim { /** * A utility class to simulate the robot battery. @@ -31,9 +31,9 @@ class BatterySim { * @param currents The currents drawn from the battery. * @return The battery's voltage under load. */ - static units::volt_t Calculate(units::volt_t nominalVoltage, - units::ohm_t resistance, - std::span currents) { + static wpi::units::volt_t Calculate(wpi::units::volt_t nominalVoltage, + wpi::units::ohm_t resistance, + std::span currents) { return std::max(0_V, nominalVoltage - std::accumulate(currents.begin(), currents.end(), 0_A) * resistance); @@ -51,9 +51,9 @@ class BatterySim { * @param currents The currents drawn from the battery. * @return The battery's voltage under load. */ - static units::volt_t Calculate( - units::volt_t nominalVoltage, units::ohm_t resistance, - std::initializer_list currents) { + static wpi::units::volt_t Calculate( + wpi::units::volt_t nominalVoltage, wpi::units::ohm_t resistance, + std::initializer_list currents) { return std::max(0_V, nominalVoltage - std::accumulate(currents.begin(), currents.end(), 0_A) * resistance); @@ -69,7 +69,7 @@ class BatterySim { * @param currents The currents drawn from the battery. * @return The battery's voltage under load. */ - static units::volt_t Calculate(std::span currents) { + static wpi::units::volt_t Calculate(std::span currents) { return Calculate(12_V, 0.02_Ohm, currents); } @@ -83,10 +83,10 @@ class BatterySim { * @param currents The currents drawn from the battery. * @return The battery's voltage under load. */ - static units::volt_t Calculate( - std::initializer_list currents) { + static wpi::units::volt_t Calculate( + std::initializer_list currents) { return Calculate(12_V, 0.02_Ohm, currents); } }; -} // namespace frc::sim +} // namespace wpi::sim diff --git a/wpilibc/src/main/native/include/wpi/simulation/CTREPCMSim.hpp b/wpilibc/src/main/native/include/wpi/simulation/CTREPCMSim.hpp index 0eceb19d82..d450d9d155 100644 --- a/wpilibc/src/main/native/include/wpi/simulation/CTREPCMSim.hpp +++ b/wpilibc/src/main/native/include/wpi/simulation/CTREPCMSim.hpp @@ -10,7 +10,7 @@ #include "wpi/simulation/CallbackStore.hpp" #include "wpi/simulation/PneumaticsBaseSim.hpp" -namespace frc::sim { +namespace wpi::sim { /** * Class to control a simulated Pneumatic Control Module (PCM). @@ -140,4 +140,4 @@ class CTREPCMSim : public PneumaticsBaseSim { void ResetData() override; }; -} // namespace frc::sim +} // namespace wpi::sim diff --git a/wpilibc/src/main/native/include/wpi/simulation/CallbackStore.hpp b/wpilibc/src/main/native/include/wpi/simulation/CallbackStore.hpp index 1b572ad7b6..1639c36a17 100644 --- a/wpilibc/src/main/native/include/wpi/simulation/CallbackStore.hpp +++ b/wpilibc/src/main/native/include/wpi/simulation/CallbackStore.hpp @@ -9,7 +9,7 @@ #include "wpi/hal/Value.h" -namespace frc::sim { +namespace wpi::sim { using NotifyCallback = std::function; using ConstBufferCallback = std::function { * Creates a simulated DC motor mechanism. * * @param plant The linear system representing the DC motor. This - * system can be created with LinearSystemId::DCMotorSystem(). If - * LinearSystemId::DCMotorSystem(kV, kA) is used, the distance unit must be + * system can be created with wpi::math::LinearSystemId::DCMotorSystem(). If + * wpi::math::LinearSystemId::DCMotorSystem(kV, kA) is used, the distance unit must be * radians. * @param gearbox The type of and number of motors in the DC motor * gearbox. * @param measurementStdDevs The standard deviation of the measurement noise. */ - DCMotorSim(const LinearSystem<2, 1, 2>& plant, const DCMotor& gearbox, + DCMotorSim(const wpi::math::LinearSystem<2, 1, 2>& plant, const wpi::math::DCMotor& gearbox, const std::array& measurementStdDevs = {0.0, 0.0}); using LinearSystemSim::SetState; @@ -41,76 +41,76 @@ class DCMotorSim : public LinearSystemSim<2, 1, 2> { * @param angularPosition The new position * @param angularVelocity The new velocity */ - void SetState(units::radian_t angularPosition, - units::radians_per_second_t angularVelocity); + void SetState(wpi::units::radian_t angularPosition, + wpi::units::radians_per_second_t angularVelocity); /** * Sets the DC motor's angular position. * * @param angularPosition The new position in radians. */ - void SetAngle(units::radian_t angularPosition); + void SetAngle(wpi::units::radian_t angularPosition); /** * Sets the DC motor's angular velocity. * * @param angularVelocity The new velocity in radians per second. */ - void SetAngularVelocity(units::radians_per_second_t angularVelocity); + void SetAngularVelocity(wpi::units::radians_per_second_t angularVelocity); /** * Returns the DC motor position. * * @return The DC motor position. */ - units::radian_t GetAngularPosition() const; + wpi::units::radian_t GetAngularPosition() const; /** * Returns the DC motor velocity. * * @return The DC motor velocity. */ - units::radians_per_second_t GetAngularVelocity() const; + wpi::units::radians_per_second_t GetAngularVelocity() const; /** * Returns the DC motor acceleration. * * @return The DC motor acceleration */ - units::radians_per_second_squared_t GetAngularAcceleration() const; + wpi::units::radians_per_second_squared_t GetAngularAcceleration() const; /** * Returns the DC motor torque. * * @return The DC motor torque */ - units::newton_meter_t GetTorque() const; + wpi::units::newton_meter_t GetTorque() const; /** * Returns the DC motor current draw. * * @return The DC motor current draw. */ - units::ampere_t GetCurrentDraw() const; + wpi::units::ampere_t GetCurrentDraw() const; /** * Gets the input voltage for the DC motor. * * @return The DC motor input voltage. */ - units::volt_t GetInputVoltage() const; + wpi::units::volt_t GetInputVoltage() const; /** * Sets the input voltage for the DC motor. * * @param voltage The input voltage. */ - void SetInputVoltage(units::volt_t voltage); + void SetInputVoltage(wpi::units::volt_t voltage); /** * Returns the gearbox. */ - const DCMotor& GetGearbox() const; + const wpi::math::DCMotor& GetGearbox() const; /** * Returns the gearing; @@ -120,11 +120,11 @@ class DCMotorSim : public LinearSystemSim<2, 1, 2> { /** * Returns the moment of inertia */ - units::kilogram_square_meter_t GetJ() const; + wpi::units::kilogram_square_meter_t GetJ() const; private: - DCMotor m_gearbox; + wpi::math::DCMotor m_gearbox; double m_gearing; - units::kilogram_square_meter_t m_j; + wpi::units::kilogram_square_meter_t m_j; }; -} // namespace frc::sim +} // namespace wpi::sim diff --git a/wpilibc/src/main/native/include/wpi/simulation/DIOSim.hpp b/wpilibc/src/main/native/include/wpi/simulation/DIOSim.hpp index 8266f43530..5e4d1a122a 100644 --- a/wpilibc/src/main/native/include/wpi/simulation/DIOSim.hpp +++ b/wpilibc/src/main/native/include/wpi/simulation/DIOSim.hpp @@ -8,7 +8,7 @@ #include "wpi/simulation/CallbackStore.hpp" -namespace frc { +namespace wpi { class DigitalInput; class DigitalOutput; @@ -178,4 +178,4 @@ class DIOSim { int m_index; }; } // namespace sim -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/simulation/DifferentialDrivetrainSim.hpp b/wpilibc/src/main/native/include/wpi/simulation/DifferentialDrivetrainSim.hpp index 4b133d5443..8ef8388dcf 100644 --- a/wpilibc/src/main/native/include/wpi/simulation/DifferentialDrivetrainSim.hpp +++ b/wpilibc/src/main/native/include/wpi/simulation/DifferentialDrivetrainSim.hpp @@ -13,19 +13,19 @@ #include "wpi/units/time.hpp" #include "wpi/units/voltage.hpp" -namespace frc::sim { +namespace wpi::sim { class DifferentialDrivetrainSim { public: /** * Creates a simulated differential drivetrain. * - * @param plant The LinearSystem representing the robot's drivetrain. This + * @param plant The wpi::math::LinearSystem representing the robot's drivetrain. This * system can be created with - * LinearSystemId::DrivetrainVelocitySystem() or - * LinearSystemId::IdentifyDrivetrainSystem(). + * wpi::math::LinearSystemId::DrivetrainVelocitySystem() or + * wpi::math::LinearSystemId::IdentifyDrivetrainSystem(). * @param trackwidth The robot's trackwidth. - * @param driveMotor A DCMotor representing the left side of the drivetrain. + * @param driveMotor A wpi::math::DCMotor representing the left side of the drivetrain. * @param gearingRatio The gearingRatio ratio of the left side, as output over * input. This must be the same ratio as the ratio used to * identify or create the plant. @@ -40,14 +40,14 @@ class DifferentialDrivetrainSim { * starting point. */ DifferentialDrivetrainSim( - LinearSystem<2, 2, 2> plant, units::meter_t trackwidth, - DCMotor driveMotor, double gearingRatio, units::meter_t wheelRadius, + wpi::math::LinearSystem<2, 2, 2> plant, wpi::units::meter_t trackwidth, + wpi::math::DCMotor driveMotor, double gearingRatio, wpi::units::meter_t wheelRadius, const std::array& measurementStdDevs = {}); /** * Creates a simulated differential drivetrain. * - * @param driveMotor A DCMotor representing the left side of the drivetrain. + * @param driveMotor A wpi::math::DCMotor representing the left side of the drivetrain. * @param gearing The gearing on the drive between motor and wheel, as * output over input. This must be the same ratio as the * ratio used to identify or create the plant. @@ -67,9 +67,9 @@ class DifferentialDrivetrainSim { * starting point. */ DifferentialDrivetrainSim( - frc::DCMotor driveMotor, double gearing, units::kilogram_square_meter_t J, - units::kilogram_t mass, units::meter_t wheelRadius, - units::meter_t trackwidth, + wpi::math::DCMotor driveMotor, double gearing, wpi::units::kilogram_square_meter_t J, + wpi::units::kilogram_t mass, wpi::units::meter_t wheelRadius, + wpi::units::meter_t trackwidth, const std::array& measurementStdDevs = {}); /** @@ -88,7 +88,7 @@ class DifferentialDrivetrainSim { * @param leftVoltage The left voltage. * @param rightVoltage The right voltage. */ - void SetInputs(units::volt_t leftVoltage, units::volt_t rightVoltage); + void SetInputs(wpi::units::volt_t leftVoltage, wpi::units::volt_t rightVoltage); /** * Sets the gearing reduction on the drivetrain. This is commonly used for @@ -101,10 +101,10 @@ class DifferentialDrivetrainSim { /** * Updates the simulation. * - * @param dt The time that's passed since the last Update(units::second_t) + * @param dt The time that's passed since the last Update(wpi::units::second_t) * call. */ - void Update(units::second_t dt); + void Update(wpi::units::second_t dt); /** * Returns the current gearing reduction of the drivetrain, as output over @@ -118,73 +118,73 @@ class DifferentialDrivetrainSim { * Note that this angle is counterclockwise-positive, while most gyros are * clockwise positive. */ - Rotation2d GetHeading() const; + wpi::math::Rotation2d GetHeading() const; /** * Returns the current pose. */ - Pose2d GetPose() const; + wpi::math::Pose2d GetPose() const; /** * Get the right encoder position in meters. * @return The encoder position. */ - units::meter_t GetRightPosition() const { - return units::meter_t{GetOutput(State::kRightPosition)}; + wpi::units::meter_t GetRightPosition() const { + return wpi::units::meter_t{GetOutput(State::kRightPosition)}; } /** * Get the right encoder velocity in meters per second. * @return The encoder velocity. */ - units::meters_per_second_t GetRightVelocity() const { - return units::meters_per_second_t{GetOutput(State::kRightVelocity)}; + wpi::units::meters_per_second_t GetRightVelocity() const { + return wpi::units::meters_per_second_t{GetOutput(State::kRightVelocity)}; } /** * Get the left encoder position in meters. * @return The encoder position. */ - units::meter_t GetLeftPosition() const { - return units::meter_t{GetOutput(State::kLeftPosition)}; + wpi::units::meter_t GetLeftPosition() const { + return wpi::units::meter_t{GetOutput(State::kLeftPosition)}; } /** * Get the left encoder velocity in meters per second. * @return The encoder velocity. */ - units::meters_per_second_t GetLeftVelocity() const { - return units::meters_per_second_t{GetOutput(State::kLeftVelocity)}; + wpi::units::meters_per_second_t GetLeftVelocity() const { + return wpi::units::meters_per_second_t{GetOutput(State::kLeftVelocity)}; } /** * Returns the currently drawn current for the right side. */ - units::ampere_t GetRightCurrentDraw() const; + wpi::units::ampere_t GetRightCurrentDraw() const; /** * Returns the currently drawn current for the left side. */ - units::ampere_t GetLeftCurrentDraw() const; + wpi::units::ampere_t GetLeftCurrentDraw() const; /** * Returns the currently drawn current. */ - units::ampere_t GetCurrentDraw() const; + wpi::units::ampere_t GetCurrentDraw() const; /** * Sets the system state. * * @param state The state. */ - void SetState(const Vectord<7>& state); + void SetState(const wpi::math::Vectord<7>& state); /** * Sets the system pose. * * @param pose The pose. */ - void SetPose(const frc::Pose2d& pose); + void SetPose(const wpi::math::Pose2d& pose); /** * The differential drive dynamics function. @@ -193,7 +193,7 @@ class DifferentialDrivetrainSim { * @param u The input. * @return The state derivative with respect to time. */ - Vectord<7> Dynamics(const Vectord<7>& x, const Eigen::Vector2d& u); + wpi::math::Vectord<7> Dynamics(const wpi::math::Vectord<7>& x, const Eigen::Vector2d& u); class State { public: @@ -234,24 +234,24 @@ class DifferentialDrivetrainSim { class KitbotMotor { public: /// One CIM motor per drive side. - static constexpr frc::DCMotor SingleCIMPerSide = frc::DCMotor::CIM(1); + static constexpr wpi::math::DCMotor SingleCIMPerSide = wpi::math::DCMotor::CIM(1); /// Two CIM motors per drive side. - static constexpr frc::DCMotor DualCIMPerSide = frc::DCMotor::CIM(2); + static constexpr wpi::math::DCMotor DualCIMPerSide = wpi::math::DCMotor::CIM(2); /// One Mini CIM motor per drive side. - static constexpr frc::DCMotor SingleMiniCIMPerSide = - frc::DCMotor::MiniCIM(1); + static constexpr wpi::math::DCMotor SingleMiniCIMPerSide = + wpi::math::DCMotor::MiniCIM(1); /// Two Mini CIM motors per drive side. - static constexpr frc::DCMotor DualMiniCIMPerSide = frc::DCMotor::MiniCIM(2); + static constexpr wpi::math::DCMotor DualMiniCIMPerSide = wpi::math::DCMotor::MiniCIM(2); /// One Falcon 500 motor per drive side. - static constexpr frc::DCMotor SingleFalcon500PerSide = - frc::DCMotor::Falcon500(1); + static constexpr wpi::math::DCMotor SingleFalcon500PerSide = + wpi::math::DCMotor::Falcon500(1); /// Two Falcon 500 motors per drive side. - static constexpr frc::DCMotor DualFalcon500PerSide = - frc::DCMotor::Falcon500(2); + static constexpr wpi::math::DCMotor DualFalcon500PerSide = + wpi::math::DCMotor::Falcon500(2); /// One NEO motor per drive side. - static constexpr frc::DCMotor SingleNEOPerSide = frc::DCMotor::NEO(1); + static constexpr wpi::math::DCMotor SingleNEOPerSide = wpi::math::DCMotor::NEO(1); /// Two NEO motors per drive side. - static constexpr frc::DCMotor DualNEOPerSide = frc::DCMotor::NEO(2); + static constexpr wpi::math::DCMotor DualNEOPerSide = wpi::math::DCMotor::NEO(2); }; /** @@ -260,11 +260,11 @@ class DifferentialDrivetrainSim { class KitbotWheelSize { public: /// Six inch diameter wheels. - static constexpr units::meter_t kSixInch = 6_in; + static constexpr wpi::units::meter_t kSixInch = 6_in; /// Eight inch diameter wheels. - static constexpr units::meter_t kEightInch = 8_in; + static constexpr wpi::units::meter_t kEightInch = 8_in; /// Ten inch diameter wheels. - static constexpr units::meter_t kTenInch = 10_in; + static constexpr wpi::units::meter_t kTenInch = 10_in; }; /** @@ -281,11 +281,11 @@ class DifferentialDrivetrainSim { * starting point. */ static DifferentialDrivetrainSim CreateKitbotSim( - frc::DCMotor motor, double gearing, units::meter_t wheelSize, + wpi::math::DCMotor motor, double gearing, wpi::units::meter_t wheelSize, const std::array& measurementStdDevs = {}) { // MOI estimation -- note that I = mr² for point masses - units::kilogram_square_meter_t batteryMoi = 12.5_lb * 10_in * 10_in; - units::kilogram_square_meter_t gearboxMoi = (2.8_lb + 2.0_lb) * + wpi::units::kilogram_square_meter_t batteryMoi = 12.5_lb * 10_in * 10_in; + wpi::units::kilogram_square_meter_t gearboxMoi = (2.8_lb + 2.0_lb) * 2 // CIM plus toughbox per side * (26_in / 2) * (26_in / 2); @@ -310,8 +310,8 @@ class DifferentialDrivetrainSim { * starting point. */ static DifferentialDrivetrainSim CreateKitbotSim( - frc::DCMotor motor, double gearing, units::meter_t wheelSize, - units::kilogram_square_meter_t J, + wpi::math::DCMotor motor, double gearing, wpi::units::meter_t wheelSize, + wpi::units::kilogram_square_meter_t J, const std::array& measurementStdDevs = {}) { return DifferentialDrivetrainSim{ motor, gearing, J, 60_lb, wheelSize / 2.0, 26_in, measurementStdDevs}; @@ -328,7 +328,7 @@ class DifferentialDrivetrainSim { /** * Returns the current output vector y. */ - Vectord<7> GetOutput() const; + wpi::math::Vectord<7> GetOutput() const; /** * Returns an element of the state vector. Note that this will not include @@ -341,20 +341,20 @@ class DifferentialDrivetrainSim { /** * Returns the current state vector x. Note that this will not include noise! */ - Vectord<7> GetState() const; + wpi::math::Vectord<7> GetState() const; - LinearSystem<2, 2, 2> m_plant; - units::meter_t m_rb; - units::meter_t m_wheelRadius; + wpi::math::LinearSystem<2, 2, 2> m_plant; + wpi::units::meter_t m_rb; + wpi::units::meter_t m_wheelRadius; - DCMotor m_motor; + wpi::math::DCMotor m_motor; double m_originalGearing; double m_currentGearing; - Vectord<7> m_x; + wpi::math::Vectord<7> m_x; Eigen::Vector2d m_u; - Vectord<7> m_y; + wpi::math::Vectord<7> m_y; std::array m_measurementStdDevs; }; -} // namespace frc::sim +} // namespace wpi::sim diff --git a/wpilibc/src/main/native/include/wpi/simulation/DigitalPWMSim.hpp b/wpilibc/src/main/native/include/wpi/simulation/DigitalPWMSim.hpp index e9c517a77a..e51ca2cff9 100644 --- a/wpilibc/src/main/native/include/wpi/simulation/DigitalPWMSim.hpp +++ b/wpilibc/src/main/native/include/wpi/simulation/DigitalPWMSim.hpp @@ -8,7 +8,7 @@ #include "wpi/simulation/CallbackStore.hpp" -namespace frc { +namespace wpi { class DigitalOutput; @@ -133,4 +133,4 @@ class DigitalPWMSim { int m_index; }; } // namespace sim -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/simulation/DoubleSolenoidSim.hpp b/wpilibc/src/main/native/include/wpi/simulation/DoubleSolenoidSim.hpp index 969e8ec1e3..d2f3f4b762 100644 --- a/wpilibc/src/main/native/include/wpi/simulation/DoubleSolenoidSim.hpp +++ b/wpilibc/src/main/native/include/wpi/simulation/DoubleSolenoidSim.hpp @@ -10,7 +10,7 @@ #include "wpi/hardware/pneumatic/PneumaticsModuleType.hpp" #include "wpi/simulation/PneumaticsBaseSim.hpp" -namespace frc::sim { +namespace wpi::sim { class DoubleSolenoidSim { public: @@ -30,4 +30,4 @@ class DoubleSolenoidSim { int m_rev; }; -} // namespace frc::sim +} // namespace wpi::sim diff --git a/wpilibc/src/main/native/include/wpi/simulation/DriverStationSim.hpp b/wpilibc/src/main/native/include/wpi/simulation/DriverStationSim.hpp index ca85972e68..8654812b9c 100644 --- a/wpilibc/src/main/native/include/wpi/simulation/DriverStationSim.hpp +++ b/wpilibc/src/main/native/include/wpi/simulation/DriverStationSim.hpp @@ -10,7 +10,7 @@ #include "wpi/hal/DriverStationTypes.h" #include "wpi/simulation/CallbackStore.hpp" -namespace frc::sim { +namespace wpi::sim { /** * Class to control a simulated driver station. @@ -396,4 +396,4 @@ class DriverStationSim { */ static void ResetData(); }; -} // namespace frc::sim +} // namespace wpi::sim diff --git a/wpilibc/src/main/native/include/wpi/simulation/DutyCycleEncoderSim.hpp b/wpilibc/src/main/native/include/wpi/simulation/DutyCycleEncoderSim.hpp index f4e3fd35cc..389a80935c 100644 --- a/wpilibc/src/main/native/include/wpi/simulation/DutyCycleEncoderSim.hpp +++ b/wpilibc/src/main/native/include/wpi/simulation/DutyCycleEncoderSim.hpp @@ -7,7 +7,7 @@ #include "wpi/hal/SimDevice.h" #include "wpi/units/angle.hpp" -namespace frc { +namespace wpi { class DutyCycleEncoder; @@ -61,9 +61,9 @@ class DutyCycleEncoderSim { void SetConnected(bool isConnected); private: - hal::SimDouble m_simPosition; - hal::SimBoolean m_simIsConnected; + wpi::hal::SimDouble m_simPosition; + wpi::hal::SimBoolean m_simIsConnected; }; } // namespace sim -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/simulation/DutyCycleSim.hpp b/wpilibc/src/main/native/include/wpi/simulation/DutyCycleSim.hpp index e043728993..49293ffc85 100644 --- a/wpilibc/src/main/native/include/wpi/simulation/DutyCycleSim.hpp +++ b/wpilibc/src/main/native/include/wpi/simulation/DutyCycleSim.hpp @@ -9,7 +9,7 @@ #include "wpi/simulation/CallbackStore.hpp" #include "wpi/units/frequency.hpp" -namespace frc { +namespace wpi { class DutyCycle; @@ -76,14 +76,14 @@ class DutyCycleSim { * * @return the duty cycle frequency */ - units::hertz_t GetFrequency() const; + wpi::units::hertz_t GetFrequency() const; /** * Change the duty cycle frequency. * * @param frequency the new frequency */ - void SetFrequency(units::hertz_t frequency); + void SetFrequency(wpi::units::hertz_t frequency); /** * Register a callback to be run whenever the output changes. @@ -121,4 +121,4 @@ class DutyCycleSim { int m_index; }; } // namespace sim -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/simulation/ElevatorSim.hpp b/wpilibc/src/main/native/include/wpi/simulation/ElevatorSim.hpp index c60261d5c1..43d246de08 100644 --- a/wpilibc/src/main/native/include/wpi/simulation/ElevatorSim.hpp +++ b/wpilibc/src/main/native/include/wpi/simulation/ElevatorSim.hpp @@ -12,27 +12,27 @@ #include "wpi/units/mass.hpp" #include "wpi/units/velocity.hpp" -namespace frc::sim { +namespace wpi::sim { /** * Represents a simulated elevator mechanism. */ class ElevatorSim : public LinearSystemSim<2, 1, 2> { public: template - using Velocity_t = units::unit_t< - units::compound_unit>>; + using Velocity_t = wpi::units::unit_t< + wpi::units::compound_unit>>; template - using Acceleration_t = units::unit_t>, - units::inverse>>; + using Acceleration_t = wpi::units::unit_t>, + wpi::units::inverse>>; /** * Constructs a simulated elevator mechanism. * * @param plant The linear system that represents the elevator. * This system can be created with - * LinearSystemId::ElevatorSystem(). + * wpi::math::LinearSystemId::ElevatorSystem(). * @param gearbox The type of and number of motors in your * elevator gearbox. * @param minHeight The minimum allowed height of the elevator. @@ -41,9 +41,9 @@ class ElevatorSim : public LinearSystemSim<2, 1, 2> { * @param startingHeight The starting height of the elevator. * @param measurementStdDevs The standard deviation of the measurements. */ - ElevatorSim(const LinearSystem<2, 1, 2>& plant, const DCMotor& gearbox, - units::meter_t minHeight, units::meter_t maxHeight, - bool simulateGravity, units::meter_t startingHeight, + ElevatorSim(const wpi::math::LinearSystem<2, 1, 2>& plant, const wpi::math::DCMotor& gearbox, + wpi::units::meter_t minHeight, wpi::units::meter_t maxHeight, + bool simulateGravity, wpi::units::meter_t startingHeight, const std::array& measurementStdDevs = {0.0, 0.0}); /** @@ -62,10 +62,10 @@ class ElevatorSim : public LinearSystemSim<2, 1, 2> { * @param startingHeight The starting height of the elevator. * @param measurementStdDevs The standard deviation of the measurements. */ - ElevatorSim(const DCMotor& gearbox, double gearing, - units::kilogram_t carriageMass, units::meter_t drumRadius, - units::meter_t minHeight, units::meter_t maxHeight, - bool simulateGravity, units::meter_t startingHeight, + ElevatorSim(const wpi::math::DCMotor& gearbox, double gearing, + wpi::units::kilogram_t carriageMass, wpi::units::meter_t drumRadius, + wpi::units::meter_t minHeight, wpi::units::meter_t maxHeight, + bool simulateGravity, wpi::units::meter_t startingHeight, const std::array& measurementStdDevs = {0.0, 0.0}); /** @@ -82,13 +82,13 @@ class ElevatorSim : public LinearSystemSim<2, 1, 2> { * @param measurementStdDevs The standard deviation of the measurements. */ template - requires std::same_as || - std::same_as + requires std::same_as || + std::same_as ElevatorSim(decltype(1_V / Velocity_t(1)) kV, decltype(1_V / Acceleration_t(1)) kA, - const DCMotor& gearbox, units::meter_t minHeight, - units::meter_t maxHeight, bool simulateGravity, - units::meter_t startingHeight, + const wpi::math::DCMotor& gearbox, wpi::units::meter_t minHeight, + wpi::units::meter_t maxHeight, bool simulateGravity, + wpi::units::meter_t startingHeight, const std::array& measurementStdDevs = {0.0, 0.0}); using LinearSystemSim::SetState; @@ -98,7 +98,7 @@ class ElevatorSim : public LinearSystemSim<2, 1, 2> { * @param position The new position * @param velocity The new velocity */ - void SetState(units::meter_t position, units::meters_per_second_t velocity); + void SetState(wpi::units::meter_t position, wpi::units::meters_per_second_t velocity); /** * Returns whether the elevator would hit the lower limit. @@ -106,7 +106,7 @@ class ElevatorSim : public LinearSystemSim<2, 1, 2> { * @param elevatorHeight The elevator height. * @return Whether the elevator would hit the lower limit. */ - bool WouldHitLowerLimit(units::meter_t elevatorHeight) const; + bool WouldHitLowerLimit(wpi::units::meter_t elevatorHeight) const; /** * Returns whether the elevator would hit the upper limit. @@ -114,7 +114,7 @@ class ElevatorSim : public LinearSystemSim<2, 1, 2> { * @param elevatorHeight The elevator height. * @return Whether the elevator would hit the upper limit. */ - bool WouldHitUpperLimit(units::meter_t elevatorHeight) const; + bool WouldHitUpperLimit(wpi::units::meter_t elevatorHeight) const; /** * Returns whether the elevator has hit the lower limit. @@ -135,28 +135,28 @@ class ElevatorSim : public LinearSystemSim<2, 1, 2> { * * @return The position of the elevator. */ - units::meter_t GetPosition() const; + wpi::units::meter_t GetPosition() const; /** * Returns the velocity of the elevator. * * @return The velocity of the elevator. */ - units::meters_per_second_t GetVelocity() const; + wpi::units::meters_per_second_t GetVelocity() const; /** * Returns the elevator current draw. * * @return The elevator current draw. */ - units::ampere_t GetCurrentDraw() const; + wpi::units::ampere_t GetCurrentDraw() const; /** * Sets the input voltage for the elevator. * * @param voltage The input voltage. */ - void SetInputVoltage(units::volt_t voltage); + void SetInputVoltage(wpi::units::volt_t voltage); protected: /** @@ -166,13 +166,13 @@ class ElevatorSim : public LinearSystemSim<2, 1, 2> { * @param u The system inputs (voltage). * @param dt The time difference between controller updates. */ - Vectord<2> UpdateX(const Vectord<2>& currentXhat, const Vectord<1>& u, - units::second_t dt) override; + wpi::math::Vectord<2> UpdateX(const wpi::math::Vectord<2>& currentXhat, const wpi::math::Vectord<1>& u, + wpi::units::second_t dt) override; private: - DCMotor m_gearbox; - units::meter_t m_minHeight; - units::meter_t m_maxHeight; + wpi::math::DCMotor m_gearbox; + wpi::units::meter_t m_minHeight; + wpi::units::meter_t m_maxHeight; bool m_simulateGravity; }; -} // namespace frc::sim +} // namespace wpi::sim diff --git a/wpilibc/src/main/native/include/wpi/simulation/EncoderSim.hpp b/wpilibc/src/main/native/include/wpi/simulation/EncoderSim.hpp index 72875ec262..2bb9abf5db 100644 --- a/wpilibc/src/main/native/include/wpi/simulation/EncoderSim.hpp +++ b/wpilibc/src/main/native/include/wpi/simulation/EncoderSim.hpp @@ -8,7 +8,7 @@ #include "wpi/simulation/CallbackStore.hpp" -namespace frc { +namespace wpi { class Encoder; @@ -317,4 +317,4 @@ class EncoderSim { int m_index; }; } // namespace sim -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/simulation/FlywheelSim.hpp b/wpilibc/src/main/native/include/wpi/simulation/FlywheelSim.hpp index 2411bc378f..54a2aa7326 100644 --- a/wpilibc/src/main/native/include/wpi/simulation/FlywheelSim.hpp +++ b/wpilibc/src/main/native/include/wpi/simulation/FlywheelSim.hpp @@ -12,7 +12,7 @@ #include "wpi/units/moment_of_inertia.hpp" #include "wpi/units/torque.hpp" -namespace frc::sim { +namespace wpi::sim { /** * Represents a simulated flywheel mechanism. */ @@ -23,13 +23,13 @@ class FlywheelSim : public LinearSystemSim<1, 1, 1> { * * @param plant The linear system representing the flywheel. This * system can be created with - * LinearSystemId::FlywheelSystem() or - * LinearSystemId::IdentifyVelocitySystem(). + * wpi::math::LinearSystemId::FlywheelSystem() or + * wpi::math::LinearSystemId::IdentifyVelocitySystem(). * @param gearbox The type of and number of motors in the flywheel * gearbox. * @param measurementStdDevs The standard deviation of the measurement noise. */ - FlywheelSim(const LinearSystem<1, 1, 1>& plant, const DCMotor& gearbox, + FlywheelSim(const wpi::math::LinearSystem<1, 1, 1>& plant, const wpi::math::DCMotor& gearbox, const std::array& measurementStdDevs = {0.0}); using LinearSystemSim::SetState; @@ -39,54 +39,54 @@ class FlywheelSim : public LinearSystemSim<1, 1, 1> { * * @param velocity The new velocity */ - void SetVelocity(units::radians_per_second_t velocity); + void SetVelocity(wpi::units::radians_per_second_t velocity); /** * Returns the flywheel's velocity. * * @return The flywheel's velocity. */ - units::radians_per_second_t GetAngularVelocity() const; + wpi::units::radians_per_second_t GetAngularVelocity() const; /** * Returns the flywheel's acceleration. * * @return The flywheel's acceleration */ - units::radians_per_second_squared_t GetAngularAcceleration() const; + wpi::units::radians_per_second_squared_t GetAngularAcceleration() const; /** * Returns the flywheel's torque. * * @return The flywheel's torque */ - units::newton_meter_t GetTorque() const; + wpi::units::newton_meter_t GetTorque() const; /** * Returns the flywheel's current draw. * * @return The flywheel's current draw. */ - units::ampere_t GetCurrentDraw() const; + wpi::units::ampere_t GetCurrentDraw() const; /** * Gets the input voltage for the flywheel. * * @return The flywheel input voltage. */ - units::volt_t GetInputVoltage() const; + wpi::units::volt_t GetInputVoltage() const; /** * Sets the input voltage for the flywheel. * * @param voltage The input voltage. */ - void SetInputVoltage(units::volt_t voltage); + void SetInputVoltage(wpi::units::volt_t voltage); /** * Returns the gearbox. */ - DCMotor Gearbox() const { return m_gearbox; } + wpi::math::DCMotor Gearbox() const { return m_gearbox; } /** * Returns the gearing; @@ -96,11 +96,11 @@ class FlywheelSim : public LinearSystemSim<1, 1, 1> { /** * Returns the moment of inertia */ - units::kilogram_square_meter_t J() const { return m_j; } + wpi::units::kilogram_square_meter_t J() const { return m_j; } private: - DCMotor m_gearbox; + wpi::math::DCMotor m_gearbox; double m_gearing; - units::kilogram_square_meter_t m_j; + wpi::units::kilogram_square_meter_t m_j; }; -} // namespace frc::sim +} // namespace wpi::sim diff --git a/wpilibc/src/main/native/include/wpi/simulation/GamepadSim.hpp b/wpilibc/src/main/native/include/wpi/simulation/GamepadSim.hpp index fac63aaff9..af9fd5f114 100644 --- a/wpilibc/src/main/native/include/wpi/simulation/GamepadSim.hpp +++ b/wpilibc/src/main/native/include/wpi/simulation/GamepadSim.hpp @@ -6,7 +6,7 @@ #include "wpi/simulation/GenericHIDSim.hpp" -namespace frc { +namespace wpi { class Gamepad; @@ -257,4 +257,4 @@ class GamepadSim : public GenericHIDSim { }; } // namespace sim -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/simulation/GenericHIDSim.hpp b/wpilibc/src/main/native/include/wpi/simulation/GenericHIDSim.hpp index 55ada4a477..ab7ac1550f 100644 --- a/wpilibc/src/main/native/include/wpi/simulation/GenericHIDSim.hpp +++ b/wpilibc/src/main/native/include/wpi/simulation/GenericHIDSim.hpp @@ -9,7 +9,7 @@ #include "wpi/driverstation/DriverStation.hpp" #include "wpi/driverstation/GenericHID.hpp" -namespace frc { +namespace wpi { class GenericHID; @@ -140,4 +140,4 @@ class GenericHIDSim { }; } // namespace sim -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/simulation/JoystickSim.hpp b/wpilibc/src/main/native/include/wpi/simulation/JoystickSim.hpp index c92e086016..d3c5bc71da 100644 --- a/wpilibc/src/main/native/include/wpi/simulation/JoystickSim.hpp +++ b/wpilibc/src/main/native/include/wpi/simulation/JoystickSim.hpp @@ -6,7 +6,7 @@ #include "wpi/simulation/GenericHIDSim.hpp" -namespace frc { +namespace wpi { class Joystick; @@ -85,4 +85,4 @@ class JoystickSim : public GenericHIDSim { }; } // namespace sim -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/simulation/LinearSystemSim.hpp b/wpilibc/src/main/native/include/wpi/simulation/LinearSystemSim.hpp index 0fe12916e7..550c5d640f 100644 --- a/wpilibc/src/main/native/include/wpi/simulation/LinearSystemSim.hpp +++ b/wpilibc/src/main/native/include/wpi/simulation/LinearSystemSim.hpp @@ -12,7 +12,7 @@ #include "wpi/units/current.hpp" #include "wpi/units/time.hpp" -namespace frc::sim { +namespace wpi::sim { /** * This class helps simulate linear systems. To use this class, do the following * in the simulationPeriodic() method. @@ -35,12 +35,12 @@ class LinearSystemSim { * @param measurementStdDevs The standard deviations of the measurements. */ explicit LinearSystemSim( - const LinearSystem& system, + const wpi::math::LinearSystem& system, const std::array& measurementStdDevs = {}) : m_plant(system), m_measurementStdDevs(measurementStdDevs) { - m_x = Vectord::Zero(); - m_y = Vectord::Zero(); - m_u = Vectord::Zero(); + m_x = wpi::math::Vectord::Zero(); + m_y = wpi::math::Vectord::Zero(); + m_u = wpi::math::Vectord::Zero(); } virtual ~LinearSystemSim() = default; @@ -50,7 +50,7 @@ class LinearSystemSim { * * @param dt The time between updates. */ - void Update(units::second_t dt) { + void Update(wpi::units::second_t dt) { // Update x. By default, this is the linear system dynamics xₖ₊₁ = Axₖ + // Buₖ. m_x = UpdateX(m_x, m_u, dt); @@ -61,7 +61,7 @@ class LinearSystemSim { // Add noise. If the user did not pass a noise vector to the // constructor, then this method will not do anything because // the standard deviations default to zero. - m_y += frc::MakeWhiteNoiseVector(m_measurementStdDevs); + m_y += wpi::math::MakeWhiteNoiseVector(m_measurementStdDevs); } /** @@ -69,7 +69,7 @@ class LinearSystemSim { * * @return The current output of the plant. */ - const Vectord& GetOutput() const { return m_y; } + const wpi::math::Vectord& GetOutput() const { return m_y; } /** * Returns an element of the current output of the plant. @@ -84,7 +84,7 @@ class LinearSystemSim { * * @param u The system inputs. */ - void SetInput(const Vectord& u) { m_u = u; } + void SetInput(const wpi::math::Vectord& u) { m_u = u; } /** * Sets the system inputs. @@ -99,7 +99,7 @@ class LinearSystemSim { * * @return The current input of the plant. */ - const Vectord& GetInput() const { return m_u; } + const wpi::math::Vectord& GetInput() const { return m_u; } /** * Returns an element of the current input of the plant. @@ -114,7 +114,7 @@ class LinearSystemSim { * * @param state The new state. */ - void SetState(const Vectord& state) { + void SetState(const wpi::math::Vectord& state) { m_x = state; // Update the output to reflect the new state. @@ -131,9 +131,9 @@ class LinearSystemSim { * @param u The system inputs (usually voltage). * @param dt The time difference between controller updates. */ - virtual Vectord UpdateX(const Vectord& currentXhat, - const Vectord& u, - units::second_t dt) { + virtual wpi::math::Vectord UpdateX(const wpi::math::Vectord& currentXhat, + const wpi::math::Vectord& u, + wpi::units::second_t dt) { return m_plant.CalculateX(currentXhat, u, dt); } @@ -144,23 +144,23 @@ class LinearSystemSim { * @param maxInput The maximum magnitude of the input vector after clamping. */ void ClampInput(double maxInput) { - m_u = frc::DesaturateInputVector(m_u, maxInput); + m_u = wpi::math::DesaturateInputVector(m_u, maxInput); } /// The plant that represents the linear system. - LinearSystem m_plant; + wpi::math::LinearSystem m_plant; /// State vector. - Vectord m_x; + wpi::math::Vectord m_x; /// Input vector. - Vectord m_u; + wpi::math::Vectord m_u; /// Output vector. - Vectord m_y; + wpi::math::Vectord m_y; /// The standard deviations of measurements, used for adding noise to the /// measurements. std::array m_measurementStdDevs; }; -} // namespace frc::sim +} // namespace wpi::sim diff --git a/wpilibc/src/main/native/include/wpi/simulation/PWMMotorControllerSim.hpp b/wpilibc/src/main/native/include/wpi/simulation/PWMMotorControllerSim.hpp index 2231dc74d5..4204a3575a 100644 --- a/wpilibc/src/main/native/include/wpi/simulation/PWMMotorControllerSim.hpp +++ b/wpilibc/src/main/native/include/wpi/simulation/PWMMotorControllerSim.hpp @@ -8,7 +8,7 @@ #include "wpi/hardware/motor/PWMMotorController.hpp" #include "wpi/units/length.hpp" -namespace frc { +namespace wpi { class PWMMotorController; @@ -23,7 +23,7 @@ class PWMMotorControllerSim { double GetSpeed() const; private: - hal::SimDouble m_simSpeed; + wpi::hal::SimDouble m_simSpeed; }; } // namespace sim -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/simulation/PWMSim.hpp b/wpilibc/src/main/native/include/wpi/simulation/PWMSim.hpp index 3059ce9355..ae9a29809d 100644 --- a/wpilibc/src/main/native/include/wpi/simulation/PWMSim.hpp +++ b/wpilibc/src/main/native/include/wpi/simulation/PWMSim.hpp @@ -8,7 +8,7 @@ #include "wpi/simulation/CallbackStore.hpp" -namespace frc { +namespace wpi { class PWM; class PWMMotorController; @@ -118,4 +118,4 @@ class PWMSim { int m_index; }; } // namespace sim -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/simulation/PneumaticsBaseSim.hpp b/wpilibc/src/main/native/include/wpi/simulation/PneumaticsBaseSim.hpp index 653bce1eb6..3102ce0074 100644 --- a/wpilibc/src/main/native/include/wpi/simulation/PneumaticsBaseSim.hpp +++ b/wpilibc/src/main/native/include/wpi/simulation/PneumaticsBaseSim.hpp @@ -10,7 +10,7 @@ #include "wpi/hardware/pneumatic/PneumaticsModuleType.hpp" #include "wpi/simulation/CallbackStore.hpp" -namespace frc::sim { +namespace wpi::sim { class PneumaticsBaseSim { public: @@ -195,4 +195,4 @@ class PneumaticsBaseSim { explicit PneumaticsBaseSim(const PneumaticsBase& module); }; -} // namespace frc::sim +} // namespace wpi::sim diff --git a/wpilibc/src/main/native/include/wpi/simulation/PowerDistributionSim.hpp b/wpilibc/src/main/native/include/wpi/simulation/PowerDistributionSim.hpp index 9336d7c94a..1c48354ce7 100644 --- a/wpilibc/src/main/native/include/wpi/simulation/PowerDistributionSim.hpp +++ b/wpilibc/src/main/native/include/wpi/simulation/PowerDistributionSim.hpp @@ -8,7 +8,7 @@ #include "wpi/simulation/CallbackStore.hpp" -namespace frc { +namespace wpi { class PowerDistribution; @@ -168,4 +168,4 @@ class PowerDistributionSim { int m_index; }; } // namespace sim -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/simulation/REVPHSim.hpp b/wpilibc/src/main/native/include/wpi/simulation/REVPHSim.hpp index 769c90db6e..e577ff2b9b 100644 --- a/wpilibc/src/main/native/include/wpi/simulation/REVPHSim.hpp +++ b/wpilibc/src/main/native/include/wpi/simulation/REVPHSim.hpp @@ -10,7 +10,7 @@ #include "wpi/simulation/CallbackStore.hpp" #include "wpi/simulation/PneumaticsBaseSim.hpp" -namespace frc { +namespace wpi { class Compressor; @@ -120,4 +120,4 @@ class REVPHSim : public PneumaticsBaseSim { void ResetData() override; }; } // namespace sim -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/simulation/RoboRioSim.hpp b/wpilibc/src/main/native/include/wpi/simulation/RoboRioSim.hpp index 03041c2760..b9a7f9b631 100644 --- a/wpilibc/src/main/native/include/wpi/simulation/RoboRioSim.hpp +++ b/wpilibc/src/main/native/include/wpi/simulation/RoboRioSim.hpp @@ -13,7 +13,7 @@ #include "wpi/units/temperature.hpp" #include "wpi/units/voltage.hpp" -namespace frc::sim { +namespace wpi::sim { /** * A utility class to control a simulated RoboRIO. @@ -36,14 +36,14 @@ class RoboRioSim { * * @return the Vin voltage */ - static units::volt_t GetVInVoltage(); + static wpi::units::volt_t GetVInVoltage(); /** * Define the Vin voltage. * * @param vInVoltage the new voltage */ - static void SetVInVoltage(units::volt_t vInVoltage); + static void SetVInVoltage(wpi::units::volt_t vInVoltage); /** * Register a callback to be run whenever the 3.3V rail voltage changes. @@ -62,14 +62,14 @@ class RoboRioSim { * * @return the 3.3V rail voltage */ - static units::volt_t GetUserVoltage3V3(); + static wpi::units::volt_t GetUserVoltage3V3(); /** * Define the 3.3V rail voltage. * * @param userVoltage3V3 the new voltage */ - static void SetUserVoltage3V3(units::volt_t userVoltage3V3); + static void SetUserVoltage3V3(wpi::units::volt_t userVoltage3V3); /** * Register a callback to be run whenever the 3.3V rail current changes. @@ -88,14 +88,14 @@ class RoboRioSim { * * @return the 3.3V rail current */ - static units::ampere_t GetUserCurrent3V3(); + static wpi::units::ampere_t GetUserCurrent3V3(); /** * Define the 3.3V rail current. * * @param userCurrent3V3 the new current */ - static void SetUserCurrent3V3(units::ampere_t userCurrent3V3); + static void SetUserCurrent3V3(wpi::units::ampere_t userCurrent3V3); /** * Register a callback to be run whenever the 3.3V rail active state changes. @@ -166,14 +166,14 @@ class RoboRioSim { * * @return the brownout voltage */ - static units::volt_t GetBrownoutVoltage(); + static wpi::units::volt_t GetBrownoutVoltage(); /** * Define the brownout voltage. * * @param brownoutVoltage the new voltage */ - static void SetBrownoutVoltage(units::volt_t brownoutVoltage); + static void SetBrownoutVoltage(wpi::units::volt_t brownoutVoltage); /** * Register a callback to be run whenever the cpu temp changes. @@ -191,14 +191,14 @@ class RoboRioSim { * * @return the cpu temp. */ - static units::celsius_t GetCPUTemp(); + static wpi::units::celsius_t GetCPUTemp(); /** * Define the cpu temp. * * @param cpuTemp the new cpu temp. */ - static void SetCPUTemp(units::celsius_t cpuTemp); + static void SetCPUTemp(wpi::units::celsius_t cpuTemp); /** * Register a callback to be run whenever the team number changes. @@ -258,4 +258,4 @@ class RoboRioSim { */ static void ResetData(); }; -} // namespace frc::sim +} // namespace wpi::sim diff --git a/wpilibc/src/main/native/include/wpi/simulation/SendableChooserSim.hpp b/wpilibc/src/main/native/include/wpi/simulation/SendableChooserSim.hpp index f2ca2f205d..82f88cf692 100644 --- a/wpilibc/src/main/native/include/wpi/simulation/SendableChooserSim.hpp +++ b/wpilibc/src/main/native/include/wpi/simulation/SendableChooserSim.hpp @@ -10,7 +10,7 @@ #include "wpi/nt/StringTopic.hpp" #include "wpi/opmode/RobotBase.hpp" -namespace frc::sim { +namespace wpi::sim { /** * Class that facilitates control of a SendableChooser's selected option in @@ -31,7 +31,7 @@ class SendableChooserSim { * @param inst The NetworkTables instance. * @param path The path where the SendableChooser is published. */ - SendableChooserSim(nt::NetworkTableInstance inst, std::string_view path); + SendableChooserSim(wpi::nt::NetworkTableInstance inst, std::string_view path); /** * Set the selected option. @@ -40,6 +40,6 @@ class SendableChooserSim { void SetSelected(std::string_view option); private: - nt::StringPublisher m_publisher; + wpi::nt::StringPublisher m_publisher; }; -} // namespace frc::sim +} // namespace wpi::sim diff --git a/wpilibc/src/main/native/include/wpi/simulation/SharpIRSim.hpp b/wpilibc/src/main/native/include/wpi/simulation/SharpIRSim.hpp index 60bb17a13a..de3a7fd646 100644 --- a/wpilibc/src/main/native/include/wpi/simulation/SharpIRSim.hpp +++ b/wpilibc/src/main/native/include/wpi/simulation/SharpIRSim.hpp @@ -8,7 +8,7 @@ #include "wpi/hardware/range/SharpIR.hpp" #include "wpi/units/length.hpp" -namespace frc { +namespace wpi { /** Simulation class for Sharp IR sensors. */ class SharpIRSim { @@ -32,10 +32,10 @@ class SharpIRSim { * * @param range range of the target returned by the sensor */ - void SetRange(units::meter_t range); + void SetRange(wpi::units::meter_t range); private: - hal::SimDouble m_simRange; + wpi::hal::SimDouble m_simRange; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/simulation/SimDeviceSim.hpp b/wpilibc/src/main/native/include/wpi/simulation/SimDeviceSim.hpp index a5c0822779..0a54f25aa8 100644 --- a/wpilibc/src/main/native/include/wpi/simulation/SimDeviceSim.hpp +++ b/wpilibc/src/main/native/include/wpi/simulation/SimDeviceSim.hpp @@ -11,7 +11,7 @@ #include "wpi/hal/SimDevice.h" #include "wpi/hal/simulation/SimDeviceData.h" -namespace frc::sim { +namespace wpi::sim { /** * Class to control the simulation side of a SimDevice. @@ -62,7 +62,7 @@ class SimDeviceSim { * @param name the property name * @return the property object */ - hal::SimValue GetValue(const char* name) const; + wpi::hal::SimValue GetValue(const char* name) const; /** * Get the property object with the given name. @@ -70,7 +70,7 @@ class SimDeviceSim { * @param name the property name * @return the property object */ - hal::SimInt GetInt(const char* name) const; + wpi::hal::SimInt GetInt(const char* name) const; /** * Get the property object with the given name. @@ -78,7 +78,7 @@ class SimDeviceSim { * @param name the property name * @return the property object */ - hal::SimLong GetLong(const char* name) const; + wpi::hal::SimLong GetLong(const char* name) const; /** * Get the property object with the given name. @@ -86,7 +86,7 @@ class SimDeviceSim { * @param name the property name * @return the property object */ - hal::SimDouble GetDouble(const char* name) const; + wpi::hal::SimDouble GetDouble(const char* name) const; /** * Get the property object with the given name. @@ -94,7 +94,7 @@ class SimDeviceSim { * @param name the property name * @return the property object */ - hal::SimEnum GetEnum(const char* name) const; + wpi::hal::SimEnum GetEnum(const char* name) const; /** * Get the property object with the given name. @@ -102,7 +102,7 @@ class SimDeviceSim { * @param name the property name * @return the property object */ - hal::SimBoolean GetBoolean(const char* name) const; + wpi::hal::SimBoolean GetBoolean(const char* name) const; /** * Get all options for the given enum. @@ -159,4 +159,4 @@ class SimDeviceSim { private: HAL_SimDeviceHandle m_handle; }; -} // namespace frc::sim +} // namespace wpi::sim diff --git a/wpilibc/src/main/native/include/wpi/simulation/SimHooks.hpp b/wpilibc/src/main/native/include/wpi/simulation/SimHooks.hpp index ff2951457f..994d28635b 100644 --- a/wpilibc/src/main/native/include/wpi/simulation/SimHooks.hpp +++ b/wpilibc/src/main/native/include/wpi/simulation/SimHooks.hpp @@ -9,7 +9,7 @@ #include "wpi/hal/HALBase.h" #include "wpi/units/time.hpp" -namespace frc::sim { +namespace wpi::sim { /** * Override the HAL runtime type (simulated/real). @@ -51,13 +51,13 @@ bool IsTimingPaused(); * * @param delta the amount to advance (in seconds) */ -void StepTiming(units::second_t delta); +void StepTiming(wpi::units::second_t delta); /** * Advance the simulator time and return immediately. * * @param delta the amount to advance (in seconds) */ -void StepTimingAsync(units::second_t delta); +void StepTimingAsync(wpi::units::second_t delta); -} // namespace frc::sim +} // namespace wpi::sim diff --git a/wpilibc/src/main/native/include/wpi/simulation/SingleJointedArmSim.hpp b/wpilibc/src/main/native/include/wpi/simulation/SingleJointedArmSim.hpp index b453a24763..52caea5801 100644 --- a/wpilibc/src/main/native/include/wpi/simulation/SingleJointedArmSim.hpp +++ b/wpilibc/src/main/native/include/wpi/simulation/SingleJointedArmSim.hpp @@ -13,7 +13,7 @@ #include "wpi/units/mass.hpp" #include "wpi/units/moment_of_inertia.hpp" -namespace frc::sim { +namespace wpi::sim { /** * Represents a simulated arm mechanism. */ @@ -24,7 +24,7 @@ class SingleJointedArmSim : public LinearSystemSim<2, 1, 2> { * * @param system The system representing this arm. This system can * be created with - * LinearSystemId::SingleJointedArmSystem(). + * wpi::math::LinearSystemId::SingleJointedArmSystem(). * @param gearbox The type and number of motors on the arm gearbox. * @param gearing The gear ratio of the arm (numbers greater than 1 * represent reductions). @@ -35,11 +35,11 @@ class SingleJointedArmSim : public LinearSystemSim<2, 1, 2> { * @param startingAngle The initial position of the arm. * @param measurementStdDevs The standard deviations of the measurements. */ - SingleJointedArmSim(const LinearSystem<2, 1, 2>& system, - const DCMotor& gearbox, double gearing, - units::meter_t armLength, units::radian_t minAngle, - units::radian_t maxAngle, bool simulateGravity, - units::radian_t startingAngle, + SingleJointedArmSim(const wpi::math::LinearSystem<2, 1, 2>& system, + const wpi::math::DCMotor& gearbox, double gearing, + wpi::units::meter_t armLength, wpi::units::radian_t minAngle, + wpi::units::radian_t maxAngle, bool simulateGravity, + wpi::units::radian_t startingAngle, const std::array& measurementStdDevs = {0.0, 0.0}); /** @@ -57,11 +57,11 @@ class SingleJointedArmSim : public LinearSystemSim<2, 1, 2> { * @param startingAngle The initial position of the arm. * @param measurementStdDevs The standard deviation of the measurement noise. */ - SingleJointedArmSim(const DCMotor& gearbox, double gearing, - units::kilogram_square_meter_t moi, - units::meter_t armLength, units::radian_t minAngle, - units::radian_t maxAngle, bool simulateGravity, - units::radian_t startingAngle, + SingleJointedArmSim(const wpi::math::DCMotor& gearbox, double gearing, + wpi::units::kilogram_square_meter_t moi, + wpi::units::meter_t armLength, wpi::units::radian_t minAngle, + wpi::units::radian_t maxAngle, bool simulateGravity, + wpi::units::radian_t startingAngle, const std::array& measurementStdDevs = {0.0, 0.0}); @@ -74,7 +74,7 @@ class SingleJointedArmSim : public LinearSystemSim<2, 1, 2> { * @param angle The new angle. * @param velocity The new angular velocity. */ - void SetState(units::radian_t angle, units::radians_per_second_t velocity); + void SetState(wpi::units::radian_t angle, wpi::units::radians_per_second_t velocity); /** * Returns whether the arm would hit the lower limit. @@ -82,7 +82,7 @@ class SingleJointedArmSim : public LinearSystemSim<2, 1, 2> { * @param armAngle The arm height. * @return Whether the arm would hit the lower limit. */ - bool WouldHitLowerLimit(units::radian_t armAngle) const; + bool WouldHitLowerLimit(wpi::units::radian_t armAngle) const; /** * Returns whether the arm would hit the upper limit. @@ -90,7 +90,7 @@ class SingleJointedArmSim : public LinearSystemSim<2, 1, 2> { * @param armAngle The arm height. * @return Whether the arm would hit the upper limit. */ - bool WouldHitUpperLimit(units::radian_t armAngle) const; + bool WouldHitUpperLimit(wpi::units::radian_t armAngle) const; /** * Returns whether the arm has hit the lower limit. @@ -111,28 +111,28 @@ class SingleJointedArmSim : public LinearSystemSim<2, 1, 2> { * * @return The current arm angle. */ - units::radian_t GetAngle() const; + wpi::units::radian_t GetAngle() const; /** * Returns the current arm velocity. * * @return The current arm velocity. */ - units::radians_per_second_t GetVelocity() const; + wpi::units::radians_per_second_t GetVelocity() const; /** * Returns the arm current draw. * * @return The arm current draw. */ - units::ampere_t GetCurrentDraw() const; + wpi::units::ampere_t GetCurrentDraw() const; /** * Sets the input voltage for the arm. * * @param voltage The input voltage. */ - void SetInputVoltage(units::volt_t voltage); + void SetInputVoltage(wpi::units::volt_t voltage); /** * Calculates a rough estimate of the moment of inertia of an arm given its @@ -143,8 +143,8 @@ class SingleJointedArmSim : public LinearSystemSim<2, 1, 2> { * * @return The calculated moment of inertia. */ - static constexpr units::kilogram_square_meter_t EstimateMOI( - units::meter_t length, units::kilogram_t mass) { + static constexpr wpi::units::kilogram_square_meter_t EstimateMOI( + wpi::units::meter_t length, wpi::units::kilogram_t mass) { return 1.0 / 3.0 * mass * length * length; } @@ -156,15 +156,15 @@ class SingleJointedArmSim : public LinearSystemSim<2, 1, 2> { * @param u The system inputs (voltage). * @param dt The time difference between controller updates. */ - Vectord<2> UpdateX(const Vectord<2>& currentXhat, const Vectord<1>& u, - units::second_t dt) override; + wpi::math::Vectord<2> UpdateX(const wpi::math::Vectord<2>& currentXhat, const wpi::math::Vectord<1>& u, + wpi::units::second_t dt) override; private: - units::meter_t m_armLen; - units::radian_t m_minAngle; - units::radian_t m_maxAngle; - const DCMotor m_gearbox; + wpi::units::meter_t m_armLen; + wpi::units::radian_t m_minAngle; + wpi::units::radian_t m_maxAngle; + const wpi::math::DCMotor m_gearbox; double m_gearing; bool m_simulateGravity; }; -} // namespace frc::sim +} // namespace wpi::sim diff --git a/wpilibc/src/main/native/include/wpi/simulation/SolenoidSim.hpp b/wpilibc/src/main/native/include/wpi/simulation/SolenoidSim.hpp index 8cb158bfc5..dfcda23d0d 100644 --- a/wpilibc/src/main/native/include/wpi/simulation/SolenoidSim.hpp +++ b/wpilibc/src/main/native/include/wpi/simulation/SolenoidSim.hpp @@ -9,7 +9,7 @@ #include "wpi/hardware/pneumatic/PneumaticsModuleType.hpp" #include "wpi/simulation/PneumaticsBaseSim.hpp" -namespace frc::sim { +namespace wpi::sim { class SolenoidSim { public: @@ -41,4 +41,4 @@ class SolenoidSim { int m_channel; }; -} // namespace frc::sim +} // namespace wpi::sim diff --git a/wpilibc/src/main/native/include/wpi/smartdashboard/Field2d.hpp b/wpilibc/src/main/native/include/wpi/smartdashboard/Field2d.hpp index a5f2334b05..ecd564b109 100644 --- a/wpilibc/src/main/native/include/wpi/smartdashboard/Field2d.hpp +++ b/wpilibc/src/main/native/include/wpi/smartdashboard/Field2d.hpp @@ -18,7 +18,7 @@ #include "wpi/util/mutex.hpp" #include "wpi/util/sendable/SendableHelper.hpp" -namespace frc { +namespace wpi { /** * 2D representation of game field for dashboards. @@ -38,7 +38,7 @@ namespace frc { * also be shown by using the GetObject() function. Other objects can * also have multiple poses (which will show the object at multiple locations). */ -class Field2d : public nt::NTSendable, public wpi::SendableHelper { +class Field2d : public wpi::nt::NTSendable, public wpi::util::SendableHelper { public: using Entry = size_t; @@ -52,7 +52,7 @@ class Field2d : public nt::NTSendable, public wpi::SendableHelper { * * @param pose 2D pose */ - void SetRobotPose(const Pose2d& pose); + void SetRobotPose(const wpi::math::Pose2d& pose); /** * Set the robot pose from x, y, and rotation. @@ -61,14 +61,14 @@ class Field2d : public nt::NTSendable, public wpi::SendableHelper { * @param y Y location * @param rotation rotation */ - void SetRobotPose(units::meter_t x, units::meter_t y, Rotation2d rotation); + void SetRobotPose(wpi::units::meter_t x, wpi::units::meter_t y, wpi::math::Rotation2d rotation); /** * Get the robot pose. * * @return 2D pose */ - Pose2d GetRobotPose() const; + wpi::math::Pose2d GetRobotPose() const; /** * Get or create a field object. @@ -84,13 +84,13 @@ class Field2d : public nt::NTSendable, public wpi::SendableHelper { */ FieldObject2d* GetRobotObject(); - void InitSendable(nt::NTSendableBuilder& builder) override; + void InitSendable(wpi::nt::NTSendableBuilder& builder) override; private: - std::shared_ptr m_table; + std::shared_ptr m_table; - mutable wpi::mutex m_mutex; + mutable wpi::util::mutex m_mutex; std::vector> m_objects; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/smartdashboard/FieldObject2d.hpp b/wpilibc/src/main/native/include/wpi/smartdashboard/FieldObject2d.hpp index 5df248590b..47ab8a0fc2 100644 --- a/wpilibc/src/main/native/include/wpi/smartdashboard/FieldObject2d.hpp +++ b/wpilibc/src/main/native/include/wpi/smartdashboard/FieldObject2d.hpp @@ -17,10 +17,10 @@ #include "wpi/util/SmallVector.hpp" #include "wpi/util/mutex.hpp" -namespace frc { +namespace wpi { class Field2d; -class Trajectory; +class wpi::math::Trajectory; /** * Game field object on a Field2d. @@ -40,7 +40,7 @@ class FieldObject2d { * * @param pose 2D pose */ - void SetPose(const Pose2d& pose); + void SetPose(const wpi::math::Pose2d& pose); /** * Set the pose from x, y, and rotation. @@ -49,14 +49,14 @@ class FieldObject2d { * @param y Y location * @param rotation rotation */ - void SetPose(units::meter_t x, units::meter_t y, Rotation2d rotation); + void SetPose(wpi::units::meter_t x, wpi::units::meter_t y, wpi::math::Rotation2d rotation); /** * Get the pose. * * @return 2D pose, or 0,0,0 if unknown / does not exist */ - Pose2d GetPose() const; + wpi::math::Pose2d GetPose() const; /** * Set multiple poses from an array of Pose objects. @@ -64,7 +64,7 @@ class FieldObject2d { * * @param poses array of 2D poses */ - void SetPoses(std::span poses); + void SetPoses(std::span poses); /** * Set multiple poses from an array of Pose objects. @@ -72,38 +72,38 @@ class FieldObject2d { * * @param poses array of 2D poses */ - void SetPoses(std::initializer_list poses); + void SetPoses(std::initializer_list poses); /** * Sets poses from a trajectory. * * @param trajectory The trajectory from which poses should be added. */ - void SetTrajectory(const Trajectory& trajectory); + void SetTrajectory(const wpi::math::Trajectory& trajectory); /** * Get multiple poses. * * @return vector of 2D poses */ - std::vector GetPoses() const; + std::vector GetPoses() const; /** * Get multiple poses. * - * @param out output SmallVector to hold 2D poses - * @return span referring to output SmallVector + * @param out output wpi::util::SmallVector to hold 2D poses + * @return span referring to output wpi::util::SmallVector */ - std::span GetPoses(wpi::SmallVectorImpl& out) const; + std::span GetPoses(wpi::util::SmallVectorImpl& out) const; private: void UpdateEntry(bool setDefault = false); void UpdateFromEntry() const; - mutable wpi::mutex m_mutex; + mutable wpi::util::mutex m_mutex; std::string m_name; - nt::DoubleArrayEntry m_entry; - mutable wpi::SmallVector m_poses; + wpi::nt::DoubleArrayEntry m_entry; + mutable wpi::util::SmallVector m_poses; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/smartdashboard/ListenerExecutor.hpp b/wpilibc/src/main/native/include/wpi/smartdashboard/ListenerExecutor.hpp index da2f022615..930ad96eb0 100644 --- a/wpilibc/src/main/native/include/wpi/smartdashboard/ListenerExecutor.hpp +++ b/wpilibc/src/main/native/include/wpi/smartdashboard/ListenerExecutor.hpp @@ -9,7 +9,7 @@ #include "wpi/util/mutex.hpp" -namespace frc::detail { +namespace wpi::detail { /** * An executor for running listener tasks posted by Sendable listeners * synchronously from the main application thread. @@ -33,6 +33,6 @@ class ListenerExecutor { private: std::vector> m_tasks; std::vector> m_runningTasks; - wpi::mutex m_lock; + wpi::util::mutex m_lock; }; -} // namespace frc::detail +} // namespace wpi::detail diff --git a/wpilibc/src/main/native/include/wpi/smartdashboard/Mechanism2d.hpp b/wpilibc/src/main/native/include/wpi/smartdashboard/Mechanism2d.hpp index c6f276c976..53cf37455d 100644 --- a/wpilibc/src/main/native/include/wpi/smartdashboard/Mechanism2d.hpp +++ b/wpilibc/src/main/native/include/wpi/smartdashboard/Mechanism2d.hpp @@ -17,7 +17,7 @@ #include "wpi/util/mutex.hpp" #include "wpi/util/sendable/SendableHelper.hpp" -namespace frc { +namespace wpi { /** * Visual 2D representation of arms, elevators, and general mechanisms through @@ -38,8 +38,8 @@ namespace frc { * @see MechanismLigament2d * @see MechanismRoot2d */ -class Mechanism2d : public nt::NTSendable, - public wpi::SendableHelper { +class Mechanism2d : public wpi::nt::NTSendable, + public wpi::util::SendableHelper { public: /** * Create a new Mechanism2d with the given dimensions and background color. @@ -75,16 +75,16 @@ class Mechanism2d : public nt::NTSendable, */ void SetBackgroundColor(const Color8Bit& color); - void InitSendable(nt::NTSendableBuilder& builder) override; + void InitSendable(wpi::nt::NTSendableBuilder& builder) override; private: double m_width; double m_height; std::string m_color; - mutable wpi::mutex m_mutex; - std::shared_ptr m_table; - wpi::StringMap m_roots; - nt::DoubleArrayPublisher m_dimsPub; - nt::StringPublisher m_colorPub; + mutable wpi::util::mutex m_mutex; + std::shared_ptr m_table; + wpi::util::StringMap m_roots; + wpi::nt::DoubleArrayPublisher m_dimsPub; + wpi::nt::StringPublisher m_colorPub; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/smartdashboard/MechanismLigament2d.hpp b/wpilibc/src/main/native/include/wpi/smartdashboard/MechanismLigament2d.hpp index a5f4bbc813..c980601361 100644 --- a/wpilibc/src/main/native/include/wpi/smartdashboard/MechanismLigament2d.hpp +++ b/wpilibc/src/main/native/include/wpi/smartdashboard/MechanismLigament2d.hpp @@ -13,7 +13,7 @@ #include "wpi/units/angle.hpp" #include "wpi/util/Color8Bit.hpp" -namespace frc { +namespace wpi { /** * Ligament node on a Mechanism2d. @@ -26,8 +26,8 @@ namespace frc { class MechanismLigament2d : public MechanismObject2d { public: MechanismLigament2d(std::string_view name, double length, - units::degree_t angle, double lineWidth = 6, - const frc::Color8Bit& color = {235, 137, 52}); + wpi::units::degree_t angle, double lineWidth = 6, + const wpi::Color8Bit& color = {235, 137, 52}); /** * Set the ligament color. @@ -62,7 +62,7 @@ class MechanismLigament2d : public MechanismObject2d { * * @param angle the angle */ - void SetAngle(units::degree_t angle); + void SetAngle(wpi::units::degree_t angle); /** * Get the ligament's angle relative to its parent. @@ -86,17 +86,17 @@ class MechanismLigament2d : public MechanismObject2d { double GetLineWeight(); protected: - void UpdateEntries(std::shared_ptr table) override; + void UpdateEntries(std::shared_ptr table) override; private: - nt::StringPublisher m_typePub; + wpi::nt::StringPublisher m_typePub; double m_length; - nt::DoubleEntry m_lengthEntry; + wpi::nt::DoubleEntry m_lengthEntry; double m_angle; - nt::DoubleEntry m_angleEntry; + wpi::nt::DoubleEntry m_angleEntry; double m_weight; - nt::DoubleEntry m_weightEntry; + wpi::nt::DoubleEntry m_weightEntry; char m_color[10]; - nt::StringEntry m_colorEntry; + wpi::nt::StringEntry m_colorEntry; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/smartdashboard/MechanismObject2d.hpp b/wpilibc/src/main/native/include/wpi/smartdashboard/MechanismObject2d.hpp index c63bde18a9..ccee666523 100644 --- a/wpilibc/src/main/native/include/wpi/smartdashboard/MechanismObject2d.hpp +++ b/wpilibc/src/main/native/include/wpi/smartdashboard/MechanismObject2d.hpp @@ -15,7 +15,7 @@ #include "wpi/system/Errors.hpp" #include "wpi/util/StringMap.hpp" -namespace frc { +namespace wpi { /** * Common base class for all Mechanism2d node types. @@ -38,9 +38,9 @@ class MechanismObject2d { * * @param table the new table. */ - virtual void UpdateEntries(std::shared_ptr table) = 0; + virtual void UpdateEntries(std::shared_ptr table) = 0; - mutable wpi::mutex m_mutex; + mutable wpi::util::mutex m_mutex; public: virtual ~MechanismObject2d() = default; @@ -82,8 +82,8 @@ class MechanismObject2d { private: std::string m_name; - wpi::StringMap> m_objects; - std::shared_ptr m_table; - void Update(std::shared_ptr table); + wpi::util::StringMap> m_objects; + std::shared_ptr m_table; + void Update(std::shared_ptr table); }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/smartdashboard/MechanismRoot2d.hpp b/wpilibc/src/main/native/include/wpi/smartdashboard/MechanismRoot2d.hpp index 7c14eb0678..d7c5748183 100644 --- a/wpilibc/src/main/native/include/wpi/smartdashboard/MechanismRoot2d.hpp +++ b/wpilibc/src/main/native/include/wpi/smartdashboard/MechanismRoot2d.hpp @@ -10,7 +10,7 @@ #include "wpi/nt/DoubleTopic.hpp" #include "wpi/smartdashboard/MechanismObject2d.hpp" -namespace frc { +namespace wpi { /** * Root Mechanism2d node. @@ -43,11 +43,11 @@ class MechanismRoot2d : private MechanismObject2d { using MechanismObject2d::Append; private: - void UpdateEntries(std::shared_ptr table) override; + void UpdateEntries(std::shared_ptr table) override; inline void Flush(); double m_x; double m_y; - nt::DoublePublisher m_xPub; - nt::DoublePublisher m_yPub; + wpi::nt::DoublePublisher m_xPub; + wpi::nt::DoublePublisher m_yPub; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/smartdashboard/SendableBuilderImpl.hpp b/wpilibc/src/main/native/include/wpi/smartdashboard/SendableBuilderImpl.hpp index bfd50bd4a6..7d913498af 100644 --- a/wpilibc/src/main/native/include/wpi/smartdashboard/SendableBuilderImpl.hpp +++ b/wpilibc/src/main/native/include/wpi/smartdashboard/SendableBuilderImpl.hpp @@ -19,12 +19,12 @@ #include "wpi/util/FunctionExtras.hpp" #include "wpi/util/SmallVector.hpp" -namespace frc { +namespace wpi { /** * Implementation detail for SendableBuilder. */ -class SendableBuilderImpl : public nt::NTSendableBuilder { +class SendableBuilderImpl : public wpi::nt::NTSendableBuilder { public: SendableBuilderImpl() = default; ~SendableBuilderImpl() override = default; @@ -37,13 +37,13 @@ class SendableBuilderImpl : public nt::NTSendableBuilder { * called. * @param table Network table */ - void SetTable(std::shared_ptr table); + void SetTable(std::shared_ptr table); /** * Get the network table. * @return The network table */ - std::shared_ptr GetTable() override; + std::shared_ptr GetTable() override; /** * Return whether this sendable has an associated table. @@ -80,8 +80,8 @@ class SendableBuilderImpl : public nt::NTSendableBuilder { void SetSmartDashboardType(std::string_view type) override; void SetActuator(bool value) override; - void SetUpdateTable(wpi::unique_function func) override; - nt::Topic GetTopic(std::string_view key) override; + void SetUpdateTable(wpi::util::unique_function func) override; + wpi::nt::Topic GetTopic(std::string_view key) override; void AddBooleanProperty(std::string_view key, std::function getter, std::function setter) override; @@ -155,44 +155,44 @@ class SendableBuilderImpl : public nt::NTSendableBuilder { void AddSmallStringProperty( std::string_view key, - std::function& buf)> getter, + std::function& buf)> getter, std::function setter) override; void AddSmallBooleanArrayProperty( std::string_view key, - std::function(wpi::SmallVectorImpl& buf)> + std::function(wpi::util::SmallVectorImpl& buf)> getter, std::function)> setter) override; void AddSmallIntegerArrayProperty( std::string_view key, std::function< - std::span(wpi::SmallVectorImpl& buf)> + std::span(wpi::util::SmallVectorImpl& buf)> getter, std::function)> setter) override; void AddSmallFloatArrayProperty( std::string_view key, - std::function(wpi::SmallVectorImpl& buf)> + std::function(wpi::util::SmallVectorImpl& buf)> getter, std::function)> setter) override; void AddSmallDoubleArrayProperty( std::string_view key, - std::function(wpi::SmallVectorImpl& buf)> + std::function(wpi::util::SmallVectorImpl& buf)> getter, std::function)> setter) override; void AddSmallStringArrayProperty( std::string_view key, std::function< - std::span(wpi::SmallVectorImpl& buf)> + std::span(wpi::util::SmallVectorImpl& buf)> getter, std::function)> setter) override; void AddSmallRawProperty( std::string_view key, std::string_view typeString, - std::function(wpi::SmallVectorImpl& buf)> + std::function(wpi::util::SmallVectorImpl& buf)> getter, std::function)> setter) override; @@ -225,14 +225,14 @@ class SendableBuilderImpl : public nt::NTSendableBuilder { void AddSmallPropertyImpl(Topic topic, Getter getter, Setter setter); std::vector> m_properties; - std::vector> m_updateTables; - std::shared_ptr m_table; + std::vector> m_updateTables; + std::shared_ptr m_table; bool m_controllable = false; bool m_actuator = false; - nt::BooleanPublisher m_controllablePublisher; - nt::StringPublisher m_typePublisher; - nt::BooleanPublisher m_actuatorPublisher; + wpi::nt::BooleanPublisher m_controllablePublisher; + wpi::nt::StringPublisher m_typePublisher; + wpi::nt::BooleanPublisher m_actuatorPublisher; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/smartdashboard/SendableChooser.hpp b/wpilibc/src/main/native/include/wpi/smartdashboard/SendableChooser.hpp index 92e20e8e0a..20e44e48cf 100644 --- a/wpilibc/src/main/native/include/wpi/smartdashboard/SendableChooser.hpp +++ b/wpilibc/src/main/native/include/wpi/smartdashboard/SendableChooser.hpp @@ -17,7 +17,7 @@ #include "wpi/util/StringMap.hpp" #include "wpi/util/sendable/SendableBuilder.hpp" -namespace frc { +namespace wpi { /** * The SendableChooser class is a useful tool for presenting a selection of @@ -35,7 +35,7 @@ namespace frc { template requires std::copy_constructible && std::default_initializable class SendableChooser : public SendableChooserBase { - wpi::StringMap m_choices; + wpi::util::StringMap m_choices; std::function m_listener; template static U _unwrap_smart_ptr(const U& value) { @@ -123,7 +123,7 @@ class SendableChooser : public SendableChooserBase { m_listener = listener; } - void InitSendable(wpi::SendableBuilder& builder) override { + void InitSendable(wpi::util::SendableBuilder& builder) override { builder.SetSmartDashboardType("String Chooser"); builder.PublishConstInteger(kInstance, m_instance); builder.AddStringArrayProperty( @@ -138,13 +138,13 @@ class SendableChooser : public SendableChooserBase { nullptr); builder.AddSmallStringProperty( kDefault, - [=, this](wpi::SmallVectorImpl&) -> std::string_view { + [=, this](wpi::util::SmallVectorImpl&) -> std::string_view { return m_defaultChoice; }, nullptr); builder.AddSmallStringProperty( kActive, - [=, this](wpi::SmallVectorImpl& buf) -> std::string_view { + [=, this](wpi::util::SmallVectorImpl& buf) -> std::string_view { std::scoped_lock lock(m_mutex); if (m_haveSelected) { buf.assign(m_selected.begin(), m_selected.end()); @@ -175,4 +175,4 @@ class SendableChooser : public SendableChooserBase { } }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/smartdashboard/SendableChooserBase.hpp b/wpilibc/src/main/native/include/wpi/smartdashboard/SendableChooserBase.hpp index 23657f6283..292634847e 100644 --- a/wpilibc/src/main/native/include/wpi/smartdashboard/SendableChooserBase.hpp +++ b/wpilibc/src/main/native/include/wpi/smartdashboard/SendableChooserBase.hpp @@ -11,7 +11,7 @@ #include "wpi/util/sendable/Sendable.hpp" #include "wpi/util/sendable/SendableHelper.hpp" -namespace frc { +namespace wpi { /** * This class is a non-template base class for SendableChooser. @@ -19,8 +19,8 @@ namespace frc { * It contains static, non-templated variables to avoid their duplication in the * template class. */ -class SendableChooserBase : public wpi::Sendable, - public wpi::SendableHelper { +class SendableChooserBase : public wpi::util::Sendable, + public wpi::util::SendableHelper { public: SendableChooserBase(); ~SendableChooserBase() override = default; @@ -38,10 +38,10 @@ class SendableChooserBase : public wpi::Sendable, std::string m_defaultChoice; std::string m_selected; bool m_haveSelected = false; - mutable wpi::mutex m_mutex; + mutable wpi::util::mutex m_mutex; int m_instance; std::string m_previousVal; static std::atomic_int s_instances; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/smartdashboard/SmartDashboard.hpp b/wpilibc/src/main/native/include/wpi/smartdashboard/SmartDashboard.hpp index b965522cf2..9b354d0630 100644 --- a/wpilibc/src/main/native/include/wpi/smartdashboard/SmartDashboard.hpp +++ b/wpilibc/src/main/native/include/wpi/smartdashboard/SmartDashboard.hpp @@ -18,7 +18,7 @@ namespace wpi { class Sendable; } // namespace wpi -namespace frc { +namespace wpi { class SmartDashboard { public: @@ -71,7 +71,7 @@ class SmartDashboard { * @param key the key * @return the entry for the key */ - static nt::NetworkTableEntry GetEntry(std::string_view key); + static wpi::nt::NetworkTableEntry GetEntry(std::string_view key); /** * Maps the specified key to the specified value in this table. @@ -85,7 +85,7 @@ class SmartDashboard { * @param key the key * @param data the value */ - static void PutData(std::string_view key, wpi::Sendable* data); + static void PutData(std::string_view key, wpi::util::Sendable* data); /** * Maps the specified key (where the key is the name of the Sendable) @@ -99,7 +99,7 @@ class SmartDashboard { * * @param value the value */ - static void PutData(wpi::Sendable* value); + static void PutData(wpi::util::Sendable* value); /** * Returns the value at the specified key. @@ -107,7 +107,7 @@ class SmartDashboard { * @param keyName the key * @return the value */ - static wpi::Sendable* GetData(std::string_view keyName); + static wpi::util::Sendable* GetData(std::string_view keyName); /** * Maps the specified key to the specified value in this table. @@ -371,7 +371,7 @@ class SmartDashboard { * @param value the value * @return False if the table key already exists with a different type */ - static bool PutValue(std::string_view keyName, const nt::Value& value); + static bool PutValue(std::string_view keyName, const wpi::nt::Value& value); /** * Set the value in the table if key does not exist. @@ -381,7 +381,7 @@ class SmartDashboard { * @returns True if the table key did not already exist, otherwise False */ static bool SetDefaultValue(std::string_view key, - const nt::Value& defaultValue); + const wpi::nt::Value& defaultValue); /** * Retrieves the complex value (such as an array) in this table into the @@ -389,7 +389,7 @@ class SmartDashboard { * * @param keyName the key */ - static nt::Value GetValue(std::string_view keyName); + static wpi::nt::Value GetValue(std::string_view keyName); /** * Posts a task from a listener to the ListenerExecutor, so that it can be run @@ -405,4 +405,4 @@ class SmartDashboard { static void UpdateValues(); }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/sysid/SysIdRoutineLog.hpp b/wpilibc/src/main/native/include/wpi/sysid/SysIdRoutineLog.hpp index 443d069455..9456ee607e 100644 --- a/wpilibc/src/main/native/include/wpi/sysid/SysIdRoutineLog.hpp +++ b/wpilibc/src/main/native/include/wpi/sysid/SysIdRoutineLog.hpp @@ -17,7 +17,7 @@ #include "wpi/units/velocity.hpp" #include "wpi/units/voltage.hpp" -namespace frc::sysid { +namespace wpi::sysid { /** * Possible state of a SysId routine. @@ -41,8 +41,8 @@ enum class State { * SysIdRoutineLog instance, with a unique log name. */ class SysIdRoutineLog { - using MotorEntries = wpi::StringMap; - using LogEntries = wpi::StringMap; + using MotorEntries = wpi::util::StringMap; + using LogEntries = wpi::util::StringMap; public: /** Logs data from a single motor during a SysIdRoutine. */ @@ -64,7 +64,7 @@ class SysIdRoutineLog { * @param voltage The voltage to record. * @return The motor log (for call chaining). */ - MotorLog& voltage(units::volt_t voltage) { + MotorLog& voltage(wpi::units::volt_t voltage) { return value("voltage", voltage.value(), voltage.name()); } @@ -74,7 +74,7 @@ class SysIdRoutineLog { * @param position The linear position to record. * @return The motor log (for call chaining). */ - MotorLog& position(units::meter_t position) { + MotorLog& position(wpi::units::meter_t position) { return value("position", position.value(), position.name()); } @@ -84,7 +84,7 @@ class SysIdRoutineLog { * @param position The angular position to record. * @return The motor log (for call chaining). */ - MotorLog& position(units::turn_t position) { + MotorLog& position(wpi::units::turn_t position) { return value("position", position.value(), position.name()); } @@ -94,7 +94,7 @@ class SysIdRoutineLog { * @param velocity The linear velocity to record. * @return The motor log (for call chaining). */ - MotorLog& velocity(units::meters_per_second_t velocity) { + MotorLog& velocity(wpi::units::meters_per_second_t velocity) { return value("velocity", velocity.value(), velocity.name()); } @@ -104,7 +104,7 @@ class SysIdRoutineLog { * @param velocity The angular velocity to record. * @return The motor log (for call chaining). */ - MotorLog& velocity(units::turns_per_second_t velocity) { + MotorLog& velocity(wpi::units::turns_per_second_t velocity) { return value("velocity", velocity.value(), velocity.name()); } @@ -116,7 +116,7 @@ class SysIdRoutineLog { * @param acceleration The linear acceleration to record. * @return The motor log (for call chaining). */ - MotorLog& acceleration(units::meters_per_second_squared_t acceleration) { + MotorLog& acceleration(wpi::units::meters_per_second_squared_t acceleration) { return value("acceleration", acceleration.value(), acceleration.name()); } @@ -128,7 +128,7 @@ class SysIdRoutineLog { * @param acceleration The angular acceleration to record. * @return The motor log (for call chaining). */ - MotorLog& acceleration(units::turns_per_second_squared_t acceleration) { + MotorLog& acceleration(wpi::units::turns_per_second_squared_t acceleration) { return value("acceleration", acceleration.value(), acceleration.name()); } @@ -140,7 +140,7 @@ class SysIdRoutineLog { * @param current The current to record. * @return The motor log (for call chaining). */ - MotorLog& current(units::ampere_t current) { + MotorLog& current(wpi::units::ampere_t current) { return value("current", current.value(), current.name()); } @@ -197,4 +197,4 @@ class SysIdRoutineLog { bool m_stateInitialized = false; wpi::log::StringLogEntry m_state; }; -} // namespace frc::sysid +} // namespace wpi::sysid diff --git a/wpilibc/src/main/native/include/wpi/system/DataLogManager.hpp b/wpilibc/src/main/native/include/wpi/system/DataLogManager.hpp index e8b30cb142..ff21b5ee94 100644 --- a/wpilibc/src/main/native/include/wpi/system/DataLogManager.hpp +++ b/wpilibc/src/main/native/include/wpi/system/DataLogManager.hpp @@ -11,7 +11,7 @@ namespace wpi::log { class DataLog; } // namespace wpi::log -namespace frc { +namespace wpi { /** * Centralized data log that provides automatic data log file management. It @@ -93,4 +93,4 @@ class DataLogManager final { static void LogConsoleOutput(bool enabled); }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/system/Errors.hpp b/wpilibc/src/main/native/include/wpi/system/Errors.hpp index d3febda277..241a4fb3ec 100644 --- a/wpilibc/src/main/native/include/wpi/system/Errors.hpp +++ b/wpilibc/src/main/native/include/wpi/system/Errors.hpp @@ -12,7 +12,7 @@ #include -namespace frc { +namespace wpi { /** * Runtime error exception. @@ -120,7 +120,7 @@ namespace warn { #include "wpi/system/WPIWarnings.mac" #undef S } // namespace warn -} // namespace frc +} // namespace wpi // C++20 relaxed the number of arguments to variadics, but Apple Clang's // warnings haven't caught up yet: https://stackoverflow.com/a/67996331 @@ -137,7 +137,7 @@ namespace warn { #define FRC_ReportError(status, format, ...) \ do { \ if ((status) != 0) { \ - ::frc::ReportError(status, __FILE__, __LINE__, __FUNCTION__, \ + ::wpi::ReportError(status, __FILE__, __LINE__, __FUNCTION__, \ format __VA_OPT__(, ) __VA_ARGS__); \ } \ } while (0) @@ -149,7 +149,7 @@ namespace warn { */ #define FRC_ReportWarning(format, ...) \ do { \ - ::frc::ReportError(::frc::warn::Warning, __FILE__, __LINE__, __FUNCTION__, \ + ::wpi::ReportError(::wpi::warn::Warning, __FILE__, __LINE__, __FUNCTION__, \ format __VA_OPT__(, ) __VA_ARGS__); \ } while (0) @@ -162,7 +162,7 @@ namespace warn { * @return runtime error object */ #define FRC_MakeError(status, format, ...) \ - ::frc::MakeError(status, __FILE__, __LINE__, __FUNCTION__, \ + ::wpi::MakeError(status, __FILE__, __LINE__, __FUNCTION__, \ format __VA_OPT__(, ) __VA_ARGS__) /** @@ -175,10 +175,10 @@ namespace warn { #define FRC_CheckErrorStatus(status, format, ...) \ do { \ if ((status) < 0) { \ - throw ::frc::MakeError(status, __FILE__, __LINE__, __FUNCTION__, \ + throw ::wpi::MakeError(status, __FILE__, __LINE__, __FUNCTION__, \ format __VA_OPT__(, ) __VA_ARGS__); \ } else if ((status) > 0) { \ - ::frc::ReportError(status, __FILE__, __LINE__, __FUNCTION__, \ + ::wpi::ReportError(status, __FILE__, __LINE__, __FUNCTION__, \ format __VA_OPT__(, ) __VA_ARGS__); \ } \ } while (0) @@ -186,7 +186,7 @@ namespace warn { #define FRC_AssertMessage(condition, format, ...) \ do { \ if (!(condition)) { \ - throw ::frc::MakeError(::frc::err::AssertionFailure, __FILE__, __LINE__, \ + throw ::wpi::MakeError(::wpi::err::AssertionFailure, __FILE__, __LINE__, \ __FUNCTION__, format __VA_OPT__(, ) __VA_ARGS__); \ } \ } while (0) diff --git a/wpilibc/src/main/native/include/wpi/system/Filesystem.hpp b/wpilibc/src/main/native/include/wpi/system/Filesystem.hpp index 59a3415931..fd477caf8e 100644 --- a/wpilibc/src/main/native/include/wpi/system/Filesystem.hpp +++ b/wpilibc/src/main/native/include/wpi/system/Filesystem.hpp @@ -7,7 +7,7 @@ #include /** WPILib FileSystem namespace */ -namespace frc::filesystem { +namespace wpi::filesystem { /** * Obtains the current working path that the program was launched with. @@ -36,4 +36,4 @@ std::string GetOperatingDirectory(); */ std::string GetDeployDirectory(); -} // namespace frc::filesystem +} // namespace wpi::filesystem diff --git a/wpilibc/src/main/native/include/wpi/system/Notifier.hpp b/wpilibc/src/main/native/include/wpi/system/Notifier.hpp index e5e6caf5b6..14f25d067e 100644 --- a/wpilibc/src/main/native/include/wpi/system/Notifier.hpp +++ b/wpilibc/src/main/native/include/wpi/system/Notifier.hpp @@ -18,7 +18,7 @@ #include "wpi/units/time.hpp" #include "wpi/util/mutex.hpp" -namespace frc { +namespace wpi { /** * Notifiers run a user-provided callback function on a separate thread. @@ -95,7 +95,7 @@ class Notifier { * * @param delay Time to wait before the callback is called. */ - void StartSingle(units::second_t delay); + void StartSingle(wpi::units::second_t delay); /** * Run the callback periodically with the given period. @@ -106,7 +106,7 @@ class Notifier { * @param period Period after which to call the callback starting one * period after the call to this method. */ - void StartPeriodic(units::second_t period); + void StartPeriodic(wpi::units::second_t period); /** * Run the callback periodically with the given frequency. @@ -117,7 +117,7 @@ class Notifier { * @param frequency Frequency after which to call the callback starting one * period after the call to this method. */ - void StartPeriodic(units::hertz_t frequency); + void StartPeriodic(wpi::units::hertz_t frequency); /** * Stop further callback invocations. @@ -164,7 +164,7 @@ class Notifier { std::thread m_thread; // The mutex held while updating process information - wpi::mutex m_processMutex; + wpi::util::mutex m_processMutex; // HAL handle (atomic for proper destruction) std::atomic m_notifier{0}; @@ -174,14 +174,14 @@ class Notifier { // The time at which the callback should be called. Has the same zero as // Timer::GetFPGATimestamp(). - units::second_t m_expirationTime = 0_s; + wpi::units::second_t m_expirationTime = 0_s; // If periodic, stores the callback period; if single, stores the time until // the callback call. - units::second_t m_period = 0_s; + wpi::units::second_t m_period = 0_s; // True if the callback is periodic bool m_periodic = false; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/system/Resource.hpp b/wpilibc/src/main/native/include/wpi/system/Resource.hpp index 6421c3c985..8a356bbf13 100644 --- a/wpilibc/src/main/native/include/wpi/system/Resource.hpp +++ b/wpilibc/src/main/native/include/wpi/system/Resource.hpp @@ -12,7 +12,7 @@ #include "wpi/util/mutex.hpp" -namespace frc { +namespace wpi { /** * The Resource class is a convenient way to track allocated resources. @@ -80,9 +80,9 @@ class [[deprecated("Use the HandleResource classes instead")]] Resource { private: std::vector m_isAllocated; - wpi::mutex m_allocateMutex; + wpi::util::mutex m_allocateMutex; - static wpi::mutex m_createMutex; + static wpi::util::mutex m_createMutex; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/system/RobotController.hpp b/wpilibc/src/main/native/include/wpi/system/RobotController.hpp index 4dab91ace4..10f3f7eb6a 100644 --- a/wpilibc/src/main/native/include/wpi/system/RobotController.hpp +++ b/wpilibc/src/main/native/include/wpi/system/RobotController.hpp @@ -12,7 +12,7 @@ #include "wpi/units/temperature.hpp" #include "wpi/units/voltage.hpp" -namespace frc { +namespace wpi { struct CANStatus { float percentBusUtilization; @@ -82,7 +82,7 @@ class RobotController { * * @return The battery voltage in Volts. */ - static units::volt_t GetBatteryVoltage(); + static wpi::units::volt_t GetBatteryVoltage(); /** * Check if the FPGA outputs are enabled. @@ -175,7 +175,7 @@ class RobotController { * * @return The brownout voltage */ - static units::volt_t GetBrownoutVoltage(); + static wpi::units::volt_t GetBrownoutVoltage(); /** * Set the voltage the roboRIO will brownout and disable all outputs. @@ -185,14 +185,14 @@ class RobotController { * * @param brownoutVoltage The brownout voltage */ - static void SetBrownoutVoltage(units::volt_t brownoutVoltage); + static void SetBrownoutVoltage(wpi::units::volt_t brownoutVoltage); /** * Get the current CPU temperature. * * @return current CPU temperature */ - static units::celsius_t GetCPUTemp(); + static wpi::units::celsius_t GetCPUTemp(); /** * Get the current status of the CAN bus. @@ -206,4 +206,4 @@ class RobotController { static std::function m_timeSource; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/system/RuntimeType.hpp b/wpilibc/src/main/native/include/wpi/system/RuntimeType.hpp index 8705020f9c..6e1c2131b2 100644 --- a/wpilibc/src/main/native/include/wpi/system/RuntimeType.hpp +++ b/wpilibc/src/main/native/include/wpi/system/RuntimeType.hpp @@ -4,7 +4,7 @@ #pragma once -namespace frc { +namespace wpi { /** * Runtime type. */ @@ -17,4 +17,4 @@ enum RuntimeType { kSimulation, kSystemCore }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/system/ScopedTracer.hpp b/wpilibc/src/main/native/include/wpi/system/ScopedTracer.hpp index ec6670b60a..18dfac3a94 100644 --- a/wpilibc/src/main/native/include/wpi/system/ScopedTracer.hpp +++ b/wpilibc/src/main/native/include/wpi/system/ScopedTracer.hpp @@ -9,17 +9,17 @@ #include "wpi/system/Tracer.hpp" -namespace wpi { +namespace wpi::util { class raw_ostream; } // namespace wpi -namespace frc { +namespace wpi { /** * A class for keeping track of how much time it takes for different * parts of code to execute. This class uses RAII, meaning you simply * need to create an instance at the top of the block you are timing. After the * block finishes execution (i.e. when the ScopedTracer instance gets - * destroyed), the epoch is printed to the provided raw_ostream. + * destroyed), the epoch is printed to the provided wpi::util::raw_ostream. */ class ScopedTracer { public: @@ -27,9 +27,9 @@ class ScopedTracer { * Constructs a ScopedTracer instance. * * @param name The name of the epoch. - * @param os A reference to the raw_ostream to print data to. + * @param os A reference to the wpi::util::raw_ostream to print data to. */ - ScopedTracer(std::string_view name, wpi::raw_ostream& os); + ScopedTracer(std::string_view name, wpi::util::raw_ostream& os); ~ScopedTracer(); ScopedTracer(const ScopedTracer&) = delete; @@ -38,6 +38,6 @@ class ScopedTracer { private: Tracer m_tracer; std::string m_name; - wpi::raw_ostream& m_os; + wpi::util::raw_ostream& m_os; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/system/SystemServer.hpp b/wpilibc/src/main/native/include/wpi/system/SystemServer.hpp index 0d07b80c58..a7d4bec632 100644 --- a/wpilibc/src/main/native/include/wpi/system/SystemServer.hpp +++ b/wpilibc/src/main/native/include/wpi/system/SystemServer.hpp @@ -6,13 +6,13 @@ #include "wpi/nt/NetworkTableInstance.hpp" -namespace frc { +namespace wpi { class SystemServer { public: SystemServer() = delete; - static nt::NetworkTableInstance GetSystemServer(); + static wpi::nt::NetworkTableInstance GetSystemServer(); }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/system/Threads.hpp b/wpilibc/src/main/native/include/wpi/system/Threads.hpp index 5822670733..b434a9a401 100644 --- a/wpilibc/src/main/native/include/wpi/system/Threads.hpp +++ b/wpilibc/src/main/native/include/wpi/system/Threads.hpp @@ -6,7 +6,7 @@ #include -namespace frc { +namespace wpi { /** * Get the thread priority for the specified thread. @@ -54,4 +54,4 @@ bool SetThreadPriority(std::thread& thread, bool realTime, int priority); */ bool SetCurrentThreadPriority(bool realTime, int priority); -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/system/Timer.hpp b/wpilibc/src/main/native/include/wpi/system/Timer.hpp index a4ce3e8c65..03820002e1 100644 --- a/wpilibc/src/main/native/include/wpi/system/Timer.hpp +++ b/wpilibc/src/main/native/include/wpi/system/Timer.hpp @@ -6,7 +6,7 @@ #include "wpi/units/time.hpp" -namespace frc { +namespace wpi { /** * Pause the task for a specified time. @@ -18,19 +18,19 @@ namespace frc { * * @param seconds Length of time to pause, in seconds. */ -void Wait(units::second_t seconds); +void Wait(wpi::units::second_t seconds); /** * @brief Gives real-time clock system time with nanosecond resolution * @return The time, just in case you want the robot to start autonomous at 8pm * on Saturday. */ -units::second_t GetTime(); +wpi::units::second_t GetTime(); /** * A timer class. * - * Note that if the user calls frc::sim::RestartTiming(), they should also reset + * Note that if the user calls wpi::sim::RestartTiming(), they should also reset * the timer so Get() won't return a negative duration. */ class Timer { @@ -57,7 +57,7 @@ class Timer { * * @return Current time value for this timer in seconds */ - units::second_t Get() const; + wpi::units::second_t Get() const; /** * Reset the timer by setting the time to 0. @@ -99,7 +99,7 @@ class Timer { * @param period The period to check. * @return True if the period has passed. */ - bool HasElapsed(units::second_t period) const; + bool HasElapsed(wpi::units::second_t period) const; /** * Check if the period specified has passed and if it has, advance the start @@ -109,7 +109,7 @@ class Timer { * @param period The period to check for. * @return True if the period has passed. */ - bool AdvanceIfElapsed(units::second_t period); + bool AdvanceIfElapsed(wpi::units::second_t period); /** * Whether the timer is currently running. @@ -126,7 +126,7 @@ class Timer { * * @returns Robot running time in seconds. */ - static units::second_t GetTimestamp(); + static wpi::units::second_t GetTimestamp(); /** * Return the FPGA system clock time in seconds. @@ -136,7 +136,7 @@ class Timer { * * @returns Robot running time in seconds. */ - static units::second_t GetFPGATimestamp(); + static wpi::units::second_t GetFPGATimestamp(); /** * Return the approximate match time. @@ -153,12 +153,12 @@ class Timer { * * @return Time remaining in current match period (auto or teleop) */ - static units::second_t GetMatchTime(); + static wpi::units::second_t GetMatchTime(); private: - units::second_t m_startTime = 0_s; - units::second_t m_accumulatedTime = 0_s; + wpi::units::second_t m_startTime = 0_s; + wpi::units::second_t m_accumulatedTime = 0_s; bool m_running = false; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/system/Tracer.hpp b/wpilibc/src/main/native/include/wpi/system/Tracer.hpp index 2601e52e05..be139a289e 100644 --- a/wpilibc/src/main/native/include/wpi/system/Tracer.hpp +++ b/wpilibc/src/main/native/include/wpi/system/Tracer.hpp @@ -10,11 +10,11 @@ #include "wpi/hal/cpp/fpga_clock.h" #include "wpi/util/StringMap.hpp" -namespace wpi { +namespace wpi::util { class raw_ostream; } // namespace wpi -namespace frc { +namespace wpi { /** * A class for keeping track of how much time it takes for different parts of * code to execute. This is done with epochs, that are added to calls to @@ -60,14 +60,14 @@ class Tracer { * * @param os output stream */ - void PrintEpochs(wpi::raw_ostream& os); + void PrintEpochs(wpi::util::raw_ostream& os); private: static constexpr std::chrono::milliseconds kMinPrintPeriod{1000}; - hal::fpga_clock::time_point m_startTime; - hal::fpga_clock::time_point m_lastEpochsPrintTime = hal::fpga_clock::epoch(); + wpi::hal::fpga_clock::time_point m_startTime; + wpi::hal::fpga_clock::time_point m_lastEpochsPrintTime = wpi::hal::fpga_clock::epoch(); - wpi::StringMap m_epochs; + wpi::util::StringMap m_epochs; }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/system/Watchdog.hpp b/wpilibc/src/main/native/include/wpi/system/Watchdog.hpp index 252767c2c3..bd27ad2f9d 100644 --- a/wpilibc/src/main/native/include/wpi/system/Watchdog.hpp +++ b/wpilibc/src/main/native/include/wpi/system/Watchdog.hpp @@ -11,7 +11,7 @@ #include "wpi/system/Tracer.hpp" #include "wpi/units/time.hpp" -namespace frc { +namespace wpi { /** * A class that's a wrapper around a watchdog timer. @@ -31,10 +31,10 @@ class Watchdog { * resolution. * @param callback This function is called when the timeout expires. */ - Watchdog(units::second_t timeout, std::function callback); + Watchdog(wpi::units::second_t timeout, std::function callback); template - Watchdog(units::second_t timeout, Callable&& f, Arg&& arg, Args&&... args) + Watchdog(wpi::units::second_t timeout, Callable&& f, Arg&& arg, Args&&... args) : Watchdog(timeout, std::bind(std::forward(f), std::forward(arg), std::forward(args)...)) {} @@ -47,7 +47,7 @@ class Watchdog { /** * Returns the time since the watchdog was last fed. */ - units::second_t GetTime() const; + wpi::units::second_t GetTime() const; /** * Sets the watchdog's timeout. @@ -55,12 +55,12 @@ class Watchdog { * @param timeout The watchdog's timeout in seconds with microsecond * resolution. */ - void SetTimeout(units::second_t timeout); + void SetTimeout(wpi::units::second_t timeout); /** * Returns the watchdog's timeout. */ - units::second_t GetTimeout() const; + wpi::units::second_t GetTimeout() const; /** * Returns true if the watchdog timer has expired. @@ -113,11 +113,11 @@ class Watchdog { // Used for timeout print rate-limiting static constexpr auto kMinPrintPeriod = 1_s; - units::second_t m_startTime = 0_s; - units::second_t m_timeout; - units::second_t m_expirationTime = 0_s; + wpi::units::second_t m_startTime = 0_s; + wpi::units::second_t m_timeout; + wpi::units::second_t m_expirationTime = 0_s; std::function m_callback; - units::second_t m_lastTimeoutPrintTime = 0_s; + wpi::units::second_t m_lastTimeoutPrintTime = 0_s; Tracer m_tracer; bool m_isExpired = false; @@ -132,4 +132,4 @@ class Watchdog { static Impl* GetImpl(); }; -} // namespace frc +} // namespace wpi diff --git a/wpilibc/src/main/native/include/wpi/util/Alert.hpp b/wpilibc/src/main/native/include/wpi/util/Alert.hpp index d51eba2b76..6286413ba1 100644 --- a/wpilibc/src/main/native/include/wpi/util/Alert.hpp +++ b/wpilibc/src/main/native/include/wpi/util/Alert.hpp @@ -9,7 +9,7 @@ #include #include -namespace frc { +namespace wpi { /** * Persistent alert to be sent via NetworkTables. Alerts are tagged with a type @@ -27,7 +27,7 @@ namespace frc { * *
  * class Robot {
- *   frc::Alert alert{"Something went wrong", frc::Alert::AlertType::kWarning};
+ *   wpi::Alert alert{"Something went wrong", wpi::Alert::AlertType::kWarning};
  * }
  *
  * Robot::periodic() {
@@ -138,4 +138,4 @@ class Alert {
 
 std::string format_as(Alert::AlertType type);
 
-}  // namespace frc
+}  // namespace wpi
diff --git a/wpilibc/src/main/native/include/wpi/util/Color.hpp b/wpilibc/src/main/native/include/wpi/util/Color.hpp
index 22bd61a7d7..f1ea0f5ded 100644
--- a/wpilibc/src/main/native/include/wpi/util/Color.hpp
+++ b/wpilibc/src/main/native/include/wpi/util/Color.hpp
@@ -15,7 +15,7 @@
 #include "wpi/util/StringExtras.hpp"
 #include "wpi/util/ct_string.hpp"
 
-namespace frc {
+namespace wpi {
 
 /**
  * Represents colors that can be used with Addressable LEDs.
@@ -782,19 +782,19 @@ class Color {
    */
   explicit constexpr Color(std::string_view hexString) {
     if (hexString.length() != 7 || !hexString.starts_with("#") ||
-        !wpi::isHexDigit(hexString[1]) || !wpi::isHexDigit(hexString[2]) ||
-        !wpi::isHexDigit(hexString[3]) || !wpi::isHexDigit(hexString[4]) ||
-        !wpi::isHexDigit(hexString[5]) || !wpi::isHexDigit(hexString[6])) {
+        !wpi::util::isHexDigit(hexString[1]) || !wpi::util::isHexDigit(hexString[2]) ||
+        !wpi::util::isHexDigit(hexString[3]) || !wpi::util::isHexDigit(hexString[4]) ||
+        !wpi::util::isHexDigit(hexString[5]) || !wpi::util::isHexDigit(hexString[6])) {
       throw std::invalid_argument(
           fmt::format("Invalid hex string for Color \"{}\"", hexString));
     }
 
-    int r = wpi::hexDigitValue(hexString[1]) * 16 +
-            wpi::hexDigitValue(hexString[2]);
-    int g = wpi::hexDigitValue(hexString[3]) * 16 +
-            wpi::hexDigitValue(hexString[4]);
-    int b = wpi::hexDigitValue(hexString[5]) * 16 +
-            wpi::hexDigitValue(hexString[6]);
+    int r = wpi::util::hexDigitValue(hexString[1]) * 16 +
+            wpi::util::hexDigitValue(hexString[2]);
+    int g = wpi::util::hexDigitValue(hexString[3]) * 16 +
+            wpi::util::hexDigitValue(hexString[4]);
+    int b = wpi::util::hexDigitValue(hexString[5]) * 16 +
+            wpi::util::hexDigitValue(hexString[6]);
 
     red = r / 255.0;
     green = g / 255.0;
@@ -859,10 +859,10 @@ class Color {
     const int g = 255.0 * green;
     const int b = 255.0 * blue;
 
-    return wpi::ct_string, 7>{
-        {'#', wpi::hexdigit(r / 16), wpi::hexdigit(r % 16),
-         wpi::hexdigit(g / 16), wpi::hexdigit(g % 16), wpi::hexdigit(b / 16),
-         wpi::hexdigit(b % 16)}};
+    return wpi::util::ct_string, 7>{
+        {'#', wpi::util::hexdigit(r / 16), wpi::util::hexdigit(r % 16),
+         wpi::util::hexdigit(g / 16), wpi::util::hexdigit(g % 16), wpi::util::hexdigit(b / 16),
+         wpi::util::hexdigit(b % 16)}};
   }
 
   /// Red component (0-1).
@@ -1053,4 +1053,4 @@ inline constexpr Color Color::kWhiteSmoke{0.9607843f, 0.9607843f, 0.9607843f};
 inline constexpr Color Color::kYellow{1.0f, 1.0f, 0.0f};
 inline constexpr Color Color::kYellowGreen{0.6039216f, 0.8039216f, 0.19607843f};
 
-}  // namespace frc
+}  // namespace wpi
diff --git a/wpilibc/src/main/native/include/wpi/util/Color8Bit.hpp b/wpilibc/src/main/native/include/wpi/util/Color8Bit.hpp
index 840dc54add..09a856ea9c 100644
--- a/wpilibc/src/main/native/include/wpi/util/Color8Bit.hpp
+++ b/wpilibc/src/main/native/include/wpi/util/Color8Bit.hpp
@@ -15,7 +15,7 @@
 #include "wpi/util/StringExtras.hpp"
 #include "wpi/util/ct_string.hpp"
 
-namespace frc {
+namespace wpi {
 
 /**
  * Represents colors that can be used with Addressable LEDs.
@@ -57,19 +57,19 @@ class Color8Bit {
    */
   explicit constexpr Color8Bit(std::string_view hexString) {
     if (hexString.length() != 7 || !hexString.starts_with("#") ||
-        !wpi::isHexDigit(hexString[1]) || !wpi::isHexDigit(hexString[2]) ||
-        !wpi::isHexDigit(hexString[3]) || !wpi::isHexDigit(hexString[4]) ||
-        !wpi::isHexDigit(hexString[5]) || !wpi::isHexDigit(hexString[6])) {
+        !wpi::util::isHexDigit(hexString[1]) || !wpi::util::isHexDigit(hexString[2]) ||
+        !wpi::util::isHexDigit(hexString[3]) || !wpi::util::isHexDigit(hexString[4]) ||
+        !wpi::util::isHexDigit(hexString[5]) || !wpi::util::isHexDigit(hexString[6])) {
       throw std::invalid_argument(
           fmt::format("Invalid hex string for Color \"{}\"", hexString));
     }
 
-    red = wpi::hexDigitValue(hexString[1]) * 16 +
-          wpi::hexDigitValue(hexString[2]);
-    green = wpi::hexDigitValue(hexString[3]) * 16 +
-            wpi::hexDigitValue(hexString[4]);
-    blue = wpi::hexDigitValue(hexString[5]) * 16 +
-           wpi::hexDigitValue(hexString[6]);
+    red = wpi::util::hexDigitValue(hexString[1]) * 16 +
+          wpi::util::hexDigitValue(hexString[2]);
+    green = wpi::util::hexDigitValue(hexString[3]) * 16 +
+            wpi::util::hexDigitValue(hexString[4]);
+    blue = wpi::util::hexDigitValue(hexString[5]) * 16 +
+           wpi::util::hexDigitValue(hexString[6]);
   }
 
   constexpr bool operator==(const Color8Bit&) const = default;
@@ -87,19 +87,19 @@ class Color8Bit {
    */
   static constexpr Color8Bit FromHexString(std::string_view hexString) {
     if (hexString.length() != 7 || !hexString.starts_with("#") ||
-        !wpi::isHexDigit(hexString[1]) || !wpi::isHexDigit(hexString[2]) ||
-        !wpi::isHexDigit(hexString[3]) || !wpi::isHexDigit(hexString[4]) ||
-        !wpi::isHexDigit(hexString[5]) || !wpi::isHexDigit(hexString[6])) {
+        !wpi::util::isHexDigit(hexString[1]) || !wpi::util::isHexDigit(hexString[2]) ||
+        !wpi::util::isHexDigit(hexString[3]) || !wpi::util::isHexDigit(hexString[4]) ||
+        !wpi::util::isHexDigit(hexString[5]) || !wpi::util::isHexDigit(hexString[6])) {
       throw std::invalid_argument(
           fmt::format("Invalid hex string for Color \"{}\"", hexString));
     }
 
-    int r = wpi::hexDigitValue(hexString[0]) * 16 +
-            wpi::hexDigitValue(hexString[1]);
-    int g = wpi::hexDigitValue(hexString[2]) * 16 +
-            wpi::hexDigitValue(hexString[3]);
-    int b = wpi::hexDigitValue(hexString[4]) * 16 +
-            wpi::hexDigitValue(hexString[5]);
+    int r = wpi::util::hexDigitValue(hexString[0]) * 16 +
+            wpi::util::hexDigitValue(hexString[1]);
+    int g = wpi::util::hexDigitValue(hexString[2]) * 16 +
+            wpi::util::hexDigitValue(hexString[3]);
+    int b = wpi::util::hexDigitValue(hexString[4]) * 16 +
+            wpi::util::hexDigitValue(hexString[5]);
     return Color8Bit{r, g, b};
   }
 
@@ -109,10 +109,10 @@ class Color8Bit {
    * @return a string of the format \#RRGGBB
    */
   constexpr auto HexString() const {
-    return wpi::ct_string, 7>{
-        {'#', wpi::hexdigit(red / 16), wpi::hexdigit(red % 16),
-         wpi::hexdigit(green / 16), wpi::hexdigit(green % 16),
-         wpi::hexdigit(blue / 16), wpi::hexdigit(blue % 16)}};
+    return wpi::util::ct_string, 7>{
+        {'#', wpi::util::hexdigit(red / 16), wpi::util::hexdigit(red % 16),
+         wpi::util::hexdigit(green / 16), wpi::util::hexdigit(green % 16),
+         wpi::util::hexdigit(blue / 16), wpi::util::hexdigit(blue % 16)}};
   }
 
   /// Red component (0-255).
@@ -125,4 +125,4 @@ class Color8Bit {
   int blue = 0;
 };
 
-}  // namespace frc
+}  // namespace wpi
diff --git a/wpilibc/src/main/native/include/wpi/util/Preferences.hpp b/wpilibc/src/main/native/include/wpi/util/Preferences.hpp
index 0094ad0e01..0b1028fecb 100644
--- a/wpilibc/src/main/native/include/wpi/util/Preferences.hpp
+++ b/wpilibc/src/main/native/include/wpi/util/Preferences.hpp
@@ -10,7 +10,7 @@
 #include 
 #include 
 
-namespace frc {
+namespace wpi {
 
 /**
  * The preferences class provides a relatively simple way to save important
@@ -218,4 +218,4 @@ class Preferences {
   Preferences() = default;
 };
 
-}  // namespace frc
+}  // namespace wpi
diff --git a/wpilibc/src/main/native/include/wpi/util/SensorUtil.hpp b/wpilibc/src/main/native/include/wpi/util/SensorUtil.hpp
index 30d067cb3b..478e23603d 100644
--- a/wpilibc/src/main/native/include/wpi/util/SensorUtil.hpp
+++ b/wpilibc/src/main/native/include/wpi/util/SensorUtil.hpp
@@ -4,7 +4,7 @@
 
 #pragma once
 
-namespace frc {
+namespace wpi {
 
 /**
  * Stores most recent status information as well as containing utility functions
@@ -63,4 +63,4 @@ class SensorUtil final {
   static int GetNumPwmChannels();
 };
 
-}  // namespace frc
+}  // namespace wpi
diff --git a/wpilibc/src/main/python/semiwrap/ADXL345_I2C.yml b/wpilibc/src/main/python/semiwrap/ADXL345_I2C.yml
index 6491ce6acc..bbbb9d80c3 100644
--- a/wpilibc/src/main/python/semiwrap/ADXL345_I2C.yml
+++ b/wpilibc/src/main/python/semiwrap/ADXL345_I2C.yml
@@ -2,11 +2,11 @@ extra_includes:
 - wpi/nt/NTSendableBuilder.hpp
 
 classes:
-  frc::ADXL345_I2C:
+  wpi::ADXL345_I2C:
     constants:
-    - frc::ADXL345_I2C::Range::kRange_2G
+    - wpi::ADXL345_I2C::Range::kRange_2G
     ignored_bases:
-    - wpi::SendableHelper
+    - wpi::util::SendableHelper
     enums:
       Axes:
       Range:
@@ -23,7 +23,7 @@ classes:
       GetAcceleration:
       GetAccelerations:
       InitSendable:
-  frc::ADXL345_I2C::AllAxes:
+  wpi::ADXL345_I2C::AllAxes:
     attributes:
       XAxis:
       YAxis:
diff --git a/wpilibc/src/main/python/semiwrap/AddressableLED.yml b/wpilibc/src/main/python/semiwrap/AddressableLED.yml
index 9e9d798094..7c77d2c1e5 100644
--- a/wpilibc/src/main/python/semiwrap/AddressableLED.yml
+++ b/wpilibc/src/main/python/semiwrap/AddressableLED.yml
@@ -3,7 +3,7 @@ functions:
     ignore: true
 
 classes:
-  frc::AddressableLED:
+  wpi::AddressableLED:
     methods:
       AddressableLED:
       SetLength:
@@ -19,7 +19,7 @@ classes:
       SetGlobalData:
     enums:
       ColorOrder:
-  frc::AddressableLED::LEDData:
+  wpi::AddressableLED::LEDData:
     force_no_trampoline: true
     base_qualnames:
       HAL_AddressableLEDData: ::HAL_AddressableLEDData
diff --git a/wpilibc/src/main/python/semiwrap/Alert.yml b/wpilibc/src/main/python/semiwrap/Alert.yml
index c37f3ca12c..f98b7e12bf 100644
--- a/wpilibc/src/main/python/semiwrap/Alert.yml
+++ b/wpilibc/src/main/python/semiwrap/Alert.yml
@@ -3,7 +3,7 @@ functions:
     ignore: true
 
 classes:
-  frc::Alert:
+  wpi::Alert:
     enums:
       AlertType:
     methods:
@@ -17,14 +17,14 @@ classes:
       GetText:
       GetType:
     inline_code: |
-      .def("close", [](frc::Alert &self) {
+      .def("close", [](wpi::Alert &self) {
         py::gil_scoped_release release;
         self.Set(false);
       }, py::doc("Disables the alert"))
-      .def("__enter__", [](frc::Alert &self) -> frc::Alert& {
+      .def("__enter__", [](wpi::Alert &self) -> wpi::Alert& {
         return self;
       })
-      .def("__exit__", [](frc::Alert &self, py::args args) {
+      .def("__exit__", [](wpi::Alert &self, py::args args) {
         py::gil_scoped_release release;
         self.Set(false);
       })
diff --git a/wpilibc/src/main/python/semiwrap/AnalogAccelerometer.yml b/wpilibc/src/main/python/semiwrap/AnalogAccelerometer.yml
index 0832def3c2..e3542e0866 100644
--- a/wpilibc/src/main/python/semiwrap/AnalogAccelerometer.yml
+++ b/wpilibc/src/main/python/semiwrap/AnalogAccelerometer.yml
@@ -2,9 +2,9 @@ extra_includes:
 - wpi/util/sendable/SendableBuilder.hpp
 
 classes:
-  frc::AnalogAccelerometer:
+  wpi::AnalogAccelerometer:
     ignored_bases:
-    - wpi::SendableHelper
+    - wpi::util::SendableHelper
     methods:
       AnalogAccelerometer:
         overloads:
diff --git a/wpilibc/src/main/python/semiwrap/AnalogEncoder.yml b/wpilibc/src/main/python/semiwrap/AnalogEncoder.yml
index bd18b0bd65..ac16eb133c 100644
--- a/wpilibc/src/main/python/semiwrap/AnalogEncoder.yml
+++ b/wpilibc/src/main/python/semiwrap/AnalogEncoder.yml
@@ -3,9 +3,9 @@ extra_includes:
 - wpi/hardware/discrete/AnalogInput.hpp
 
 classes:
-  frc::AnalogEncoder:
+  wpi::AnalogEncoder:
     ignored_bases:
-    - wpi::SendableHelper
+    - wpi::util::SendableHelper
     methods:
       AnalogEncoder:
         overloads:
diff --git a/wpilibc/src/main/python/semiwrap/AnalogInput.yml b/wpilibc/src/main/python/semiwrap/AnalogInput.yml
index 4e7c266b5d..043bede9af 100644
--- a/wpilibc/src/main/python/semiwrap/AnalogInput.yml
+++ b/wpilibc/src/main/python/semiwrap/AnalogInput.yml
@@ -2,9 +2,9 @@ extra_includes:
 - wpi/util/sendable/SendableBuilder.hpp
 
 classes:
-  frc::AnalogInput:
+  wpi::AnalogInput:
     ignored_bases:
-    - wpi::SendableHelper
+    - wpi::util::SendableHelper
     methods:
       AnalogInput:
       GetValue:
diff --git a/wpilibc/src/main/python/semiwrap/AnalogPotentiometer.yml b/wpilibc/src/main/python/semiwrap/AnalogPotentiometer.yml
index fb4f801393..d77aac548d 100644
--- a/wpilibc/src/main/python/semiwrap/AnalogPotentiometer.yml
+++ b/wpilibc/src/main/python/semiwrap/AnalogPotentiometer.yml
@@ -2,9 +2,9 @@ extra_includes:
 - wpi/util/sendable/SendableBuilder.hpp
 
 classes:
-  frc::AnalogPotentiometer:
+  wpi::AnalogPotentiometer:
     ignored_bases:
-    - wpi::SendableHelper
+    - wpi::util::SendableHelper
     methods:
       AnalogPotentiometer:
         overloads:
diff --git a/wpilibc/src/main/python/semiwrap/CAN.yml b/wpilibc/src/main/python/semiwrap/CAN.yml
index da8247de31..d6e25a6b7c 100644
--- a/wpilibc/src/main/python/semiwrap/CAN.yml
+++ b/wpilibc/src/main/python/semiwrap/CAN.yml
@@ -1,5 +1,5 @@
 classes:
-  frc::CAN:
+  wpi::CAN:
     attributes:
       kTeamManufacturer:
       kTeamDeviceType:
diff --git a/wpilibc/src/main/python/semiwrap/Color.yml b/wpilibc/src/main/python/semiwrap/Color.yml
index 450a6016f3..f21d8d4127 100644
--- a/wpilibc/src/main/python/semiwrap/Color.yml
+++ b/wpilibc/src/main/python/semiwrap/Color.yml
@@ -2,9 +2,9 @@ extra_includes:
 - pybind11/operators.h
 
 classes:
-  frc::Color:
+  wpi::Color:
     force_type_casters:
-    - wpi::ct_string
+    - wpi::util::ct_string
     attributes:
       kDenim:
       kFirstBlue:
diff --git a/wpilibc/src/main/python/semiwrap/Color8Bit.yml b/wpilibc/src/main/python/semiwrap/Color8Bit.yml
index 1c29743cb6..bebd9c3a0c 100644
--- a/wpilibc/src/main/python/semiwrap/Color8Bit.yml
+++ b/wpilibc/src/main/python/semiwrap/Color8Bit.yml
@@ -2,9 +2,9 @@ extra_includes:
 - pybind11/operators.h
 
 classes:
-  frc::Color8Bit:
+  wpi::Color8Bit:
     force_type_casters:
-    - wpi::ct_string
+    - wpi::util::ct_string
     attributes:
       red:
         access: readonly
@@ -32,7 +32,7 @@ classes:
 
 inline_code: |
   cls_Color8Bit
-    .def("toColor", [](const Color8Bit &self) -> frc::Color {
+    .def("toColor", [](const Color8Bit &self) -> wpi::Color {
       return self;
     })
     .def("__hash__", [](Color8Bit *self) -> size_t {
diff --git a/wpilibc/src/main/python/semiwrap/Compressor.yml b/wpilibc/src/main/python/semiwrap/Compressor.yml
index 49037a62c6..c5faad234d 100644
--- a/wpilibc/src/main/python/semiwrap/Compressor.yml
+++ b/wpilibc/src/main/python/semiwrap/Compressor.yml
@@ -5,9 +5,9 @@ extra_includes:
 - wpi/hardware/pneumatic/DoubleSolenoid.hpp
 
 classes:
-  frc::Compressor:
+  wpi::Compressor:
     ignored_bases:
-    - wpi::SendableHelper
+    - wpi::util::SendableHelper
     methods:
       Compressor:
         overloads:
diff --git a/wpilibc/src/main/python/semiwrap/CounterBase.yml b/wpilibc/src/main/python/semiwrap/CounterBase.yml
index 94929e183c..bb857f6b2f 100644
--- a/wpilibc/src/main/python/semiwrap/CounterBase.yml
+++ b/wpilibc/src/main/python/semiwrap/CounterBase.yml
@@ -2,7 +2,7 @@ defaults:
   subpackage: interfaces
 
 classes:
-  frc::CounterBase:
+  wpi::CounterBase:
     enums:
       EncodingType:
     methods:
diff --git a/wpilibc/src/main/python/semiwrap/DSControlWord.yml b/wpilibc/src/main/python/semiwrap/DSControlWord.yml
index 2b34b2abee..39b5343d53 100644
--- a/wpilibc/src/main/python/semiwrap/DSControlWord.yml
+++ b/wpilibc/src/main/python/semiwrap/DSControlWord.yml
@@ -1,5 +1,5 @@
 classes:
-  frc::DSControlWord:
+  wpi::DSControlWord:
     methods:
       DSControlWord:
       IsEnabled:
diff --git a/wpilibc/src/main/python/semiwrap/DataLogManager.yml b/wpilibc/src/main/python/semiwrap/DataLogManager.yml
index 68751068cd..930f6cbc3c 100644
--- a/wpilibc/src/main/python/semiwrap/DataLogManager.yml
+++ b/wpilibc/src/main/python/semiwrap/DataLogManager.yml
@@ -2,7 +2,7 @@ extra_includes:
 - wpi/datalog/DataLog.hpp
 
 classes:
-  frc::DataLogManager:
+  wpi::DataLogManager:
     methods:
       Start:
       Stop:
diff --git a/wpilibc/src/main/python/semiwrap/DigitalInput.yml b/wpilibc/src/main/python/semiwrap/DigitalInput.yml
index 582a0d0a9e..be9158ca84 100644
--- a/wpilibc/src/main/python/semiwrap/DigitalInput.yml
+++ b/wpilibc/src/main/python/semiwrap/DigitalInput.yml
@@ -2,9 +2,9 @@ extra_includes:
 - wpi/util/sendable/SendableBuilder.hpp
 
 classes:
-  frc::DigitalInput:
+  wpi::DigitalInput:
     ignored_bases:
-    - wpi::SendableHelper
+    - wpi::util::SendableHelper
     methods:
       DigitalInput:
       Get:
diff --git a/wpilibc/src/main/python/semiwrap/DigitalOutput.yml b/wpilibc/src/main/python/semiwrap/DigitalOutput.yml
index ae5245e920..448e7c9728 100644
--- a/wpilibc/src/main/python/semiwrap/DigitalOutput.yml
+++ b/wpilibc/src/main/python/semiwrap/DigitalOutput.yml
@@ -2,9 +2,9 @@ extra_includes:
 - wpi/util/sendable/SendableBuilder.hpp
 
 classes:
-  frc::DigitalOutput:
+  wpi::DigitalOutput:
     ignored_bases:
-    - wpi::SendableHelper
+    - wpi::util::SendableHelper
     methods:
       DigitalOutput:
       Set:
diff --git a/wpilibc/src/main/python/semiwrap/DoubleSolenoid.yml b/wpilibc/src/main/python/semiwrap/DoubleSolenoid.yml
index 17de2050e2..e36d1054e2 100644
--- a/wpilibc/src/main/python/semiwrap/DoubleSolenoid.yml
+++ b/wpilibc/src/main/python/semiwrap/DoubleSolenoid.yml
@@ -2,9 +2,9 @@ extra_includes:
 - wpi/util/sendable/SendableBuilder.hpp
 
 classes:
-  frc::DoubleSolenoid:
+  wpi::DoubleSolenoid:
     ignored_bases:
-    - wpi::SendableHelper
+    - wpi::util::SendableHelper
     enums:
       Value:
     methods:
diff --git a/wpilibc/src/main/python/semiwrap/DriverStation.yml b/wpilibc/src/main/python/semiwrap/DriverStation.yml
index fdd5b28136..8020d6a5d7 100644
--- a/wpilibc/src/main/python/semiwrap/DriverStation.yml
+++ b/wpilibc/src/main/python/semiwrap/DriverStation.yml
@@ -3,7 +3,7 @@ extra_includes:
 - wpi/datalog/DataLog.hpp
 
 classes:
-  frc::DriverStation:
+  wpi::DriverStation:
     attributes:
       kJoystickPorts:
     enums:
diff --git a/wpilibc/src/main/python/semiwrap/DriverStationModeThread.yml b/wpilibc/src/main/python/semiwrap/DriverStationModeThread.yml
index 3fc8e68230..7ec1c67047 100644
--- a/wpilibc/src/main/python/semiwrap/DriverStationModeThread.yml
+++ b/wpilibc/src/main/python/semiwrap/DriverStationModeThread.yml
@@ -1,5 +1,5 @@
 classes:
-  frc::internal::DriverStationModeThread:
+  wpi::internal::DriverStationModeThread:
     rename: _DriverStationModeThread
     methods:
       DriverStationModeThread:
diff --git a/wpilibc/src/main/python/semiwrap/DutyCycle.yml b/wpilibc/src/main/python/semiwrap/DutyCycle.yml
index 5fac451d20..96d4ec4dac 100644
--- a/wpilibc/src/main/python/semiwrap/DutyCycle.yml
+++ b/wpilibc/src/main/python/semiwrap/DutyCycle.yml
@@ -2,9 +2,9 @@ extra_includes:
 - wpi/util/sendable/SendableBuilder.hpp
 
 classes:
-  frc::DutyCycle:
+  wpi::DutyCycle:
     ignored_bases:
-    - wpi::SendableHelper
+    - wpi::util::SendableHelper
     methods:
       DutyCycle:
         overloads:
diff --git a/wpilibc/src/main/python/semiwrap/DutyCycleEncoder.yml b/wpilibc/src/main/python/semiwrap/DutyCycleEncoder.yml
index 0429a9d6b5..fba4b09e8f 100644
--- a/wpilibc/src/main/python/semiwrap/DutyCycleEncoder.yml
+++ b/wpilibc/src/main/python/semiwrap/DutyCycleEncoder.yml
@@ -3,9 +3,9 @@ extra_includes:
 - wpi/hardware/rotation/DutyCycle.hpp
 
 classes:
-  frc::DutyCycleEncoder:
+  wpi::DutyCycleEncoder:
     ignored_bases:
-    - wpi::SendableHelper
+    - wpi::util::SendableHelper
     methods:
       DutyCycleEncoder:
         overloads:
diff --git a/wpilibc/src/main/python/semiwrap/Encoder.yml b/wpilibc/src/main/python/semiwrap/Encoder.yml
index 6ac1340b13..905a2b8413 100644
--- a/wpilibc/src/main/python/semiwrap/Encoder.yml
+++ b/wpilibc/src/main/python/semiwrap/Encoder.yml
@@ -2,18 +2,18 @@ extra_includes:
 - wpi/util/sendable/SendableBuilder.hpp
 
 classes:
-  frc::Encoder:
+  wpi::Encoder:
     ignored_bases:
-    - wpi::SendableHelper
+    - wpi::util::SendableHelper
     typealias:
-    - frc::Encoder::EncodingType
+    - wpi::Encoder::EncodingType
     methods:
       Encoder:
         overloads:
           int, int, bool, EncodingType:
             param_override:
               encodingType:
-                default: frc::Encoder::EncodingType::k4X
+                default: wpi::Encoder::EncodingType::k4X
           DigitalSource*, DigitalSource*, bool, EncodingType:
             ignore: true
           DigitalSource&, DigitalSource&, bool, EncodingType:
@@ -21,7 +21,7 @@ classes:
           std::shared_ptr, std::shared_ptr, bool, EncodingType:
             param_override:
               encodingType:
-                default: frc::Encoder::EncodingType::k4X
+                default: wpi::Encoder::EncodingType::k4X
       Get:
       Reset:
       GetPeriod:
diff --git a/wpilibc/src/main/python/semiwrap/Errors.yml b/wpilibc/src/main/python/semiwrap/Errors.yml
index d5750d5379..46b847958e 100644
--- a/wpilibc/src/main/python/semiwrap/Errors.yml
+++ b/wpilibc/src/main/python/semiwrap/Errors.yml
@@ -9,5 +9,5 @@ functions:
   MakeError:
     ignore: true
 classes:
-  frc::RuntimeError:
+  wpi::RuntimeError:
     ignore: true
diff --git a/wpilibc/src/main/python/semiwrap/ExpansionHub.yml b/wpilibc/src/main/python/semiwrap/ExpansionHub.yml
index cc95384620..cdd055f3ce 100644
--- a/wpilibc/src/main/python/semiwrap/ExpansionHub.yml
+++ b/wpilibc/src/main/python/semiwrap/ExpansionHub.yml
@@ -3,7 +3,7 @@ extra_includes:
 - wpi/ExpansionHubServo.hpp
 
 classes:
-  frc::ExpansionHub:
+  wpi::ExpansionHub:
     attributes:
       NumUsbPorts:
       NumServoPorts:
diff --git a/wpilibc/src/main/python/semiwrap/ExpansionHubMotor.yml b/wpilibc/src/main/python/semiwrap/ExpansionHubMotor.yml
index 67a176012d..baade5f066 100644
--- a/wpilibc/src/main/python/semiwrap/ExpansionHubMotor.yml
+++ b/wpilibc/src/main/python/semiwrap/ExpansionHubMotor.yml
@@ -1,5 +1,5 @@
 classes:
-  frc::ExpansionHubMotor:
+  wpi::ExpansionHubMotor:
     methods:
       ExpansionHubMotor:
       SetPercentagePower:
diff --git a/wpilibc/src/main/python/semiwrap/ExpansionHubPidConstants.yml b/wpilibc/src/main/python/semiwrap/ExpansionHubPidConstants.yml
index d9efd8cc6b..e98ed02be8 100644
--- a/wpilibc/src/main/python/semiwrap/ExpansionHubPidConstants.yml
+++ b/wpilibc/src/main/python/semiwrap/ExpansionHubPidConstants.yml
@@ -1,5 +1,5 @@
 classes:
-  frc::ExpansionHubPidConstants:
+  wpi::ExpansionHubPidConstants:
     methods:
       SetPID:
       SetFF:
diff --git a/wpilibc/src/main/python/semiwrap/ExpansionHubServo.yml b/wpilibc/src/main/python/semiwrap/ExpansionHubServo.yml
index 1764536f9e..206ea545cd 100644
--- a/wpilibc/src/main/python/semiwrap/ExpansionHubServo.yml
+++ b/wpilibc/src/main/python/semiwrap/ExpansionHubServo.yml
@@ -1,5 +1,5 @@
 classes:
-  frc::ExpansionHubServo:
+  wpi::ExpansionHubServo:
     methods:
       ExpansionHubServo:
       Set:
diff --git a/wpilibc/src/main/python/semiwrap/Field2d.yml b/wpilibc/src/main/python/semiwrap/Field2d.yml
index e4aea9cb6d..d246d9132a 100644
--- a/wpilibc/src/main/python/semiwrap/Field2d.yml
+++ b/wpilibc/src/main/python/semiwrap/Field2d.yml
@@ -2,15 +2,15 @@ extra_includes:
 - wpi/nt/NTSendableBuilder.hpp
 
 classes:
-  frc::Field2d:
+  wpi::Field2d:
     ignored_bases:
-    - wpi::SendableHelper
+    - wpi::util::SendableHelper
     methods:
       Field2d:
       SetRobotPose:
         overloads:
-          const Pose2d&:
-          units::meter_t, units::meter_t, Rotation2d:
+          const wpi::math::Pose2d&:
+          wpi::units::meter_t, wpi::units::meter_t, wpi::math::Rotation2d:
       GetRobotPose:
       GetObject:
         return_value_policy: reference_internal
diff --git a/wpilibc/src/main/python/semiwrap/FieldObject2d.yml b/wpilibc/src/main/python/semiwrap/FieldObject2d.yml
index 48a2334eb3..3647718590 100644
--- a/wpilibc/src/main/python/semiwrap/FieldObject2d.yml
+++ b/wpilibc/src/main/python/semiwrap/FieldObject2d.yml
@@ -2,24 +2,24 @@ extra_includes:
 - wpi/math/trajectory/Trajectory.hpp
 
 classes:
-  frc::FieldObject2d:
+  wpi::FieldObject2d:
     nodelete: true
     methods:
       FieldObject2d:
         ignore: true
       SetPose:
         overloads:
-          const Pose2d&:
-          units::meter_t, units::meter_t, Rotation2d:
+          const wpi::math::Pose2d&:
+          wpi::units::meter_t, wpi::units::meter_t, wpi::math::Rotation2d:
       GetPose:
       SetPoses:
         overloads:
-          std::span:
-          std::initializer_list:
+          std::span:
+          std::initializer_list:
             ignore: true
       SetTrajectory:
       GetPoses:
         overloads:
           '[const]':
-          wpi::SmallVectorImpl& [const]:
+          wpi::util::SmallVectorImpl& [const]:
             ignore: true
diff --git a/wpilibc/src/main/python/semiwrap/Gamepad.yml b/wpilibc/src/main/python/semiwrap/Gamepad.yml
index 7ef9a80133..a70d6464cf 100644
--- a/wpilibc/src/main/python/semiwrap/Gamepad.yml
+++ b/wpilibc/src/main/python/semiwrap/Gamepad.yml
@@ -1,7 +1,7 @@
 classes:
-  frc::Gamepad:
+  wpi::Gamepad:
     ignored_bases:
-    - wpi::SendableHelper
+    - wpi::util::SendableHelper
     methods:
       Gamepad:
       GetLeftX:
@@ -123,7 +123,7 @@ classes:
       GetMisc6ButtonReleased:
       Misc6:
       InitSendable:
-  frc::Gamepad::Button:
+  wpi::Gamepad::Button:
     attributes:
       kSouthFace:
       kEastFace:
@@ -151,7 +151,7 @@ classes:
       kMisc4:
       kMisc5:
       kMisc6:
-  frc::Gamepad::Axis:
+  wpi::Gamepad::Axis:
     attributes:
       kLeftX:
       kLeftY:
diff --git a/wpilibc/src/main/python/semiwrap/GenericHID.yml b/wpilibc/src/main/python/semiwrap/GenericHID.yml
index 4d26c4967c..2494435edd 100644
--- a/wpilibc/src/main/python/semiwrap/GenericHID.yml
+++ b/wpilibc/src/main/python/semiwrap/GenericHID.yml
@@ -6,7 +6,7 @@ extra_includes:
 - wpi/event/BooleanEvent.hpp
 
 classes:
-  frc::GenericHID:
+  wpi::GenericHID:
     enums:
       RumbleType:
       HIDType:
diff --git a/wpilibc/src/main/python/semiwrap/I2C.yml b/wpilibc/src/main/python/semiwrap/I2C.yml
index 5ac39cbf54..05fcf32df2 100644
--- a/wpilibc/src/main/python/semiwrap/I2C.yml
+++ b/wpilibc/src/main/python/semiwrap/I2C.yml
@@ -1,5 +1,5 @@
 classes:
-  frc::I2C:
+  wpi::I2C:
     enums:
       Port:
     methods:
diff --git a/wpilibc/src/main/python/semiwrap/IterativeRobotBase.yml b/wpilibc/src/main/python/semiwrap/IterativeRobotBase.yml
index d13d6941cd..035506a7a8 100644
--- a/wpilibc/src/main/python/semiwrap/IterativeRobotBase.yml
+++ b/wpilibc/src/main/python/semiwrap/IterativeRobotBase.yml
@@ -1,5 +1,5 @@
 classes:
-  frc::IterativeRobotBase:
+  wpi::IterativeRobotBase:
     methods:
       DriverStationConnected:
       DisabledInit:
@@ -15,7 +15,7 @@ classes:
         overloads:
           double:
             ignore: true
-          units::second_t:
+          wpi::units::second_t:
       LoopFunc:
       SimulationInit:
         internal: true
diff --git a/wpilibc/src/main/python/semiwrap/Joystick.yml b/wpilibc/src/main/python/semiwrap/Joystick.yml
index 2637bb5ea4..70c9921276 100644
--- a/wpilibc/src/main/python/semiwrap/Joystick.yml
+++ b/wpilibc/src/main/python/semiwrap/Joystick.yml
@@ -2,7 +2,7 @@ extra_includes:
 - wpi/driverstation/DriverStation.hpp
 
 classes:
-  frc::Joystick:
+  wpi::Joystick:
     attributes:
       kDefaultXChannel:
       kDefaultYChannel:
@@ -41,6 +41,6 @@ classes:
       GetDirection:
         rename: getDirectionRadians
     inline_code: |
-      .def("getDirectionDegrees", [](const Joystick &self) -> units::degree_t {
+      .def("getDirectionDegrees", [](const Joystick &self) -> wpi::units::degree_t {
         return self.GetDirection();
       })
diff --git a/wpilibc/src/main/python/semiwrap/Koors40.yml b/wpilibc/src/main/python/semiwrap/Koors40.yml
index edfff8c78c..0332f2c0d2 100644
--- a/wpilibc/src/main/python/semiwrap/Koors40.yml
+++ b/wpilibc/src/main/python/semiwrap/Koors40.yml
@@ -1,4 +1,4 @@
 classes:
-  frc::Koors40:
+  wpi::Koors40:
     methods:
       Koors40:
diff --git a/wpilibc/src/main/python/semiwrap/LEDPattern.yml b/wpilibc/src/main/python/semiwrap/LEDPattern.yml
index 0cff3e7d6a..5b7d0c5bf8 100644
--- a/wpilibc/src/main/python/semiwrap/LEDPattern.yml
+++ b/wpilibc/src/main/python/semiwrap/LEDPattern.yml
@@ -1,5 +1,5 @@
 classes:
-  frc::LEDPattern:
+  wpi::LEDPattern:
     enums:
       GradientType:
     methods:
@@ -7,17 +7,17 @@ classes:
       LEDPattern:
       ApplyTo:
         overloads:
-          std::span [const]:
-          LEDReader, std::function [const]:
-          std::span, std::function [const]:
+          std::span [const]:
+          LEDReader, std::function [const]:
+          std::span, std::function [const]:
       Reversed:
       OffsetBy:
       ScrollAtRelativeSpeed:
       ScrollAtAbsoluteSpeed:
       Blink:
         overloads:
-          units::second_t, units::second_t:
-          units::second_t:
+          wpi::units::second_t, wpi::units::second_t:
+          wpi::units::second_t:
       SynchronizedBlink:
       Breathe:
       OverlayOn:
@@ -38,7 +38,7 @@ classes:
             ignore: true
       Rainbow:
       MapIndex:
-  frc::LEDPattern::LEDReader:
+  wpi::LEDPattern::LEDReader:
     methods:
       LEDReader:
       size:
diff --git a/wpilibc/src/main/python/semiwrap/Mechanism2d.yml b/wpilibc/src/main/python/semiwrap/Mechanism2d.yml
index 6c122b8191..7b4abb6ce6 100644
--- a/wpilibc/src/main/python/semiwrap/Mechanism2d.yml
+++ b/wpilibc/src/main/python/semiwrap/Mechanism2d.yml
@@ -2,9 +2,9 @@ extra_includes:
 - wpi/util/sendable/SendableBuilder.hpp
 
 classes:
-  frc::Mechanism2d:
+  wpi::Mechanism2d:
     ignored_bases:
-    - wpi::SendableHelper
+    - wpi::util::SendableHelper
     methods:
       Mechanism2d:
       GetRoot:
diff --git a/wpilibc/src/main/python/semiwrap/MechanismLigament2d.yml b/wpilibc/src/main/python/semiwrap/MechanismLigament2d.yml
index 6b63a58864..742dfc0ecd 100644
--- a/wpilibc/src/main/python/semiwrap/MechanismLigament2d.yml
+++ b/wpilibc/src/main/python/semiwrap/MechanismLigament2d.yml
@@ -1,5 +1,5 @@
 classes:
-  frc::MechanismLigament2d:
+  wpi::MechanismLigament2d:
     methods:
       MechanismLigament2d:
         ignore: true
diff --git a/wpilibc/src/main/python/semiwrap/MechanismObject2d.yml b/wpilibc/src/main/python/semiwrap/MechanismObject2d.yml
index 51e04abe97..bdd8cf2ef5 100644
--- a/wpilibc/src/main/python/semiwrap/MechanismObject2d.yml
+++ b/wpilibc/src/main/python/semiwrap/MechanismObject2d.yml
@@ -2,9 +2,9 @@ extra_includes:
 - wpi/smartdashboard/MechanismLigament2d.hpp
 
 classes:
-  frc::MechanismObject2d:
+  wpi::MechanismObject2d:
     force_type_casters:
-    - units::degree_t
+    - wpi::units::degree_t
     attributes:
       m_mutex:
         ignore: true
@@ -20,12 +20,12 @@ classes:
 inline_code: |-
   cls_MechanismObject2d
     .def("appendLigament", [](MechanismObject2d *self,
-      std::string_view name, double length, units::degree_t angle,
-      double lineWidth, const frc::Color8Bit& color) {
+      std::string_view name, double length, wpi::units::degree_t angle,
+      double lineWidth, const wpi::Color8Bit& color) {
         return self->Append(name, length, angle, lineWidth, color);
       },
       py::arg("name"), py::arg("length"), py::arg("angle"),
-      py::arg("lineWidth") = 6, py::arg("color") = frc::Color8Bit{235, 137, 52},
+      py::arg("lineWidth") = 6, py::arg("color") = wpi::Color8Bit{235, 137, 52},
       "Append a ligament node",
       py::return_value_policy::reference_internal)
     ;
diff --git a/wpilibc/src/main/python/semiwrap/MechanismRoot2d.yml b/wpilibc/src/main/python/semiwrap/MechanismRoot2d.yml
index ad6a1ac39f..d4f8215d04 100644
--- a/wpilibc/src/main/python/semiwrap/MechanismRoot2d.yml
+++ b/wpilibc/src/main/python/semiwrap/MechanismRoot2d.yml
@@ -2,9 +2,9 @@ extra_includes:
 - wpi/smartdashboard/MechanismLigament2d.hpp
 
 classes:
-  frc::MechanismRoot2d:
+  wpi::MechanismRoot2d:
     force_type_casters:
-    - units::degree_t
+    - wpi::units::degree_t
     methods:
       MechanismRoot2d:
         ignore: true
@@ -19,12 +19,12 @@ inline_code: |-
   cls_MechanismRoot2d
     .def("getName", [](MechanismRoot2d *self) { return self->GetName(); }, release_gil())
     .def("appendLigament", [](MechanismRoot2d *self,
-      std::string_view name, double length, units::degree_t angle,
-      double lineWidth, const frc::Color8Bit& color) {
+      std::string_view name, double length, wpi::units::degree_t angle,
+      double lineWidth, const wpi::Color8Bit& color) {
         return self->Append(name, length, angle, lineWidth, color);
       },
       py::arg("name"), py::arg("length"), py::arg("angle"),
-      py::arg("lineWidth") = 6, py::arg("color") = frc::Color8Bit{235, 137, 52},
+      py::arg("lineWidth") = 6, py::arg("color") = wpi::Color8Bit{235, 137, 52},
       release_gil(), "Append a ligament node",
       py::return_value_policy::reference_internal)
     ;
diff --git a/wpilibc/src/main/python/semiwrap/MotorController.yml b/wpilibc/src/main/python/semiwrap/MotorController.yml
index 8249a2b37b..94764b64ee 100644
--- a/wpilibc/src/main/python/semiwrap/MotorController.yml
+++ b/wpilibc/src/main/python/semiwrap/MotorController.yml
@@ -2,7 +2,7 @@ defaults:
   subpackage: interfaces
 
 classes:
-  frc::MotorController:
+  wpi::MotorController:
     methods:
       Set:
       SetVoltage:
diff --git a/wpilibc/src/main/python/semiwrap/MotorControllerGroup.yml b/wpilibc/src/main/python/semiwrap/MotorControllerGroup.yml
index 21bb9519e7..44baa068e8 100644
--- a/wpilibc/src/main/python/semiwrap/MotorControllerGroup.yml
+++ b/wpilibc/src/main/python/semiwrap/MotorControllerGroup.yml
@@ -3,10 +3,10 @@ extra_includes:
 - pybind11/stl.h
 
 classes:
-  frc::PyMotorControllerGroup:
+  wpi::PyMotorControllerGroup:
     rename: MotorControllerGroup
     ignored_bases:
-    - wpi::SendableHelper
+    - wpi::util::SendableHelper
     methods:
       PyMotorControllerGroup:
         cpp_code: |
diff --git a/wpilibc/src/main/python/semiwrap/MotorSafety.yml b/wpilibc/src/main/python/semiwrap/MotorSafety.yml
index 67a3501b0f..bdffafd12f 100644
--- a/wpilibc/src/main/python/semiwrap/MotorSafety.yml
+++ b/wpilibc/src/main/python/semiwrap/MotorSafety.yml
@@ -2,7 +2,7 @@ extra_includes:
 - wpi/util/SmallString.hpp
 
 classes:
-  frc::MotorSafety:
+  wpi::MotorSafety:
     methods:
       MotorSafety:
       Feed:
diff --git a/wpilibc/src/main/python/semiwrap/Notifier.yml b/wpilibc/src/main/python/semiwrap/Notifier.yml
index cfa1876b01..6e167ebbaa 100644
--- a/wpilibc/src/main/python/semiwrap/Notifier.yml
+++ b/wpilibc/src/main/python/semiwrap/Notifier.yml
@@ -1,5 +1,5 @@
 classes:
-  frc::PyNotifier:
+  wpi::PyNotifier:
     rename: Notifier
     methods:
       PyNotifier:
@@ -11,11 +11,11 @@ classes:
         overloads:
           double:
             ignore: true
-          units::second_t:
+          wpi::units::second_t:
       StartPeriodic:
         overloads:
           double:
             ignore: true
-          units::second_t:
+          wpi::units::second_t:
       Stop:
       SetHALThreadPriority:
diff --git a/wpilibc/src/main/python/semiwrap/OnboardIMU.yml b/wpilibc/src/main/python/semiwrap/OnboardIMU.yml
index 97f70ec98c..45d208b4b9 100644
--- a/wpilibc/src/main/python/semiwrap/OnboardIMU.yml
+++ b/wpilibc/src/main/python/semiwrap/OnboardIMU.yml
@@ -1,5 +1,5 @@
 classes:
-  frc::OnboardIMU:
+  wpi::OnboardIMU:
     enums:
       MountOrientation:
     methods:
diff --git a/wpilibc/src/main/python/semiwrap/PS4Controller.yml b/wpilibc/src/main/python/semiwrap/PS4Controller.yml
index 6a0b5dc33b..6864efd150 100644
--- a/wpilibc/src/main/python/semiwrap/PS4Controller.yml
+++ b/wpilibc/src/main/python/semiwrap/PS4Controller.yml
@@ -3,9 +3,9 @@ extra_includes:
 - wpi/event/BooleanEvent.hpp
 
 classes:
-  frc::PS4Controller:
+  wpi::PS4Controller:
     ignored_bases:
-    - wpi::SendableHelper
+    - wpi::util::SendableHelper
     methods:
       PS4Controller:
       GetLeftX:
@@ -74,7 +74,7 @@ classes:
       GetTouchpadButtonPressed:
       GetTouchpadButtonReleased:
       InitSendable:
-  frc::PS4Controller::Button:
+  wpi::PS4Controller::Button:
     attributes:
       kSquare:
       kCross:
@@ -90,7 +90,7 @@ classes:
       kR3:
       kPS:
       kTouchpad:
-  frc::PS4Controller::Axis:
+  wpi::PS4Controller::Axis:
     attributes:
       kLeftX:
       kLeftY:
diff --git a/wpilibc/src/main/python/semiwrap/PS5Controller.yml b/wpilibc/src/main/python/semiwrap/PS5Controller.yml
index f18b7d8ee9..afe1a1cc95 100644
--- a/wpilibc/src/main/python/semiwrap/PS5Controller.yml
+++ b/wpilibc/src/main/python/semiwrap/PS5Controller.yml
@@ -2,9 +2,9 @@ extra_includes:
 - wpi/util/sendable/SendableBuilder.hpp
 
 classes:
-  frc::PS5Controller:
+  wpi::PS5Controller:
     ignored_bases:
-    - wpi::SendableHelper
+    - wpi::util::SendableHelper
     methods:
       PS5Controller:
       GetLeftX:
@@ -73,7 +73,7 @@ classes:
       GetTouchpadButtonPressed:
       GetTouchpadButtonReleased:
       InitSendable:
-  frc::PS5Controller::Button:
+  wpi::PS5Controller::Button:
     attributes:
       kSquare:
       kCross:
@@ -89,7 +89,7 @@ classes:
       kR3:
       kPS:
       kTouchpad:
-  frc::PS5Controller::Axis:
+  wpi::PS5Controller::Axis:
     attributes:
       kLeftX:
       kLeftY:
diff --git a/wpilibc/src/main/python/semiwrap/PWM.yml b/wpilibc/src/main/python/semiwrap/PWM.yml
index 62287d38bb..1ce7cff460 100644
--- a/wpilibc/src/main/python/semiwrap/PWM.yml
+++ b/wpilibc/src/main/python/semiwrap/PWM.yml
@@ -4,9 +4,9 @@ extra_includes:
 - wpi/util/SmallString.hpp
 
 classes:
-  frc::PWM:
+  wpi::PWM:
     ignored_bases:
-    - wpi::SendableHelper
+    - wpi::util::SendableHelper
     enums:
       OutputPeriod:
     methods:
diff --git a/wpilibc/src/main/python/semiwrap/PWMMotorController.yml b/wpilibc/src/main/python/semiwrap/PWMMotorController.yml
index 5078b7da93..9a847a5f27 100644
--- a/wpilibc/src/main/python/semiwrap/PWMMotorController.yml
+++ b/wpilibc/src/main/python/semiwrap/PWMMotorController.yml
@@ -2,9 +2,9 @@ extra_includes:
 - wpi/util/sendable/SendableBuilder.hpp
 
 classes:
-  frc::PWMMotorController:
+  wpi::PWMMotorController:
     ignored_bases:
-    - wpi::SendableHelper
+    - wpi::util::SendableHelper
     attributes:
       m_pwm:
     methods:
diff --git a/wpilibc/src/main/python/semiwrap/PWMSparkFlex.yml b/wpilibc/src/main/python/semiwrap/PWMSparkFlex.yml
index 631385f360..a5664c6572 100644
--- a/wpilibc/src/main/python/semiwrap/PWMSparkFlex.yml
+++ b/wpilibc/src/main/python/semiwrap/PWMSparkFlex.yml
@@ -1,4 +1,4 @@
 classes:
-  frc::PWMSparkFlex:
+  wpi::PWMSparkFlex:
     methods:
       PWMSparkFlex:
diff --git a/wpilibc/src/main/python/semiwrap/PWMSparkMax.yml b/wpilibc/src/main/python/semiwrap/PWMSparkMax.yml
index 2133741ed0..0f1d565874 100644
--- a/wpilibc/src/main/python/semiwrap/PWMSparkMax.yml
+++ b/wpilibc/src/main/python/semiwrap/PWMSparkMax.yml
@@ -2,6 +2,6 @@ extra_includes:
 - wpi/util/sendable/SendableBuilder.hpp
 
 classes:
-  frc::PWMSparkMax:
+  wpi::PWMSparkMax:
     methods:
       PWMSparkMax:
diff --git a/wpilibc/src/main/python/semiwrap/PWMTalonFX.yml b/wpilibc/src/main/python/semiwrap/PWMTalonFX.yml
index 1e52875d9d..a64fdd6c8b 100644
--- a/wpilibc/src/main/python/semiwrap/PWMTalonFX.yml
+++ b/wpilibc/src/main/python/semiwrap/PWMTalonFX.yml
@@ -2,6 +2,6 @@ extra_includes:
 - wpi/util/sendable/SendableBuilder.hpp
 
 classes:
-  frc::PWMTalonFX:
+  wpi::PWMTalonFX:
     methods:
       PWMTalonFX:
diff --git a/wpilibc/src/main/python/semiwrap/PWMTalonSRX.yml b/wpilibc/src/main/python/semiwrap/PWMTalonSRX.yml
index e94d9b616d..02145178bd 100644
--- a/wpilibc/src/main/python/semiwrap/PWMTalonSRX.yml
+++ b/wpilibc/src/main/python/semiwrap/PWMTalonSRX.yml
@@ -2,6 +2,6 @@ extra_includes:
 - wpi/util/sendable/SendableBuilder.hpp
 
 classes:
-  frc::PWMTalonSRX:
+  wpi::PWMTalonSRX:
     methods:
       PWMTalonSRX:
diff --git a/wpilibc/src/main/python/semiwrap/PWMVenom.yml b/wpilibc/src/main/python/semiwrap/PWMVenom.yml
index cc65942e6b..89e4bec595 100644
--- a/wpilibc/src/main/python/semiwrap/PWMVenom.yml
+++ b/wpilibc/src/main/python/semiwrap/PWMVenom.yml
@@ -2,6 +2,6 @@ extra_includes:
 - wpi/util/sendable/SendableBuilder.hpp
 
 classes:
-  frc::PWMVenom:
+  wpi::PWMVenom:
     methods:
       PWMVenom:
diff --git a/wpilibc/src/main/python/semiwrap/PWMVictorSPX.yml b/wpilibc/src/main/python/semiwrap/PWMVictorSPX.yml
index 66d922322b..4f071fbe02 100644
--- a/wpilibc/src/main/python/semiwrap/PWMVictorSPX.yml
+++ b/wpilibc/src/main/python/semiwrap/PWMVictorSPX.yml
@@ -2,6 +2,6 @@ extra_includes:
 - wpi/util/sendable/SendableBuilder.hpp
 
 classes:
-  frc::PWMVictorSPX:
+  wpi::PWMVictorSPX:
     methods:
       PWMVictorSPX:
diff --git a/wpilibc/src/main/python/semiwrap/PneumaticHub.yml b/wpilibc/src/main/python/semiwrap/PneumaticHub.yml
index fa00e3631d..b6f7576fc7 100644
--- a/wpilibc/src/main/python/semiwrap/PneumaticHub.yml
+++ b/wpilibc/src/main/python/semiwrap/PneumaticHub.yml
@@ -5,7 +5,7 @@ extra_includes:
 - wpi/hardware/pneumatic/DoubleSolenoid.hpp
 
 classes:
-  frc::PneumaticHub:
+  wpi::PneumaticHub:
     methods:
       PneumaticHub:
         overloads:
@@ -44,7 +44,7 @@ classes:
       GetAnalogVoltage:
       GetPressure:
       ReportUsage:
-  frc::PneumaticHub::Version:
+  wpi::PneumaticHub::Version:
     attributes:
       FirmwareMajor:
       FirmwareMinor:
@@ -52,7 +52,7 @@ classes:
       HardwareMinor:
       HardwareMajor:
       UniqueId:
-  frc::PneumaticHub::Faults:
+  wpi::PneumaticHub::Faults:
     attributes:
       Channel0Fault:
       Channel1Fault:
@@ -78,7 +78,7 @@ classes:
       HardwareFault:
     methods:
       GetChannelFault:
-  frc::PneumaticHub::StickyFaults:
+  wpi::PneumaticHub::StickyFaults:
     attributes:
       CompressorOverCurrent:
       CompressorOpen:
diff --git a/wpilibc/src/main/python/semiwrap/PneumaticsBase.yml b/wpilibc/src/main/python/semiwrap/PneumaticsBase.yml
index d9aba5bf79..0adeac1500 100644
--- a/wpilibc/src/main/python/semiwrap/PneumaticsBase.yml
+++ b/wpilibc/src/main/python/semiwrap/PneumaticsBase.yml
@@ -6,7 +6,7 @@ extra_includes:
 
 
 classes:
-  frc::PneumaticsBase:
+  wpi::PneumaticsBase:
     methods:
       GetCompressor:
       GetPressureSwitch:
diff --git a/wpilibc/src/main/python/semiwrap/PneumaticsControlModule.yml b/wpilibc/src/main/python/semiwrap/PneumaticsControlModule.yml
index 2a519bfe77..30c68c1e8b 100644
--- a/wpilibc/src/main/python/semiwrap/PneumaticsControlModule.yml
+++ b/wpilibc/src/main/python/semiwrap/PneumaticsControlModule.yml
@@ -5,7 +5,7 @@ extra_includes:
 - wpi/hardware/pneumatic/DoubleSolenoid.hpp
 
 classes:
-  frc::PneumaticsControlModule:
+  wpi::PneumaticsControlModule:
     methods:
       PneumaticsControlModule:
         overloads:
diff --git a/wpilibc/src/main/python/semiwrap/PowerDistribution.yml b/wpilibc/src/main/python/semiwrap/PowerDistribution.yml
index e415fc8fdf..66109fc036 100644
--- a/wpilibc/src/main/python/semiwrap/PowerDistribution.yml
+++ b/wpilibc/src/main/python/semiwrap/PowerDistribution.yml
@@ -2,9 +2,9 @@ extra_includes:
 - wpi/util/sendable/SendableBuilder.hpp
 
 classes:
-  frc::PowerDistribution:
+  wpi::PowerDistribution:
     ignored_bases:
-    - wpi::SendableHelper
+    - wpi::util::SendableHelper
     attributes:
       kDefaultModule:
     enums:
@@ -32,7 +32,7 @@ classes:
       GetNumChannels:
       GetAllCurrents:
       InitSendable:
-  frc::PowerDistribution::Version:
+  wpi::PowerDistribution::Version:
     attributes:
       FirmwareMajor:
       FirmwareMinor:
@@ -40,7 +40,7 @@ classes:
       HardwareMinor:
       HardwareMajor:
       UniqueId:
-  frc::PowerDistribution::Faults:
+  wpi::PowerDistribution::Faults:
     attributes:
       Channel0BreakerFault:
       Channel1BreakerFault:
@@ -71,7 +71,7 @@ classes:
       HardwareFault:
     methods:
       GetBreakerFault:
-  frc::PowerDistribution::StickyFaults:
+  wpi::PowerDistribution::StickyFaults:
     attributes:
       Channel0BreakerFault:
       Channel1BreakerFault:
diff --git a/wpilibc/src/main/python/semiwrap/Preferences.yml b/wpilibc/src/main/python/semiwrap/Preferences.yml
index 7d8bd60574..ae2f0320a2 100644
--- a/wpilibc/src/main/python/semiwrap/Preferences.yml
+++ b/wpilibc/src/main/python/semiwrap/Preferences.yml
@@ -1,5 +1,5 @@
 classes:
-  frc::Preferences:
+  wpi::Preferences:
     methods:
       GetKeys:
       GetString:
diff --git a/wpilibc/src/main/python/semiwrap/RobotBase.yml b/wpilibc/src/main/python/semiwrap/RobotBase.yml
index 683769a484..7fa1f770ab 100644
--- a/wpilibc/src/main/python/semiwrap/RobotBase.yml
+++ b/wpilibc/src/main/python/semiwrap/RobotBase.yml
@@ -13,7 +13,7 @@ functions:
   ResetMotorSafety:
     ignore: true
 classes:
-  frc::RobotBase:
+  wpi::RobotBase:
     attributes:
       m_threadId:
         ignore: true
diff --git a/wpilibc/src/main/python/semiwrap/RobotController.yml b/wpilibc/src/main/python/semiwrap/RobotController.yml
index eeaa85e4e3..422ba4cdac 100644
--- a/wpilibc/src/main/python/semiwrap/RobotController.yml
+++ b/wpilibc/src/main/python/semiwrap/RobotController.yml
@@ -1,12 +1,12 @@
 classes:
-  frc::CANStatus:
+  wpi::CANStatus:
     attributes:
       percentBusUtilization:
       busOffCount:
       txFullCount:
       receiveErrorCount:
       transmitErrorCount:
-  frc::RobotController:
+  wpi::RobotController:
     nodelete: true
     methods:
       GetSerialNumber:
diff --git a/wpilibc/src/main/python/semiwrap/RobotState.yml b/wpilibc/src/main/python/semiwrap/RobotState.yml
index 63c29f64e8..2ccb2d0e84 100644
--- a/wpilibc/src/main/python/semiwrap/RobotState.yml
+++ b/wpilibc/src/main/python/semiwrap/RobotState.yml
@@ -1,5 +1,5 @@
 classes:
-  frc::RobotState:
+  wpi::RobotState:
     nodelete: true
     methods:
       IsDisabled:
diff --git a/wpilibc/src/main/python/semiwrap/SendableBuilderImpl.yml b/wpilibc/src/main/python/semiwrap/SendableBuilderImpl.yml
index c4cee26d95..ee320df3a8 100644
--- a/wpilibc/src/main/python/semiwrap/SendableBuilderImpl.yml
+++ b/wpilibc/src/main/python/semiwrap/SendableBuilderImpl.yml
@@ -1,5 +1,5 @@
 classes:
-  frc::SendableBuilderImpl:
+  wpi::SendableBuilderImpl:
     methods:
       SendableBuilderImpl:
       SetTable:
diff --git a/wpilibc/src/main/python/semiwrap/SendableChooser.yml b/wpilibc/src/main/python/semiwrap/SendableChooser.yml
index 68947a3c31..1cb5fc1dce 100644
--- a/wpilibc/src/main/python/semiwrap/SendableChooser.yml
+++ b/wpilibc/src/main/python/semiwrap/SendableChooser.yml
@@ -2,7 +2,7 @@ extra_includes:
 - gilsafe_object.h
 
 classes:
-  frc::SendableChooser:
+  wpi::SendableChooser:
     template_params:
     - T
     methods:
@@ -12,7 +12,7 @@ classes:
       GetSelected:
         # weirdness because return type
         cpp_code: |
-          [](frc::SendableChooser * __that) -> py::object {
+          [](wpi::SendableChooser * __that) -> py::object {
             auto v = __that->GetSelected();
             if (!v) {
               return py::none();
@@ -22,7 +22,7 @@ classes:
       OnChange:
         # more weirdness
         cpp_code: |
-          [](frc::SendableChooser *self, std::function fn) {
+          [](wpi::SendableChooser *self, std::function fn) {
             self->OnChange([fn](T v) {
               py::gil_scoped_acquire lock;
               if (v) {
@@ -37,6 +37,6 @@ classes:
 
 templates:
   SendableChooser:
-    qualname: frc::SendableChooser
+    qualname: wpi::SendableChooser
     params:
     - semiwrap::gilsafe_object
diff --git a/wpilibc/src/main/python/semiwrap/SendableChooserBase.yml b/wpilibc/src/main/python/semiwrap/SendableChooserBase.yml
index e4764ab316..4ac230e5da 100644
--- a/wpilibc/src/main/python/semiwrap/SendableChooserBase.yml
+++ b/wpilibc/src/main/python/semiwrap/SendableChooserBase.yml
@@ -2,9 +2,9 @@ extra_includes:
 - wpi/util/sendable/SendableBuilder.hpp
 
 classes:
-  frc::SendableChooserBase:
+  wpi::SendableChooserBase:
     ignored_bases:
-    - wpi::SendableHelper
+    - wpi::util::SendableHelper
     attributes:
       kDefault:
       kOptions:
diff --git a/wpilibc/src/main/python/semiwrap/SensorUtil.yml b/wpilibc/src/main/python/semiwrap/SensorUtil.yml
index 1de1a6eb02..4c2f284a71 100644
--- a/wpilibc/src/main/python/semiwrap/SensorUtil.yml
+++ b/wpilibc/src/main/python/semiwrap/SensorUtil.yml
@@ -1,5 +1,5 @@
 classes:
-  frc::SensorUtil:
+  wpi::SensorUtil:
     nodelete: true
     methods:
       CheckDigitalChannel:
diff --git a/wpilibc/src/main/python/semiwrap/SerialPort.yml b/wpilibc/src/main/python/semiwrap/SerialPort.yml
index 0bb859adb0..8788584017 100644
--- a/wpilibc/src/main/python/semiwrap/SerialPort.yml
+++ b/wpilibc/src/main/python/semiwrap/SerialPort.yml
@@ -1,5 +1,5 @@
 classes:
-  frc::SerialPort:
+  wpi::SerialPort:
     enums:
       Parity:
       StopBits:
@@ -12,19 +12,19 @@ classes:
           int, Port, int, Parity, StopBits:
             param_override:
               port:
-                default: frc::SerialPort::Port::kOnboard
+                default: wpi::SerialPort::Port::kOnboard
               parity:
-                default: frc::SerialPort::Parity::kParity_None
+                default: wpi::SerialPort::Parity::kParity_None
               stopBits:
-                default: frc::SerialPort::StopBits::kStopBits_One
+                default: wpi::SerialPort::StopBits::kStopBits_One
           int, std::string_view, Port, int, Parity, StopBits:
             param_override:
               port:
-                default: frc::SerialPort::Port::kOnboard
+                default: wpi::SerialPort::Port::kOnboard
               parity:
-                default: frc::SerialPort::Parity::kParity_None
+                default: wpi::SerialPort::Parity::kParity_None
               stopBits:
-                default: frc::SerialPort::StopBits::kStopBits_One
+                default: wpi::SerialPort::StopBits::kStopBits_One
       SetFlowControl:
       EnableTermination:
         param_override:
diff --git a/wpilibc/src/main/python/semiwrap/SharpIR.yml b/wpilibc/src/main/python/semiwrap/SharpIR.yml
index b460021e83..ec1e4805f2 100644
--- a/wpilibc/src/main/python/semiwrap/SharpIR.yml
+++ b/wpilibc/src/main/python/semiwrap/SharpIR.yml
@@ -2,9 +2,9 @@ extra_includes:
 - wpi/util/sendable/SendableBuilder.hpp
 
 classes:
-  frc::SharpIR:
+  wpi::SharpIR:
     ignored_bases:
-    - wpi::SendableHelper
+    - wpi::util::SendableHelper
     methods:
       GP2Y0A02YK0F:
       GP2Y0A21YK0F:
diff --git a/wpilibc/src/main/python/semiwrap/SmartDashboard.yml b/wpilibc/src/main/python/semiwrap/SmartDashboard.yml
index 54452f8319..e19d3155ab 100644
--- a/wpilibc/src/main/python/semiwrap/SmartDashboard.yml
+++ b/wpilibc/src/main/python/semiwrap/SmartDashboard.yml
@@ -4,7 +4,7 @@ extra_includes:
 - wpi/util/sendable/SendableRegistry.hpp
 
 classes:
-  frc::SmartDashboard:
+  wpi::SmartDashboard:
     methods:
       init:
       ContainsKey:
@@ -16,9 +16,9 @@ classes:
       PutData:
         # overrides ensure data doesn't die if this is the only reference
         overloads:
-          std::string_view, wpi::Sendable*:
+          std::string_view, wpi::util::Sendable*:
             cpp_code: |
-              [](py::str &key, std::shared_ptr data) {
+              [](py::str &key, std::shared_ptr data) {
                 if (!data) {
                   throw FRC_MakeError(err::NullParameter, "{}", "value");
                 }
@@ -31,19 +31,19 @@ classes:
                 }
 
                 std::string_view keyRef(raw_str, raw_size);
-                frc::SmartDashboard::PutData(keyRef, data.get());
+                wpi::SmartDashboard::PutData(keyRef, data.get());
 
                 // this comes after the PutData to ensure that the original object doesn't die
                 // while PutData is called
                 rpy::addSmartDashboardData(key, data);
               }
-          wpi::Sendable*:
+          wpi::util::Sendable*:
             cpp_code: |
-              [](std::shared_ptr value) {
-                frc::SmartDashboard::PutData(value.get());
+              [](std::shared_ptr value) {
+                wpi::SmartDashboard::PutData(value.get());
                 // this comes after the PutData to ensure that the original object doesn't die
                 // while PutData is called
-                auto name = wpi::SendableRegistry::GetName(value.get());
+                auto name = wpi::util::SendableRegistry::GetName(value.get());
                 if (!name.empty()) {
                   py::str key(name);
                   rpy::addSmartDashboardData(key, value);
@@ -55,11 +55,11 @@ classes:
       GetBoolean:
         cpp_code: |
           [](std::string_view key, py::object defaultValue) -> py::object {
-              nt::Value value;
+              wpi::nt::Value value;
               {
                 py::gil_scoped_release release;
-                auto entry = frc::SmartDashboard::GetEntry(key);
-                value = nt::GetEntryValue(entry.GetHandle());
+                auto entry = wpi::SmartDashboard::GetEntry(key);
+                value = wpi::nt::GetEntryValue(entry.GetHandle());
               }
               if (!value || value.type() != NT_BOOLEAN) return defaultValue;
               return py::cast(value.GetBoolean());
@@ -69,11 +69,11 @@ classes:
       GetNumber:
         cpp_code: |
           [](std::string_view key, py::object defaultValue) -> py::object {
-              nt::Value value;
+              wpi::nt::Value value;
               {
                 py::gil_scoped_release release;
-                auto entry = frc::SmartDashboard::GetEntry(key);
-                value = nt::GetEntryValue(entry.GetHandle());
+                auto entry = wpi::SmartDashboard::GetEntry(key);
+                value = wpi::nt::GetEntryValue(entry.GetHandle());
               }
               if (!value || value.type() != NT_DOUBLE) return defaultValue;
               return py::cast(value.GetDouble());
@@ -83,11 +83,11 @@ classes:
       GetString:
         cpp_code: |
           [](std::string_view key, py::object defaultValue) -> py::object {
-              nt::Value value;
+              wpi::nt::Value value;
               {
                 py::gil_scoped_release release;
-                auto entry = frc::SmartDashboard::GetEntry(key);
-                value = nt::GetEntryValue(entry.GetHandle());
+                auto entry = wpi::SmartDashboard::GetEntry(key);
+                value = wpi::nt::GetEntryValue(entry.GetHandle());
               }
               if (!value || value.type() != NT_STRING) return defaultValue;
               return py::cast(value.GetString());
@@ -97,11 +97,11 @@ classes:
       GetBooleanArray:
         cpp_code: |
           [](std::string_view key, py::object defaultValue) -> py::object {
-            nt::Value value;
+            wpi::nt::Value value;
             {
               py::gil_scoped_release release;
-              auto entry = frc::SmartDashboard::GetEntry(key);
-              value = nt::GetEntryValue(entry.GetHandle());
+              auto entry = wpi::SmartDashboard::GetEntry(key);
+              value = wpi::nt::GetEntryValue(entry.GetHandle());
             }
             if (!value || value.type() != NT_BOOLEAN_ARRAY) return defaultValue;
             // ntcore will return bit vector by default. Convert to List[bool]
@@ -118,11 +118,11 @@ classes:
       GetNumberArray:
         cpp_code: |
           [](std::string_view key, py::object defaultValue) -> py::object {
-              nt::Value value;
+              wpi::nt::Value value;
               {
                 py::gil_scoped_release release;
-                auto entry = frc::SmartDashboard::GetEntry(key);
-                value = nt::GetEntryValue(entry.GetHandle());
+                auto entry = wpi::SmartDashboard::GetEntry(key);
+                value = wpi::nt::GetEntryValue(entry.GetHandle());
               }
               if (!value || value.type() != NT_DOUBLE_ARRAY) return defaultValue;
               return py::cast(value.GetDoubleArray());
@@ -132,11 +132,11 @@ classes:
       GetStringArray:
         cpp_code: |
           [](std::string_view key, py::object defaultValue) -> py::object {
-              nt::Value value;
+              wpi::nt::Value value;
               {
                 py::gil_scoped_release release;
-                auto entry = frc::SmartDashboard::GetEntry(key);
-                value = nt::GetEntryValue(entry.GetHandle());
+                auto entry = wpi::SmartDashboard::GetEntry(key);
+                value = wpi::nt::GetEntryValue(entry.GetHandle());
               }
               if (!value || value.type() != NT_STRING_ARRAY) return defaultValue;
               return py::cast(value.GetStringArray());
@@ -146,11 +146,11 @@ classes:
       GetRaw:
         cpp_code: |
           [](std::string_view key, py::object defaultValue) -> py::object {
-              nt::Value value;
+              wpi::nt::Value value;
               {
                 py::gil_scoped_release release;
-                auto entry = frc::SmartDashboard::GetEntry(key);
-                value = nt::GetEntryValue(entry.GetHandle());
+                auto entry = wpi::SmartDashboard::GetEntry(key);
+                value = wpi::nt::GetEntryValue(entry.GetHandle());
               }
               if (!value || value.type() != NT_STRING) return defaultValue;
               return py::cast(value.GetString());
diff --git a/wpilibc/src/main/python/semiwrap/Solenoid.yml b/wpilibc/src/main/python/semiwrap/Solenoid.yml
index 29a05579ef..717eb2d312 100644
--- a/wpilibc/src/main/python/semiwrap/Solenoid.yml
+++ b/wpilibc/src/main/python/semiwrap/Solenoid.yml
@@ -2,9 +2,9 @@ extra_includes:
 - wpi/util/sendable/SendableBuilder.hpp
 
 classes:
-  frc::Solenoid:
+  wpi::Solenoid:
     ignored_bases:
-    - wpi::SendableHelper
+    - wpi::util::SendableHelper
     methods:
       Solenoid:
         overloads:
diff --git a/wpilibc/src/main/python/semiwrap/Spark.yml b/wpilibc/src/main/python/semiwrap/Spark.yml
index 87f3143e18..5094bb7489 100644
--- a/wpilibc/src/main/python/semiwrap/Spark.yml
+++ b/wpilibc/src/main/python/semiwrap/Spark.yml
@@ -2,6 +2,6 @@ extra_includes:
 - wpi/util/sendable/SendableBuilder.hpp
 
 classes:
-  frc::Spark:
+  wpi::Spark:
     methods:
       Spark:
diff --git a/wpilibc/src/main/python/semiwrap/SparkMini.yml b/wpilibc/src/main/python/semiwrap/SparkMini.yml
index fa2f380434..964f852f60 100644
--- a/wpilibc/src/main/python/semiwrap/SparkMini.yml
+++ b/wpilibc/src/main/python/semiwrap/SparkMini.yml
@@ -1,4 +1,4 @@
 classes:
-  frc::SparkMini:
+  wpi::SparkMini:
     methods:
       SparkMini:
diff --git a/wpilibc/src/main/python/semiwrap/StadiaController.yml b/wpilibc/src/main/python/semiwrap/StadiaController.yml
index 7a03fafb40..ec4ba04451 100644
--- a/wpilibc/src/main/python/semiwrap/StadiaController.yml
+++ b/wpilibc/src/main/python/semiwrap/StadiaController.yml
@@ -2,9 +2,9 @@ extra_includes:
 - wpi/util/sendable/SendableBuilder.hpp
 
 classes:
-  frc::StadiaController:
+  wpi::StadiaController:
     ignored_bases:
-    - wpi::SendableHelper
+    - wpi::util::SendableHelper
     methods:
       StadiaController:
       GetLeftX:
@@ -78,7 +78,7 @@ classes:
       GetRightBumperButtonPressed:
       GetRightBumperButtonReleased:
       InitSendable:
-  frc::StadiaController::Button:
+  wpi::StadiaController::Button:
     attributes:
       kA:
       kB:
@@ -95,7 +95,7 @@ classes:
       kLeftTrigger:
       kGoogle:
       kFrame:
-  frc::StadiaController::Axis:
+  wpi::StadiaController::Axis:
     attributes:
       kLeftX:
       kRightX:
diff --git a/wpilibc/src/main/python/semiwrap/SysIdRoutineLog.yml b/wpilibc/src/main/python/semiwrap/SysIdRoutineLog.yml
index f8e020e5c2..45d79c3279 100644
--- a/wpilibc/src/main/python/semiwrap/SysIdRoutineLog.yml
+++ b/wpilibc/src/main/python/semiwrap/SysIdRoutineLog.yml
@@ -7,29 +7,29 @@ enums:
       .def("__str__", &SysIdRoutineLog::StateEnumToString)
 
 classes:
-  frc::sysid::SysIdRoutineLog:
+  wpi::sysid::SysIdRoutineLog:
     methods:
       SysIdRoutineLog:
       RecordState:
       Motor:
       StateEnumToString:
-  frc::sysid::SysIdRoutineLog::MotorLog:
+  wpi::sysid::SysIdRoutineLog::MotorLog:
     methods:
       value:
       voltage:
       position:
         overloads:
-          units::meter_t:
-          units::turn_t:
+          wpi::units::meter_t:
+          wpi::units::turn_t:
             rename: angularPosition
       velocity:
         overloads:
-          units::meters_per_second_t:
-          units::turns_per_second_t:
+          wpi::units::meters_per_second_t:
+          wpi::units::turns_per_second_t:
             rename: angularVelocity
       acceleration:
         overloads:
-          units::meters_per_second_squared_t:
-          units::turns_per_second_squared_t:
+          wpi::units::meters_per_second_squared_t:
+          wpi::units::turns_per_second_squared_t:
             rename: angularAcceleration
       current:
diff --git a/wpilibc/src/main/python/semiwrap/SystemServer.yml b/wpilibc/src/main/python/semiwrap/SystemServer.yml
index 21bfd10ca8..16aa56d149 100644
--- a/wpilibc/src/main/python/semiwrap/SystemServer.yml
+++ b/wpilibc/src/main/python/semiwrap/SystemServer.yml
@@ -1,4 +1,4 @@
 classes:
-  frc::SystemServer:
+  wpi::SystemServer:
     methods:
       GetSystemServer:
diff --git a/wpilibc/src/main/python/semiwrap/Talon.yml b/wpilibc/src/main/python/semiwrap/Talon.yml
index 4af53569f0..3b06fe904d 100644
--- a/wpilibc/src/main/python/semiwrap/Talon.yml
+++ b/wpilibc/src/main/python/semiwrap/Talon.yml
@@ -2,6 +2,6 @@ extra_includes:
 - wpi/util/sendable/SendableBuilder.hpp
 
 classes:
-  frc::Talon:
+  wpi::Talon:
     methods:
       Talon:
diff --git a/wpilibc/src/main/python/semiwrap/TimedRobot.yml b/wpilibc/src/main/python/semiwrap/TimedRobot.yml
index bbbd87e2a5..0f57397833 100644
--- a/wpilibc/src/main/python/semiwrap/TimedRobot.yml
+++ b/wpilibc/src/main/python/semiwrap/TimedRobot.yml
@@ -1,5 +1,5 @@
 classes:
-  frc::TimedRobot:
+  wpi::TimedRobot:
     attributes:
       kDefaultPeriod:
     methods:
@@ -12,5 +12,5 @@ classes:
             default: 0_s
       TimedRobot:
         overloads:
-          units::second_t:
-          units::hertz_t:
+          wpi::units::second_t:
+          wpi::units::hertz_t:
diff --git a/wpilibc/src/main/python/semiwrap/Timer.yml b/wpilibc/src/main/python/semiwrap/Timer.yml
index 5b50a3f2fb..869d27d118 100644
--- a/wpilibc/src/main/python/semiwrap/Timer.yml
+++ b/wpilibc/src/main/python/semiwrap/Timer.yml
@@ -2,7 +2,7 @@ functions:
   Wait:
   GetTime:
 classes:
-  frc::Timer:
+  wpi::Timer:
     methods:
       Timer:
       Get:
diff --git a/wpilibc/src/main/python/semiwrap/TimesliceRobot.yml b/wpilibc/src/main/python/semiwrap/TimesliceRobot.yml
index 1e507942da..298e31ced0 100644
--- a/wpilibc/src/main/python/semiwrap/TimesliceRobot.yml
+++ b/wpilibc/src/main/python/semiwrap/TimesliceRobot.yml
@@ -1,5 +1,5 @@
 classes:
-  frc::TimesliceRobot:
+  wpi::TimesliceRobot:
     methods:
       TimesliceRobot:
       Schedule:
diff --git a/wpilibc/src/main/python/semiwrap/Tracer.yml b/wpilibc/src/main/python/semiwrap/Tracer.yml
index 0f7284e2ea..95767e438a 100644
--- a/wpilibc/src/main/python/semiwrap/Tracer.yml
+++ b/wpilibc/src/main/python/semiwrap/Tracer.yml
@@ -3,7 +3,7 @@ extra_includes:
 - wpi/util/raw_ostream.hpp
 
 classes:
-  frc::Tracer:
+  wpi::Tracer:
     methods:
       Tracer:
       ResetTimer:
@@ -12,15 +12,15 @@ classes:
       PrintEpochs:
         overloads:
           '':
-          wpi::raw_ostream&:
+          wpi::util::raw_ostream&:
             ignore: true
 
 inline_code: |-
   cls_Tracer
     .def("getEpochs",
       [](Tracer * self) -> py::str {
-        wpi::SmallString<128> buf;
-        wpi::raw_svector_ostream s(buf);
+        wpi::util::SmallString<128> buf;
+        wpi::util::raw_svector_ostream s(buf);
         self->PrintEpochs(s);
         return py::cast(s.str());
       },
diff --git a/wpilibc/src/main/python/semiwrap/VictorSP.yml b/wpilibc/src/main/python/semiwrap/VictorSP.yml
index cdf9b95be2..d81438eaa3 100644
--- a/wpilibc/src/main/python/semiwrap/VictorSP.yml
+++ b/wpilibc/src/main/python/semiwrap/VictorSP.yml
@@ -2,6 +2,6 @@ extra_includes:
 - wpi/util/sendable/SendableBuilder.hpp
 
 classes:
-  frc::VictorSP:
+  wpi::VictorSP:
     methods:
       VictorSP:
diff --git a/wpilibc/src/main/python/semiwrap/Watchdog.yml b/wpilibc/src/main/python/semiwrap/Watchdog.yml
index cd00aca4b5..e00b98c485 100644
--- a/wpilibc/src/main/python/semiwrap/Watchdog.yml
+++ b/wpilibc/src/main/python/semiwrap/Watchdog.yml
@@ -1,17 +1,17 @@
 classes:
-  frc::Watchdog:
+  wpi::Watchdog:
     methods:
       Watchdog:
         overloads:
-          units::second_t, std::function:
-          units::second_t, Callable&&, Arg&&, Args&&...:
+          wpi::units::second_t, std::function:
+          wpi::units::second_t, Callable&&, Arg&&, Args&&...:
             ignore: true
       GetTime:
       SetTimeout:
         overloads:
           double:
             ignore: true
-          units::second_t:
+          wpi::units::second_t:
       GetTimeout:
       IsExpired:
       AddEpoch:
diff --git a/wpilibc/src/main/python/semiwrap/XboxController.yml b/wpilibc/src/main/python/semiwrap/XboxController.yml
index 0fac38d8b8..05d1301b4f 100644
--- a/wpilibc/src/main/python/semiwrap/XboxController.yml
+++ b/wpilibc/src/main/python/semiwrap/XboxController.yml
@@ -4,9 +4,9 @@ extra_includes:
 - wpi/event/BooleanEvent.hpp
 
 classes:
-  frc::XboxController:
+  wpi::XboxController:
     ignored_bases:
-    - wpi::SendableHelper
+    - wpi::util::SendableHelper
     methods:
       XboxController:
       GetLeftX:
@@ -70,7 +70,7 @@ classes:
       GetRightBumperButtonPressed:
       GetRightBumperButtonReleased:
       InitSendable:
-  frc::XboxController::Button:
+  wpi::XboxController::Button:
     attributes:
       kLeftBumper:
       kRightBumper:
@@ -82,7 +82,7 @@ classes:
       kY:
       kBack:
       kStart:
-  frc::XboxController::Axis:
+  wpi::XboxController::Axis:
     attributes:
       kLeftX:
       kRightX:
diff --git a/wpilibc/src/main/python/semiwrap/counter/Tachometer.yml b/wpilibc/src/main/python/semiwrap/counter/Tachometer.yml
index 21a59af959..4c3a692d0a 100644
--- a/wpilibc/src/main/python/semiwrap/counter/Tachometer.yml
+++ b/wpilibc/src/main/python/semiwrap/counter/Tachometer.yml
@@ -1,7 +1,7 @@
 classes:
-  frc::Tachometer:
+  wpi::Tachometer:
     ignored_bases:
-    - wpi::SendableHelper
+    - wpi::util::SendableHelper
     methods:
       Tachometer:
         overloads:
diff --git a/wpilibc/src/main/python/semiwrap/counter/UpDownCounter.yml b/wpilibc/src/main/python/semiwrap/counter/UpDownCounter.yml
index 9941ef0c38..512eff831d 100644
--- a/wpilibc/src/main/python/semiwrap/counter/UpDownCounter.yml
+++ b/wpilibc/src/main/python/semiwrap/counter/UpDownCounter.yml
@@ -1,7 +1,7 @@
 classes:
-  frc::UpDownCounter:
+  wpi::UpDownCounter:
     ignored_bases:
-    - wpi::SendableHelper
+    - wpi::util::SendableHelper
     methods:
       UpDownCounter:
         overloads:
diff --git a/wpilibc/src/main/python/semiwrap/drive/DifferentialDrive.yml b/wpilibc/src/main/python/semiwrap/drive/DifferentialDrive.yml
index dcbfe1771e..2d0f029971 100644
--- a/wpilibc/src/main/python/semiwrap/drive/DifferentialDrive.yml
+++ b/wpilibc/src/main/python/semiwrap/drive/DifferentialDrive.yml
@@ -3,9 +3,9 @@ extra_includes:
 - wpi/hardware/motor/MotorController.hpp
 
 classes:
-  frc::DifferentialDrive:
+  wpi::DifferentialDrive:
     ignored_bases:
-    - wpi::SendableHelper
+    - wpi::util::SendableHelper
     methods:
       DifferentialDrive:
         overloads:
@@ -103,7 +103,7 @@ classes:
       * :meth:`curvatureDrive` is similar in concept to
         ``RobotDrive.drive`` with the addition of a quick turn
         mode. However, it is not designed to give exactly the same response.
-  frc::DifferentialDrive::WheelSpeeds:
+  wpi::DifferentialDrive::WheelSpeeds:
     attributes:
       left:
       right:
diff --git a/wpilibc/src/main/python/semiwrap/drive/MecanumDrive.yml b/wpilibc/src/main/python/semiwrap/drive/MecanumDrive.yml
index 7ec40ff6d6..d713db8827 100644
--- a/wpilibc/src/main/python/semiwrap/drive/MecanumDrive.yml
+++ b/wpilibc/src/main/python/semiwrap/drive/MecanumDrive.yml
@@ -3,11 +3,11 @@ extra_includes:
 - wpi/hardware/motor/MotorController.hpp
 
 classes:
-  frc::MecanumDrive:
+  wpi::MecanumDrive:
     force_type_casters:
-    - units::radian_t
+    - wpi::units::radian_t
     ignored_bases:
-    - wpi::SendableHelper
+    - wpi::util::SendableHelper
     methods:
       MecanumDrive:
         overloads:
@@ -21,16 +21,16 @@ classes:
       DriveCartesian:
         param_override:
           gyroAngle:
-            default: frc::Rotation2d(0_rad)
+            default: wpi::math::Rotation2d(0_rad)
       DrivePolar:
       DriveCartesianIK:
         param_override:
           gyroAngle:
-            default: frc::Rotation2d(0_rad)
+            default: wpi::math::Rotation2d(0_rad)
       StopMotor:
       GetDescription:
       InitSendable:
-  frc::MecanumDrive::WheelSpeeds:
+  wpi::MecanumDrive::WheelSpeeds:
     attributes:
       frontLeft:
       frontRight:
diff --git a/wpilibc/src/main/python/semiwrap/drive/RobotDriveBase.yml b/wpilibc/src/main/python/semiwrap/drive/RobotDriveBase.yml
index 47e6a9315e..a146ef0fa0 100644
--- a/wpilibc/src/main/python/semiwrap/drive/RobotDriveBase.yml
+++ b/wpilibc/src/main/python/semiwrap/drive/RobotDriveBase.yml
@@ -3,7 +3,7 @@ extra_includes:
 - wpi/util/SmallString.hpp
 
 classes:
-  frc::RobotDriveBase:
+  wpi::RobotDriveBase:
     attributes:
       m_deadband:
       m_maxOutput:
diff --git a/wpilibc/src/main/python/semiwrap/event/BooleanEvent.yml b/wpilibc/src/main/python/semiwrap/event/BooleanEvent.yml
index 7de3bc73f4..69dc7fd6f0 100644
--- a/wpilibc/src/main/python/semiwrap/event/BooleanEvent.yml
+++ b/wpilibc/src/main/python/semiwrap/event/BooleanEvent.yml
@@ -1,5 +1,5 @@
 classes:
-  frc::BooleanEvent:
+  wpi::BooleanEvent:
     methods:
       BooleanEvent:
       GetAsBoolean:
diff --git a/wpilibc/src/main/python/semiwrap/event/EventLoop.yml b/wpilibc/src/main/python/semiwrap/event/EventLoop.yml
index eab98c2db5..0f678cfd99 100644
--- a/wpilibc/src/main/python/semiwrap/event/EventLoop.yml
+++ b/wpilibc/src/main/python/semiwrap/event/EventLoop.yml
@@ -1,5 +1,5 @@
 classes:
-  frc::EventLoop:
+  wpi::EventLoop:
     force_type_casters:
     - std::function
     methods:
diff --git a/wpilibc/src/main/python/semiwrap/event/NetworkBooleanEvent.yml b/wpilibc/src/main/python/semiwrap/event/NetworkBooleanEvent.yml
index 05ebc9736a..f6521d5095 100644
--- a/wpilibc/src/main/python/semiwrap/event/NetworkBooleanEvent.yml
+++ b/wpilibc/src/main/python/semiwrap/event/NetworkBooleanEvent.yml
@@ -4,21 +4,21 @@ extra_includes:
 - wpi/nt/NetworkTableInstance.hpp
 
 classes:
-  frc::NetworkBooleanEvent:
+  wpi::NetworkBooleanEvent:
     force_no_trampoline: true
     methods:
       NetworkBooleanEvent:
         overloads:
-          EventLoop*, nt::BooleanTopic:
+          EventLoop*, wpi::nt::BooleanTopic:
             cpp_code: |
-              [](EventLoop *loop, nt::BooleanTopic &topic) {
+              [](EventLoop *loop, wpi::nt::BooleanTopic &topic) {
                 return std::make_unique(loop, std::move(topic));
               }
-          EventLoop*, nt::BooleanSubscriber:
+          EventLoop*, wpi::nt::BooleanSubscriber:
             cpp_code: |
-              [](EventLoop *loop, nt::BooleanSubscriber &sub) {
+              [](EventLoop *loop, wpi::nt::BooleanSubscriber &sub) {
                 return std::make_unique(loop, std::move(sub));
               }
-          EventLoop*, std::shared_ptr, std::string_view:
+          EventLoop*, std::shared_ptr, std::string_view:
           EventLoop*, std::string_view, std::string_view:
-          EventLoop*, nt::NetworkTableInstance, std::string_view, std::string_view:
+          EventLoop*, wpi::nt::NetworkTableInstance, std::string_view, std::string_view:
diff --git a/wpilibc/src/main/python/semiwrap/simulation/ADXL345Sim.yml b/wpilibc/src/main/python/semiwrap/simulation/ADXL345Sim.yml
index 59dff03910..8f8080585a 100644
--- a/wpilibc/src/main/python/semiwrap/simulation/ADXL345Sim.yml
+++ b/wpilibc/src/main/python/semiwrap/simulation/ADXL345Sim.yml
@@ -2,7 +2,7 @@ extra_includes:
 - wpi/hardware/accelerometer/ADXL345_I2C.hpp
 
 classes:
-  frc::sim::ADXL345Sim:
+  wpi::sim::ADXL345Sim:
     methods:
       ADXL345Sim:
         overloads:
diff --git a/wpilibc/src/main/python/semiwrap/simulation/AddressableLEDSim.yml b/wpilibc/src/main/python/semiwrap/simulation/AddressableLEDSim.yml
index c0dbc08dd2..ac48cce4fe 100644
--- a/wpilibc/src/main/python/semiwrap/simulation/AddressableLEDSim.yml
+++ b/wpilibc/src/main/python/semiwrap/simulation/AddressableLEDSim.yml
@@ -2,7 +2,7 @@ extra_includes:
 - wpi/hardware/led/AddressableLED.hpp
 
 classes:
-  frc::sim::AddressableLEDSim:
+  wpi::sim::AddressableLEDSim:
     force_type_casters:
     - std::function
     methods:
diff --git a/wpilibc/src/main/python/semiwrap/simulation/AnalogEncoderSim.yml b/wpilibc/src/main/python/semiwrap/simulation/AnalogEncoderSim.yml
index 10352621a2..01e06327bf 100644
--- a/wpilibc/src/main/python/semiwrap/simulation/AnalogEncoderSim.yml
+++ b/wpilibc/src/main/python/semiwrap/simulation/AnalogEncoderSim.yml
@@ -2,7 +2,7 @@ extra_includes:
 - wpi/hardware/rotation/AnalogEncoder.hpp
 
 classes:
-  frc::sim::AnalogEncoderSim:
+  wpi::sim::AnalogEncoderSim:
     force_type_casters:
     - std::function
     methods:
diff --git a/wpilibc/src/main/python/semiwrap/simulation/AnalogInputSim.yml b/wpilibc/src/main/python/semiwrap/simulation/AnalogInputSim.yml
index fff6a8603f..f13e7c0ae5 100644
--- a/wpilibc/src/main/python/semiwrap/simulation/AnalogInputSim.yml
+++ b/wpilibc/src/main/python/semiwrap/simulation/AnalogInputSim.yml
@@ -2,7 +2,7 @@ extra_includes:
 - wpi/hardware/discrete/AnalogInput.hpp
 
 classes:
-  frc::sim::AnalogInputSim:
+  wpi::sim::AnalogInputSim:
     force_type_casters:
     - std::function
     methods:
diff --git a/wpilibc/src/main/python/semiwrap/simulation/BatterySim.yml b/wpilibc/src/main/python/semiwrap/simulation/BatterySim.yml
index e840ddf7fc..ef2ad412d3 100644
--- a/wpilibc/src/main/python/semiwrap/simulation/BatterySim.yml
+++ b/wpilibc/src/main/python/semiwrap/simulation/BatterySim.yml
@@ -1,13 +1,13 @@
 classes:
-  frc::sim::BatterySim:
+  wpi::sim::BatterySim:
     force_type_casters:
-    - units::ampere_t
+    - wpi::units::ampere_t
     methods:
       Calculate:
         overloads:
-          units::volt_t, units::ohm_t, std::span:
-          units::volt_t, units::ohm_t, std::initializer_list:
+          wpi::units::volt_t, wpi::units::ohm_t, std::span:
+          wpi::units::volt_t, wpi::units::ohm_t, std::initializer_list:
             ignore: true
-          std::span:
-          std::initializer_list:
+          std::span:
+          std::initializer_list:
             ignore: true
diff --git a/wpilibc/src/main/python/semiwrap/simulation/CTREPCMSim.yml b/wpilibc/src/main/python/semiwrap/simulation/CTREPCMSim.yml
index 60f8e7b585..463ded844a 100644
--- a/wpilibc/src/main/python/semiwrap/simulation/CTREPCMSim.yml
+++ b/wpilibc/src/main/python/semiwrap/simulation/CTREPCMSim.yml
@@ -2,9 +2,9 @@ extra_includes:
 - wpi/hardware/pneumatic/Compressor.hpp
 
 classes:
-  frc::sim::CTREPCMSim:
+  wpi::sim::CTREPCMSim:
     typealias:
-    - frc::PneumaticsBase
+    - wpi::PneumaticsBase
     force_type_casters:
     - std::function
     methods:
diff --git a/wpilibc/src/main/python/semiwrap/simulation/CallbackStore.yml b/wpilibc/src/main/python/semiwrap/simulation/CallbackStore.yml
index 5254c98d48..eb974c231d 100644
--- a/wpilibc/src/main/python/semiwrap/simulation/CallbackStore.yml
+++ b/wpilibc/src/main/python/semiwrap/simulation/CallbackStore.yml
@@ -4,7 +4,7 @@ functions:
   ConstBufferCallbackStoreThunk:
     ignore: true
 classes:
-  frc::sim::CallbackStore:
+  wpi::sim::CallbackStore:
     force_type_casters:
     - std::function
     methods:
diff --git a/wpilibc/src/main/python/semiwrap/simulation/DCMotorSim.yml b/wpilibc/src/main/python/semiwrap/simulation/DCMotorSim.yml
index 19ba351052..79b9b4c34b 100644
--- a/wpilibc/src/main/python/semiwrap/simulation/DCMotorSim.yml
+++ b/wpilibc/src/main/python/semiwrap/simulation/DCMotorSim.yml
@@ -1,14 +1,14 @@
 classes:
-  frc::sim::DCMotorSim:
+  wpi::sim::DCMotorSim:
     typealias:
-    - frc::DCMotor
+    - wpi::math::DCMotor
     methods:
       DCMotorSim:
         overloads:
-          const LinearSystem<2, 1, 2>&, const DCMotor&, const std::array&:
+          const wpi::math::LinearSystem<2, 1, 2>&, const wpi::math::DCMotor&, const std::array&:
             param_override:
               plant:
-                x_type: frc::LinearSystem<2,1,2>
+                x_type: wpi::math::LinearSystem<2,1,2>
       SetState:
       GetAngularPosition:
       GetAngularVelocity:
@@ -27,9 +27,9 @@ inline_code: |
   cls_DCMotorSim
     // java API compatibility
     .def("getAngularPositionRotations", [](const DCMotorSim &self) {
-      return units::turn_t{self.GetAngularPosition()};
+      return wpi::units::turn_t{self.GetAngularPosition()};
     }, py::doc("Returns the DC motor position in rotations"))
     .def("getAngularVelocityRPM", [](const DCMotorSim &self) {
-      return units::revolutions_per_minute_t{self.GetAngularVelocity()};
+      return wpi::units::revolutions_per_minute_t{self.GetAngularVelocity()};
     }, py::doc("Returns the DC motor velocity in revolutions per minute"))
   ;
diff --git a/wpilibc/src/main/python/semiwrap/simulation/DIOSim.yml b/wpilibc/src/main/python/semiwrap/simulation/DIOSim.yml
index a231bcf38e..1643f6cdbf 100644
--- a/wpilibc/src/main/python/semiwrap/simulation/DIOSim.yml
+++ b/wpilibc/src/main/python/semiwrap/simulation/DIOSim.yml
@@ -3,7 +3,7 @@ extra_includes:
 - wpi/hardware/discrete/DigitalOutput.hpp
 
 classes:
-  frc::sim::DIOSim:
+  wpi::sim::DIOSim:
     force_type_casters:
     - std::function
     methods:
diff --git a/wpilibc/src/main/python/semiwrap/simulation/DifferentialDrivetrainSim.yml b/wpilibc/src/main/python/semiwrap/simulation/DifferentialDrivetrainSim.yml
index 045bfe7673..8c779e82c4 100644
--- a/wpilibc/src/main/python/semiwrap/simulation/DifferentialDrivetrainSim.yml
+++ b/wpilibc/src/main/python/semiwrap/simulation/DifferentialDrivetrainSim.yml
@@ -1,16 +1,16 @@
 classes:
-  frc::sim::DifferentialDrivetrainSim:
+  wpi::sim::DifferentialDrivetrainSim:
     typealias:
-    - frc::DCMotor
-    - template  using LinearSystem = frc::LinearSystem
+    - wpi::math::DCMotor
+    - template  using wpi::math::LinearSystem = wpi::math::LinearSystem
     methods:
       DifferentialDrivetrainSim:
         overloads:
-          LinearSystem<2, 2, 2>, units::meter_t, DCMotor, double, units::meter_t, const std::array&:
+          wpi::math::LinearSystem<2, 2, 2>, wpi::units::meter_t, wpi::math::DCMotor, double, wpi::units::meter_t, const std::array&:
             param_override:
               measurementStdDevs:
                 default: std::array{}
-          ? frc::DCMotor, double, units::kilogram_square_meter_t, units::kilogram_t, units::meter_t, units::meter_t, const std::array&
+          ? wpi::math::DCMotor, double, wpi::units::kilogram_square_meter_t, wpi::units::kilogram_t, wpi::units::meter_t, wpi::units::meter_t, const std::array&
           : param_override:
               measurementStdDevs:
                 default: std::array{}
@@ -33,15 +33,15 @@ classes:
       Dynamics:
       CreateKitbotSim:
         overloads:
-          frc::DCMotor, double, units::meter_t, const std::array&:
+          wpi::math::DCMotor, double, wpi::units::meter_t, const std::array&:
             param_override:
               measurementStdDevs:
                 default: std::array{}
-          frc::DCMotor, double, units::meter_t, units::kilogram_square_meter_t, const std::array&:
+          wpi::math::DCMotor, double, wpi::units::meter_t, wpi::units::kilogram_square_meter_t, const std::array&:
             param_override:
               measurementStdDevs:
                 default: std::array{}
-  frc::sim::DifferentialDrivetrainSim::State:
+  wpi::sim::DifferentialDrivetrainSim::State:
     attributes:
       kX:
       kY:
@@ -50,14 +50,14 @@ classes:
       kRightVelocity:
       kLeftPosition:
       kRightPosition:
-  frc::sim::DifferentialDrivetrainSim::KitbotGearing:
+  wpi::sim::DifferentialDrivetrainSim::KitbotGearing:
     attributes:
       k12p75:
       k10p71:
       k8p45:
       k7p31:
       k5p95:
-  frc::sim::DifferentialDrivetrainSim::KitbotMotor:
+  wpi::sim::DifferentialDrivetrainSim::KitbotMotor:
     attributes:
       SingleCIMPerSide:
       DualCIMPerSide:
@@ -67,7 +67,7 @@ classes:
       DualFalcon500PerSide:
       SingleNEOPerSide:
       DualNEOPerSide:
-  frc::sim::DifferentialDrivetrainSim::KitbotWheelSize:
+  wpi::sim::DifferentialDrivetrainSim::KitbotWheelSize:
     attributes:
       kSixInch:
       kEightInch:
@@ -75,22 +75,22 @@ classes:
 
 inline_code: |-
   cls_DifferentialDrivetrainSim
-    .def("getLeftPositionFeet", [](DifferentialDrivetrainSim * self) -> units::foot_t {
+    .def("getLeftPositionFeet", [](DifferentialDrivetrainSim * self) -> wpi::units::foot_t {
       return self->GetLeftPosition();
     })
-    .def("getLeftPositionInches", [](DifferentialDrivetrainSim * self) -> units::inch_t {
+    .def("getLeftPositionInches", [](DifferentialDrivetrainSim * self) -> wpi::units::inch_t {
       return self->GetLeftPosition();
     })
-    .def("getLeftVelocityFps", [](DifferentialDrivetrainSim * self) -> units::feet_per_second_t {
+    .def("getLeftVelocityFps", [](DifferentialDrivetrainSim * self) -> wpi::units::feet_per_second_t {
       return self->GetLeftVelocity();
     })
-    .def("getRightPositionFeet", [](DifferentialDrivetrainSim * self) -> units::foot_t {
+    .def("getRightPositionFeet", [](DifferentialDrivetrainSim * self) -> wpi::units::foot_t {
       return self->GetRightPosition();
     })
-    .def("getRightPositionInches", [](DifferentialDrivetrainSim * self) -> units::inch_t {
+    .def("getRightPositionInches", [](DifferentialDrivetrainSim * self) -> wpi::units::inch_t {
       return self->GetRightPosition();
     })
-    .def("getRightVelocityFps", [](DifferentialDrivetrainSim * self) -> units::feet_per_second_t {
+    .def("getRightVelocityFps", [](DifferentialDrivetrainSim * self) -> wpi::units::feet_per_second_t {
       return self->GetRightVelocity();
     })
   ;
diff --git a/wpilibc/src/main/python/semiwrap/simulation/DigitalPWMSim.yml b/wpilibc/src/main/python/semiwrap/simulation/DigitalPWMSim.yml
index b705c370b5..e537214864 100644
--- a/wpilibc/src/main/python/semiwrap/simulation/DigitalPWMSim.yml
+++ b/wpilibc/src/main/python/semiwrap/simulation/DigitalPWMSim.yml
@@ -2,7 +2,7 @@ extra_includes:
 - wpi/hardware/discrete/DigitalOutput.hpp
 
 classes:
-  frc::sim::DigitalPWMSim:
+  wpi::sim::DigitalPWMSim:
     force_type_casters:
     - std::function
     methods:
diff --git a/wpilibc/src/main/python/semiwrap/simulation/DoubleSolenoidSim.yml b/wpilibc/src/main/python/semiwrap/simulation/DoubleSolenoidSim.yml
index 4b44c64500..4678e03a84 100644
--- a/wpilibc/src/main/python/semiwrap/simulation/DoubleSolenoidSim.yml
+++ b/wpilibc/src/main/python/semiwrap/simulation/DoubleSolenoidSim.yml
@@ -1,7 +1,7 @@
 classes:
-  frc::sim::DoubleSolenoidSim:
+  wpi::sim::DoubleSolenoidSim:
     typealias:
-    - frc::PneumaticsModuleType
+    - wpi::PneumaticsModuleType
     methods:
       DoubleSolenoidSim:
         overloads:
diff --git a/wpilibc/src/main/python/semiwrap/simulation/DriverStationSim.yml b/wpilibc/src/main/python/semiwrap/simulation/DriverStationSim.yml
index b04367a661..273c2584fe 100644
--- a/wpilibc/src/main/python/semiwrap/simulation/DriverStationSim.yml
+++ b/wpilibc/src/main/python/semiwrap/simulation/DriverStationSim.yml
@@ -1,5 +1,5 @@
 classes:
-  frc::sim::DriverStationSim:
+  wpi::sim::DriverStationSim:
     force_type_casters:
     - std::function
     methods:
diff --git a/wpilibc/src/main/python/semiwrap/simulation/DutyCycleEncoderSim.yml b/wpilibc/src/main/python/semiwrap/simulation/DutyCycleEncoderSim.yml
index 8eaba60d6e..174e96fddd 100644
--- a/wpilibc/src/main/python/semiwrap/simulation/DutyCycleEncoderSim.yml
+++ b/wpilibc/src/main/python/semiwrap/simulation/DutyCycleEncoderSim.yml
@@ -2,7 +2,7 @@ extra_includes:
 - wpi/hardware/rotation/DutyCycleEncoder.hpp
 
 classes:
-  frc::sim::DutyCycleEncoderSim:
+  wpi::sim::DutyCycleEncoderSim:
     methods:
       DutyCycleEncoderSim:
         overloads:
diff --git a/wpilibc/src/main/python/semiwrap/simulation/DutyCycleSim.yml b/wpilibc/src/main/python/semiwrap/simulation/DutyCycleSim.yml
index c76b86186f..a15d245dcf 100644
--- a/wpilibc/src/main/python/semiwrap/simulation/DutyCycleSim.yml
+++ b/wpilibc/src/main/python/semiwrap/simulation/DutyCycleSim.yml
@@ -2,7 +2,7 @@ extra_includes:
 - wpi/hardware/rotation/DutyCycle.hpp
 
 classes:
-  frc::sim::DutyCycleSim:
+  wpi::sim::DutyCycleSim:
     force_type_casters:
     - std::function
     methods:
diff --git a/wpilibc/src/main/python/semiwrap/simulation/ElevatorSim.yml b/wpilibc/src/main/python/semiwrap/simulation/ElevatorSim.yml
index 8301854dfb..b086ba47ed 100644
--- a/wpilibc/src/main/python/semiwrap/simulation/ElevatorSim.yml
+++ b/wpilibc/src/main/python/semiwrap/simulation/ElevatorSim.yml
@@ -1,21 +1,21 @@
 classes:
-  frc::sim::ElevatorSim:
+  wpi::sim::ElevatorSim:
     typealias:
-    - frc::DCMotor
-    - template  using LinearSystem = frc::LinearSystem
-    - template  using Vectord = frc::Vectord
+    - wpi::math::DCMotor
+    - template  using wpi::math::LinearSystem = wpi::math::LinearSystem
+    - template  using wpi::math::Vectord = wpi::math::Vectord
     methods:
       ElevatorSim:
         overloads:
-          ? const LinearSystem<2, 1, 2>&, const DCMotor&, units::meter_t, units::meter_t, bool, units::meter_t, const std::array&
+          ? const wpi::math::LinearSystem<2, 1, 2>&, const wpi::math::DCMotor&, wpi::units::meter_t, wpi::units::meter_t, bool, wpi::units::meter_t, const std::array&
           : param_override:
               measurementStdDevs:
                 default: std::array{0.0, 0.0}
-          ? const DCMotor&, double, units::kilogram_t, units::meter_t, units::meter_t, units::meter_t, bool, units::meter_t, const std::array&
+          ? const wpi::math::DCMotor&, double, wpi::units::kilogram_t, wpi::units::meter_t, wpi::units::meter_t, wpi::units::meter_t, bool, wpi::units::meter_t, const std::array&
           : param_override:
               measurementStdDevs:
                 default: std::array{0.0}
-          ? decltype(1_V/Velocity_t (1)), decltype(1_V/Acceleration_t (1)), const DCMotor&, units::meter_t, units::meter_t, bool, units::meter_t, const std::array&
+          ? decltype(1_V/Velocity_t (1)), decltype(1_V/Acceleration_t (1)), const wpi::math::DCMotor&, wpi::units::meter_t, wpi::units::meter_t, bool, wpi::units::meter_t, const std::array&
           : ignore: true
       SetState:
       WouldHitLowerLimit:
@@ -30,13 +30,13 @@ classes:
 
 inline_code: |-
   cls_ElevatorSim
-    .def("getPositionFeet", [](ElevatorSim * self) -> units::foot_t {
+    .def("getPositionFeet", [](ElevatorSim * self) -> wpi::units::foot_t {
       return self->GetPosition();
     })
-    .def("getPositionInches", [](ElevatorSim * self) -> units::inch_t {
+    .def("getPositionInches", [](ElevatorSim * self) -> wpi::units::inch_t {
       return self->GetPosition();
     })
-    .def("getVelocityFps", [](ElevatorSim * self) -> units::feet_per_second_t {
+    .def("getVelocityFps", [](ElevatorSim * self) -> wpi::units::feet_per_second_t {
       return self->GetVelocity();
     })
   ;
diff --git a/wpilibc/src/main/python/semiwrap/simulation/EncoderSim.yml b/wpilibc/src/main/python/semiwrap/simulation/EncoderSim.yml
index 92d0dc91ed..9b4288ba40 100644
--- a/wpilibc/src/main/python/semiwrap/simulation/EncoderSim.yml
+++ b/wpilibc/src/main/python/semiwrap/simulation/EncoderSim.yml
@@ -2,7 +2,7 @@ extra_includes:
 - wpi/hardware/rotation/Encoder.hpp
 
 classes:
-  frc::sim::EncoderSim:
+  wpi::sim::EncoderSim:
     force_type_casters:
     - std::function
     methods:
diff --git a/wpilibc/src/main/python/semiwrap/simulation/FlywheelSim.yml b/wpilibc/src/main/python/semiwrap/simulation/FlywheelSim.yml
index 4e80360f8c..23b2c4d0c2 100644
--- a/wpilibc/src/main/python/semiwrap/simulation/FlywheelSim.yml
+++ b/wpilibc/src/main/python/semiwrap/simulation/FlywheelSim.yml
@@ -1,16 +1,16 @@
 classes:
-  frc::sim::FlywheelSim:
+  wpi::sim::FlywheelSim:
     typealias:
-    - frc::DCMotor
-    - template  using LinearSystem = frc::LinearSystem
+    - wpi::math::DCMotor
+    - template  using wpi::math::LinearSystem = wpi::math::LinearSystem
     methods:
       FlywheelSim:
         overloads:
-          const LinearSystem<1, 1, 1>&, const DCMotor&, double, const std::array&:
+          const wpi::math::LinearSystem<1, 1, 1>&, const wpi::math::DCMotor&, double, const std::array&:
             param_override:
               measurementStdDevs:
                 default: std::array{0.0}
-          const DCMotor&, double, units::kilogram_square_meter_t, const std::array&:
+          const wpi::math::DCMotor&, double, wpi::units::kilogram_square_meter_t, const std::array&:
             param_override:
               measurementStdDevs:
                 default: std::array{0.0}
diff --git a/wpilibc/src/main/python/semiwrap/simulation/GamepadSim.yml b/wpilibc/src/main/python/semiwrap/simulation/GamepadSim.yml
index 4ce6851641..a9572823aa 100644
--- a/wpilibc/src/main/python/semiwrap/simulation/GamepadSim.yml
+++ b/wpilibc/src/main/python/semiwrap/simulation/GamepadSim.yml
@@ -2,7 +2,7 @@ extra_includes:
 - wpi/driverstation/Gamepad.hpp
 
 classes:
-  frc::sim::GamepadSim:
+  wpi::sim::GamepadSim:
     force_no_trampoline: true
     methods:
       GamepadSim:
diff --git a/wpilibc/src/main/python/semiwrap/simulation/GenericHIDSim.yml b/wpilibc/src/main/python/semiwrap/simulation/GenericHIDSim.yml
index 41fc24e297..f001bd92cf 100644
--- a/wpilibc/src/main/python/semiwrap/simulation/GenericHIDSim.yml
+++ b/wpilibc/src/main/python/semiwrap/simulation/GenericHIDSim.yml
@@ -1,5 +1,5 @@
 classes:
-  frc::sim::GenericHIDSim:
+  wpi::sim::GenericHIDSim:
     methods:
       GenericHIDSim:
         overloads:
diff --git a/wpilibc/src/main/python/semiwrap/simulation/JoystickSim.yml b/wpilibc/src/main/python/semiwrap/simulation/JoystickSim.yml
index e17e514312..2b080ac824 100644
--- a/wpilibc/src/main/python/semiwrap/simulation/JoystickSim.yml
+++ b/wpilibc/src/main/python/semiwrap/simulation/JoystickSim.yml
@@ -2,7 +2,7 @@ extra_includes:
 - wpi/driverstation/Joystick.hpp
 
 classes:
-  frc::sim::JoystickSim:
+  wpi::sim::JoystickSim:
     force_no_trampoline: true
     methods:
       JoystickSim:
diff --git a/wpilibc/src/main/python/semiwrap/simulation/LinearSystemSim.yml b/wpilibc/src/main/python/semiwrap/simulation/LinearSystemSim.yml
index 9261649ed2..0006ff4b43 100644
--- a/wpilibc/src/main/python/semiwrap/simulation/LinearSystemSim.yml
+++ b/wpilibc/src/main/python/semiwrap/simulation/LinearSystemSim.yml
@@ -1,8 +1,8 @@
 classes:
-  frc::sim::LinearSystemSim:
+  wpi::sim::LinearSystemSim:
     typealias:
-    - template  using LinearSystem = frc::LinearSystem
-    - template  using Vectord = frc::Vectord
+    - template  using wpi::math::LinearSystem = wpi::math::LinearSystem
+    - template  using wpi::math::Vectord = wpi::math::Vectord
     template_params:
     - int States
     - int Inputs
@@ -25,7 +25,7 @@ classes:
           int [const]:
       SetInput:
         overloads:
-          const Vectord&:
+          const wpi::math::Vectord&:
           int, double:
       GetInput:
         overloads:
@@ -38,37 +38,37 @@ classes:
 
 templates:
   LinearSystemSim_1_1_1:
-    qualname: frc::sim::LinearSystemSim
+    qualname: wpi::sim::LinearSystemSim
     params:
     - 1
     - 1
     - 1
   LinearSystemSim_1_1_2:
-    qualname: frc::sim::LinearSystemSim
+    qualname: wpi::sim::LinearSystemSim
     params:
     - 1
     - 1
     - 2
   LinearSystemSim_2_1_1:
-    qualname: frc::sim::LinearSystemSim
+    qualname: wpi::sim::LinearSystemSim
     params:
     - 2
     - 1
     - 1
   LinearSystemSim_2_1_2:
-    qualname: frc::sim::LinearSystemSim
+    qualname: wpi::sim::LinearSystemSim
     params:
     - 2
     - 1
     - 2
   LinearSystemSim_2_2_1:
-    qualname: frc::sim::LinearSystemSim
+    qualname: wpi::sim::LinearSystemSim
     params:
     - 2
     - 2
     - 1
   LinearSystemSim_2_2_2:
-    qualname: frc::sim::LinearSystemSim
+    qualname: wpi::sim::LinearSystemSim
     params:
     - 2
     - 2
diff --git a/wpilibc/src/main/python/semiwrap/simulation/PS4ControllerSim.yml b/wpilibc/src/main/python/semiwrap/simulation/PS4ControllerSim.yml
index 6196e21854..cc19ca4968 100644
--- a/wpilibc/src/main/python/semiwrap/simulation/PS4ControllerSim.yml
+++ b/wpilibc/src/main/python/semiwrap/simulation/PS4ControllerSim.yml
@@ -2,7 +2,7 @@ extra_includes:
 - wpi/driverstation/PS4Controller.hpp
 
 classes:
-  frc::sim::PS4ControllerSim:
+  wpi::sim::PS4ControllerSim:
     force_no_trampoline: true
     methods:
       PS4ControllerSim:
diff --git a/wpilibc/src/main/python/semiwrap/simulation/PS5ControllerSim.yml b/wpilibc/src/main/python/semiwrap/simulation/PS5ControllerSim.yml
index 3f71bb8533..36cb9c57c1 100644
--- a/wpilibc/src/main/python/semiwrap/simulation/PS5ControllerSim.yml
+++ b/wpilibc/src/main/python/semiwrap/simulation/PS5ControllerSim.yml
@@ -2,7 +2,7 @@ extra_includes:
 - wpi/driverstation/PS5Controller.hpp
 
 classes:
-  frc::sim::PS5ControllerSim:
+  wpi::sim::PS5ControllerSim:
     force_no_trampoline: true
     methods:
       PS5ControllerSim:
diff --git a/wpilibc/src/main/python/semiwrap/simulation/PWMMotorControllerSim.yml b/wpilibc/src/main/python/semiwrap/simulation/PWMMotorControllerSim.yml
index 2b1e8e7d3d..8f65140ba3 100644
--- a/wpilibc/src/main/python/semiwrap/simulation/PWMMotorControllerSim.yml
+++ b/wpilibc/src/main/python/semiwrap/simulation/PWMMotorControllerSim.yml
@@ -1,5 +1,5 @@
 classes:
-  frc::sim::PWMMotorControllerSim:
+  wpi::sim::PWMMotorControllerSim:
     methods:
       PWMMotorControllerSim:
         overloads:
diff --git a/wpilibc/src/main/python/semiwrap/simulation/PWMSim.yml b/wpilibc/src/main/python/semiwrap/simulation/PWMSim.yml
index 8c35569bc1..dd58ff550f 100644
--- a/wpilibc/src/main/python/semiwrap/simulation/PWMSim.yml
+++ b/wpilibc/src/main/python/semiwrap/simulation/PWMSim.yml
@@ -3,7 +3,7 @@ extra_includes:
 - wpi/hardware/motor/PWMMotorController.hpp
 
 classes:
-  frc::sim::PWMSim:
+  wpi::sim::PWMSim:
     force_type_casters:
     - std::function
     methods:
diff --git a/wpilibc/src/main/python/semiwrap/simulation/PneumaticsBaseSim.yml b/wpilibc/src/main/python/semiwrap/simulation/PneumaticsBaseSim.yml
index 4dc83550b0..6e62b57697 100644
--- a/wpilibc/src/main/python/semiwrap/simulation/PneumaticsBaseSim.yml
+++ b/wpilibc/src/main/python/semiwrap/simulation/PneumaticsBaseSim.yml
@@ -1,7 +1,7 @@
 classes:
-  frc::sim::PneumaticsBaseSim:
+  wpi::sim::PneumaticsBaseSim:
     typealias:
-    - frc::PneumaticsBase
+    - wpi::PneumaticsBase
     attributes:
       m_index:
     force_type_casters:
diff --git a/wpilibc/src/main/python/semiwrap/simulation/PowerDistributionSim.yml b/wpilibc/src/main/python/semiwrap/simulation/PowerDistributionSim.yml
index d9e0eadec0..ca67074740 100644
--- a/wpilibc/src/main/python/semiwrap/simulation/PowerDistributionSim.yml
+++ b/wpilibc/src/main/python/semiwrap/simulation/PowerDistributionSim.yml
@@ -2,7 +2,7 @@ extra_includes:
 - wpi/hardware/power/PowerDistribution.hpp
 
 classes:
-  frc::sim::PowerDistributionSim:
+  wpi::sim::PowerDistributionSim:
     force_type_casters:
     - std::function
     methods:
diff --git a/wpilibc/src/main/python/semiwrap/simulation/REVPHSim.yml b/wpilibc/src/main/python/semiwrap/simulation/REVPHSim.yml
index a7d63adb7a..16e23cb778 100644
--- a/wpilibc/src/main/python/semiwrap/simulation/REVPHSim.yml
+++ b/wpilibc/src/main/python/semiwrap/simulation/REVPHSim.yml
@@ -2,9 +2,9 @@ extra_includes:
 - wpi/hardware/pneumatic/Compressor.hpp
 
 classes:
-  frc::sim::REVPHSim:
+  wpi::sim::REVPHSim:
     typealias:
-    - frc::PneumaticsBase
+    - wpi::PneumaticsBase
     force_type_casters:
     - std::function
     methods:
diff --git a/wpilibc/src/main/python/semiwrap/simulation/RoboRioSim.yml b/wpilibc/src/main/python/semiwrap/simulation/RoboRioSim.yml
index 75a6cdb25d..3cdb3fff7e 100644
--- a/wpilibc/src/main/python/semiwrap/simulation/RoboRioSim.yml
+++ b/wpilibc/src/main/python/semiwrap/simulation/RoboRioSim.yml
@@ -1,5 +1,5 @@
 classes:
-  frc::sim::RoboRioSim:
+  wpi::sim::RoboRioSim:
     force_type_casters:
     - std::function
     methods:
diff --git a/wpilibc/src/main/python/semiwrap/simulation/SendableChooserSim.yml b/wpilibc/src/main/python/semiwrap/simulation/SendableChooserSim.yml
index 8fde3ba616..778bc3c9d6 100644
--- a/wpilibc/src/main/python/semiwrap/simulation/SendableChooserSim.yml
+++ b/wpilibc/src/main/python/semiwrap/simulation/SendableChooserSim.yml
@@ -1,8 +1,8 @@
 classes:
-  frc::sim::SendableChooserSim:
+  wpi::sim::SendableChooserSim:
     methods:
       SendableChooserSim:
         overloads:
           std::string_view:
-          nt::NetworkTableInstance, std::string_view:
+          wpi::nt::NetworkTableInstance, std::string_view:
       SetSelected:
diff --git a/wpilibc/src/main/python/semiwrap/simulation/SharpIRSim.yml b/wpilibc/src/main/python/semiwrap/simulation/SharpIRSim.yml
index 5b9659ae7f..3f75e476af 100644
--- a/wpilibc/src/main/python/semiwrap/simulation/SharpIRSim.yml
+++ b/wpilibc/src/main/python/semiwrap/simulation/SharpIRSim.yml
@@ -1,5 +1,5 @@
 classes:
-  frc::SharpIRSim:
+  wpi::SharpIRSim:
     methods:
       SharpIRSim:
         overloads:
diff --git a/wpilibc/src/main/python/semiwrap/simulation/SimDeviceSim.yml b/wpilibc/src/main/python/semiwrap/simulation/SimDeviceSim.yml
index 8be1e5942b..4eac4dc700 100644
--- a/wpilibc/src/main/python/semiwrap/simulation/SimDeviceSim.yml
+++ b/wpilibc/src/main/python/semiwrap/simulation/SimDeviceSim.yml
@@ -2,7 +2,7 @@ extra_includes:
 - pybind11/stl.h
 
 classes:
-  frc::sim::SimDeviceSim:
+  wpi::sim::SimDeviceSim:
     doc: |
       Interact with a generic simulated device
 
@@ -65,7 +65,7 @@ classes:
 
 inline_code: |
   cls_SimDeviceSim
-    .def("enumerateValues", [](frc::sim::SimDeviceSim * that) {
+    .def("enumerateValues", [](wpi::sim::SimDeviceSim * that) {
       std::vector> values;
       that->EnumerateValues([&values](const char * name, HAL_SimValueHandle handle,
                                HAL_Bool readonly, const struct HAL_Value * value){
@@ -76,7 +76,7 @@ inline_code: |
     "Returns a list of (name, readonly) tuples of available values for this device")
     .def_static("enumerateDevices", [](const char * prefix) {
       std::vector devices;
-      frc::sim::SimDeviceSim::EnumerateDevices(prefix, [&devices](const char * name, HAL_SimDeviceHandle handle) {
+      wpi::sim::SimDeviceSim::EnumerateDevices(prefix, [&devices](const char * name, HAL_SimDeviceHandle handle) {
         devices.push_back(std::string(name));
       });
       return devices;
diff --git a/wpilibc/src/main/python/semiwrap/simulation/SingleJointedArmSim.yml b/wpilibc/src/main/python/semiwrap/simulation/SingleJointedArmSim.yml
index 7321580345..08cf0b5e78 100644
--- a/wpilibc/src/main/python/semiwrap/simulation/SingleJointedArmSim.yml
+++ b/wpilibc/src/main/python/semiwrap/simulation/SingleJointedArmSim.yml
@@ -1,17 +1,17 @@
 classes:
-  frc::sim::SingleJointedArmSim:
+  wpi::sim::SingleJointedArmSim:
     typealias:
-    - frc::DCMotor
-    - template  using LinearSystem = frc::LinearSystem
-    - template  using Vectord = frc::Vectord
+    - wpi::math::DCMotor
+    - template  using wpi::math::LinearSystem = wpi::math::LinearSystem
+    - template  using wpi::math::Vectord = wpi::math::Vectord
     methods:
       SingleJointedArmSim:
         overloads:
-          ? const LinearSystem<2, 1, 2>&, const DCMotor&, double, units::meter_t, units::radian_t, units::radian_t, bool, units::radian_t, const std::array&
+          ? const wpi::math::LinearSystem<2, 1, 2>&, const wpi::math::DCMotor&, double, wpi::units::meter_t, wpi::units::radian_t, wpi::units::radian_t, bool, wpi::units::radian_t, const std::array&
           : param_override:
               measurementStdDevs:
                 default: std::array{0.0, 0.0}
-          ? const DCMotor&, double, units::kilogram_square_meter_t, units::meter_t, units::radian_t, units::radian_t, bool, units::radian_t, const std::array&
+          ? const wpi::math::DCMotor&, double, wpi::units::kilogram_square_meter_t, wpi::units::meter_t, wpi::units::radian_t, wpi::units::radian_t, bool, wpi::units::radian_t, const std::array&
           : param_override:
               measurementStdDevs:
                 default: std::array{0.0, 0.0}
@@ -29,10 +29,10 @@ classes:
 
 inline_code: |-
   cls_SingleJointedArmSim
-    .def("getAngleDegrees", [](SingleJointedArmSim * self) -> units::degree_t {
+    .def("getAngleDegrees", [](SingleJointedArmSim * self) -> wpi::units::degree_t {
       return self->GetAngle();
     })
-    .def("getVelocityDps", [](SingleJointedArmSim * self) -> units::degrees_per_second_t {
+    .def("getVelocityDps", [](SingleJointedArmSim * self) -> wpi::units::degrees_per_second_t {
       return self->GetVelocity();
     })
   ;
diff --git a/wpilibc/src/main/python/semiwrap/simulation/SolenoidSim.yml b/wpilibc/src/main/python/semiwrap/simulation/SolenoidSim.yml
index 8cee1025ad..bd495d9805 100644
--- a/wpilibc/src/main/python/semiwrap/simulation/SolenoidSim.yml
+++ b/wpilibc/src/main/python/semiwrap/simulation/SolenoidSim.yml
@@ -1,9 +1,9 @@
 classes:
-  frc::sim::SolenoidSim:
+  wpi::sim::SolenoidSim:
     force_type_casters:
     - std::function
     typealias:
-    - frc::PneumaticsModuleType
+    - wpi::PneumaticsModuleType
     methods:
       SolenoidSim:
         overloads:
diff --git a/wpilibc/src/main/python/semiwrap/simulation/StadiaControllerSim.yml b/wpilibc/src/main/python/semiwrap/simulation/StadiaControllerSim.yml
index 7b3a5a03c4..171bbec1a0 100644
--- a/wpilibc/src/main/python/semiwrap/simulation/StadiaControllerSim.yml
+++ b/wpilibc/src/main/python/semiwrap/simulation/StadiaControllerSim.yml
@@ -2,7 +2,7 @@ extra_includes:
 - wpi/driverstation/StadiaController.hpp
 
 classes:
-  frc::sim::StadiaControllerSim:
+  wpi::sim::StadiaControllerSim:
     force_no_trampoline: true
     methods:
       StadiaControllerSim:
diff --git a/wpilibc/src/main/python/semiwrap/simulation/XboxControllerSim.yml b/wpilibc/src/main/python/semiwrap/simulation/XboxControllerSim.yml
index 540ecd9c9c..9f1eb5813b 100644
--- a/wpilibc/src/main/python/semiwrap/simulation/XboxControllerSim.yml
+++ b/wpilibc/src/main/python/semiwrap/simulation/XboxControllerSim.yml
@@ -2,10 +2,10 @@ extra_includes:
 - wpi/driverstation/XboxController.hpp
 
 classes:
-  frc::sim::XboxControllerSim:
+  wpi::sim::XboxControllerSim:
     force_no_trampoline: true
     typealias:
-    - frc::XboxController
+    - wpi::XboxController
     methods:
       XboxControllerSim:
         overloads:
diff --git a/wpilibc/src/main/python/wpilib/simulation/simulation.cpp b/wpilibc/src/main/python/wpilib/simulation/simulation.cpp
index 107d55fc5c..e3f880e905 100644
--- a/wpilibc/src/main/python/wpilib/simulation/simulation.cpp
+++ b/wpilibc/src/main/python/wpilib/simulation/simulation.cpp
@@ -3,23 +3,23 @@
 
 #ifndef __FRC_SYSTEMCORE__
 
-namespace frc::impl {
+namespace wpi::impl {
 void ResetSmartDashboardInstance();
 void ResetMotorSafety();
-} // namespace frc::impl
+} // namespace wpi::impl
 
 namespace wpi::impl {
 void ResetSendableRegistry();
 } // namespace wpi::impl
 
 void resetWpilibSimulationData() {
-  frc::impl::ResetSmartDashboardInstance();
-  frc::impl::ResetMotorSafety();
+  wpi::impl::ResetSmartDashboardInstance();
+  wpi::impl::ResetMotorSafety();
   wpi::impl::ResetSendableRegistry();
 }
 
 void resetMotorSafety() {
-  frc::impl::ResetMotorSafety();
+  wpi::impl::ResetMotorSafety();
 }
 
 #else
diff --git a/wpilibc/src/main/python/wpilib/src/rpy/MotorControllerGroup.cpp b/wpilibc/src/main/python/wpilib/src/rpy/MotorControllerGroup.cpp
index 5e39962b2f..9243a63bcc 100644
--- a/wpilibc/src/main/python/wpilib/src/rpy/MotorControllerGroup.cpp
+++ b/wpilibc/src/main/python/wpilib/src/rpy/MotorControllerGroup.cpp
@@ -6,15 +6,15 @@
 
 #include "wpi/util/sendable/SendableBuilder.hpp"
 
-using namespace frc;
+using namespace wpi;
 
 void PyMotorControllerGroup::Initialize() {
   for (auto motorController : m_motorControllers) {
-    wpi::SendableRegistry::AddChild(this, motorController.get());
+    wpi::util::SendableRegistry::AddChild(this, motorController.get());
   }
   static int instances = 0;
   ++instances;
-  wpi::SendableRegistry::Add(this, "MotorControllerGroup", instances);
+  wpi::util::SendableRegistry::Add(this, "MotorControllerGroup", instances);
 }
 
 void PyMotorControllerGroup::Set(double speed) {
@@ -23,7 +23,7 @@ void PyMotorControllerGroup::Set(double speed) {
   }
 }
 
-void PyMotorControllerGroup::SetVoltage(units::volt_t output) {
+void PyMotorControllerGroup::SetVoltage(wpi::units::volt_t output) {
   for (auto motorController : m_motorControllers) {
     motorController->SetVoltage(m_isInverted ? -output : output);
   }
@@ -54,7 +54,7 @@ void PyMotorControllerGroup::StopMotor() {
   }
 }
 
-void PyMotorControllerGroup::InitSendable(wpi::SendableBuilder& builder) {
+void PyMotorControllerGroup::InitSendable(wpi::util::SendableBuilder& builder) {
   builder.SetSmartDashboardType("Motor Controller");
   builder.SetActuator(true);
   builder.AddDoubleProperty("Value", [=, this]() { return Get(); },
diff --git a/wpilibc/src/main/python/wpilib/src/rpy/MotorControllerGroup.h b/wpilibc/src/main/python/wpilib/src/rpy/MotorControllerGroup.h
index 54d4043de1..26714d64f7 100644
--- a/wpilibc/src/main/python/wpilib/src/rpy/MotorControllerGroup.h
+++ b/wpilibc/src/main/python/wpilib/src/rpy/MotorControllerGroup.h
@@ -13,13 +13,13 @@
 #include "wpi/util/sendable/Sendable.hpp"
 #include "wpi/util/sendable/SendableHelper.hpp"
 
-namespace frc {
+namespace wpi {
 
-class PyMotorControllerGroup : public wpi::Sendable,
+class PyMotorControllerGroup : public wpi::util::Sendable,
                              public MotorController,
-                             public wpi::SendableHelper {
+                             public wpi::util::SendableHelper {
  public:
-  PyMotorControllerGroup(std::vector> &&args) :
+  PyMotorControllerGroup(std::vector> &&args) :
     m_motorControllers(args) {}
   ~PyMotorControllerGroup() override = default;
 
@@ -27,20 +27,20 @@ class PyMotorControllerGroup : public wpi::Sendable,
   PyMotorControllerGroup& operator=(PyMotorControllerGroup&&) = default;
 
   void Set(double speed) override;
-  void SetVoltage(units::volt_t output) override;
+  void SetVoltage(wpi::units::volt_t output) override;
   double Get() const override;
   void SetInverted(bool isInverted) override;
   bool GetInverted() const override;
   void Disable() override;
   void StopMotor() override;
 
-  void InitSendable(wpi::SendableBuilder& builder) override;
+  void InitSendable(wpi::util::SendableBuilder& builder) override;
 
  private:
   void Initialize();
 
   bool m_isInverted = false;
-  std::vector> m_motorControllers;
+  std::vector> m_motorControllers;
 };
 
 }  // namespace rpy
diff --git a/wpilibc/src/main/python/wpilib/src/rpy/Notifier.cpp b/wpilibc/src/main/python/wpilib/src/rpy/Notifier.cpp
index 62ab763c1d..e12173aa10 100644
--- a/wpilibc/src/main/python/wpilib/src/rpy/Notifier.cpp
+++ b/wpilibc/src/main/python/wpilib/src/rpy/Notifier.cpp
@@ -16,7 +16,7 @@
 #include 
 #include 
 
-using namespace frc;
+using namespace wpi;
 using namespace pybind11::literals;
 
 // Hang the thread since returning to the caller is going to crash when we try
@@ -144,7 +144,7 @@ void PyNotifier::SetCallback(std::function handler) {
   m_handler = handler;
 }
 
-void PyNotifier::StartSingle(units::second_t delay) {
+void PyNotifier::StartSingle(wpi::units::second_t delay) {
   std::scoped_lock lock(m_processMutex);
   m_periodic = false;
   m_period = delay;
@@ -152,7 +152,7 @@ void PyNotifier::StartSingle(units::second_t delay) {
   UpdateAlarm();
 }
 
-void PyNotifier::StartPeriodic(units::second_t period) {
+void PyNotifier::StartPeriodic(wpi::units::second_t period) {
   std::scoped_lock lock(m_processMutex);
   m_periodic = true;
   m_period = period;
diff --git a/wpilibc/src/main/python/wpilib/src/rpy/Notifier.h b/wpilibc/src/main/python/wpilib/src/rpy/Notifier.h
index 8ef024c0cb..ebd39b4fc8 100644
--- a/wpilibc/src/main/python/wpilib/src/rpy/Notifier.h
+++ b/wpilibc/src/main/python/wpilib/src/rpy/Notifier.h
@@ -19,7 +19,7 @@
 
 #include 
 
-namespace frc {
+namespace wpi {
 
 class PyNotifier {
  public:
@@ -66,7 +66,7 @@ class PyNotifier {
    *
    * @param delay Amount of time to wait before the handler is called.
    */
-  void StartSingle(units::second_t delay);
+  void StartSingle(wpi::units::second_t delay);
 
   /**
    * Register for periodic event notification.
@@ -78,7 +78,7 @@ class PyNotifier {
    * @param period Period to call the handler starting one period
    *               after the call to this method.
    */
-  void StartPeriodic(units::second_t period);
+  void StartPeriodic(wpi::units::second_t period);
 
   /**
    * Stop timer events from occurring.
@@ -125,7 +125,7 @@ private:
   py::object m_thread;
 
   // Held while updating process information
-  wpi::mutex m_processMutex;
+  wpi::util::mutex m_processMutex;
 
   // HAL handle, atomic for proper destruction
   std::atomic m_notifier{0};
@@ -134,13 +134,13 @@ private:
   std::function m_handler;
 
   // The absolute expiration time
-  units::second_t m_expirationTime = 0_s;
+  wpi::units::second_t m_expirationTime = 0_s;
 
   // The relative time (either periodic or single)
-  units::second_t m_period = 0_s;
+  wpi::units::second_t m_period = 0_s;
 
   // True if this is a periodic event
   bool m_periodic = false;
 };
 
-} // namespace frc
+} // namespace wpi
diff --git a/wpilibc/src/main/python/wpilib/src/rpy/SmartDashboardData.cpp b/wpilibc/src/main/python/wpilib/src/rpy/SmartDashboardData.cpp
index 13cf561f21..9b8d430024 100644
--- a/wpilibc/src/main/python/wpilib/src/rpy/SmartDashboardData.cpp
+++ b/wpilibc/src/main/python/wpilib/src/rpy/SmartDashboardData.cpp
@@ -15,7 +15,7 @@ static py::dict &getSmartDashboardData() {
   return data;
 }
 
-void addSmartDashboardData(py::str &key, std::shared_ptr data) {
+void addSmartDashboardData(py::str &key, std::shared_ptr data) {
   auto &sdData = getSmartDashboardData();
   sdData[key] = py::cast(data);
 }
diff --git a/wpilibc/src/main/python/wpilib/src/rpy/SmartDashboardData.h b/wpilibc/src/main/python/wpilib/src/rpy/SmartDashboardData.h
index 3d341e34c2..6ec19f63b2 100644
--- a/wpilibc/src/main/python/wpilib/src/rpy/SmartDashboardData.h
+++ b/wpilibc/src/main/python/wpilib/src/rpy/SmartDashboardData.h
@@ -10,7 +10,7 @@ namespace rpy {
 // These functions must be called with the GIL held
 //
 
-void addSmartDashboardData(py::str &key, std::shared_ptr data);
+void addSmartDashboardData(py::str &key, std::shared_ptr data);
 void clearSmartDashboardData();
 void destroySmartDashboardData();
 
diff --git a/wpilibc/src/test/native/cpp/AlertTest.cpp b/wpilibc/src/test/native/cpp/AlertTest.cpp
index 596a5bcd17..0af76e3db6 100644
--- a/wpilibc/src/test/native/cpp/AlertTest.cpp
+++ b/wpilibc/src/test/native/cpp/AlertTest.cpp
@@ -18,7 +18,7 @@
 #include "wpi/smartdashboard/SmartDashboard.hpp"
 #include "wpi/util/Alert.hpp"
 
-using namespace frc;
+using namespace wpi;
 using enum Alert::AlertType;
 class AlertsTest : public ::testing::Test {
  public:
@@ -52,7 +52,7 @@ class AlertsTest : public ::testing::Test {
            activeAlerts.end();
   }
 
-  void Update() { frc::SmartDashboard::UpdateValues(); }
+  void Update() { wpi::SmartDashboard::UpdateValues(); }
 
  private:
   std::string GetSubtableName(Alert::AlertType type) {
@@ -68,8 +68,8 @@ class AlertsTest : public ::testing::Test {
     }
   }
 
-  const nt::StringArraySubscriber GetSubscriberForType(Alert::AlertType type) {
-    return nt::NetworkTableInstance::GetDefault()
+  const wpi::nt::StringArraySubscriber GetSubscriberForType(Alert::AlertType type) {
+    return wpi::nt::NetworkTableInstance::GetDefault()
         .GetStringArrayTopic(fmt::format("/SmartDashboard/{}/{}",
                                          GetGroupName(), GetSubtableName(type)))
         .Subscribe({});
@@ -158,16 +158,16 @@ TEST_F(AlertsTest, SetTextWhileSet) {
 }
 
 TEST_F(AlertsTest, SetTextDoesNotAffectFirstOrderSort) {
-  frc::sim::PauseTiming();
+  wpi::sim::PauseTiming();
 
   auto a = MakeAlert("A", kError);
   auto b = MakeAlert("B", kError);
   auto c = MakeAlert("C", kError);
 
   a.Set(true);
-  frc::sim::StepTiming(1_s);
+  wpi::sim::StepTiming(1_s);
   b.Set(true);
-  frc::sim::StepTiming(1_s);
+  wpi::sim::StepTiming(1_s);
   c.Set(true);
 
   auto expectedEndState = GetActiveAlerts(kError);
@@ -176,7 +176,7 @@ TEST_F(AlertsTest, SetTextDoesNotAffectFirstOrderSort) {
   b.SetText("AFTER");
 
   EXPECT_STATE(kError, expectedEndState);
-  frc::sim::ResumeTiming();
+  wpi::sim::ResumeTiming();
 }
 
 TEST_F(AlertsTest, MoveAssign) {
@@ -209,42 +209,42 @@ TEST_F(AlertsTest, MoveConstruct) {
 }
 
 TEST_F(AlertsTest, SortOrder) {
-  frc::sim::PauseTiming();
+  wpi::sim::PauseTiming();
   auto a = MakeAlert("A", kInfo);
   auto b = MakeAlert("B", kInfo);
   auto c = MakeAlert("C", kInfo);
   a.Set(true);
   EXPECT_STATE(kInfo, "A");
-  frc::sim::StepTiming(1_s);
+  wpi::sim::StepTiming(1_s);
   b.Set(true);
   EXPECT_STATE(kInfo, "B", "A");
-  frc::sim::StepTiming(1_s);
+  wpi::sim::StepTiming(1_s);
   c.Set(true);
   EXPECT_STATE(kInfo, "C", "B", "A");
 
-  frc::sim::StepTiming(1_s);
+  wpi::sim::StepTiming(1_s);
   c.Set(false);
   EXPECT_STATE(kInfo, "B", "A");
 
-  frc::sim::StepTiming(1_s);
+  wpi::sim::StepTiming(1_s);
   c.Set(true);
   EXPECT_STATE(kInfo, "C", "B", "A");
 
-  frc::sim::StepTiming(1_s);
+  wpi::sim::StepTiming(1_s);
   a.Set(false);
   EXPECT_STATE(kInfo, "C", "B");
 
-  frc::sim::StepTiming(1_s);
+  wpi::sim::StepTiming(1_s);
   b.Set(false);
   EXPECT_STATE(kInfo, "C");
 
-  frc::sim::StepTiming(1_s);
+  wpi::sim::StepTiming(1_s);
   b.Set(true);
   EXPECT_STATE(kInfo, "B", "C");
 
-  frc::sim::StepTiming(1_s);
+  wpi::sim::StepTiming(1_s);
   a.Set(true);
   EXPECT_STATE(kInfo, "A", "B", "C");
 
-  frc::sim::ResumeTiming();
+  wpi::sim::ResumeTiming();
 }
diff --git a/wpilibc/src/test/native/cpp/AnalogPotentiometerTest.cpp b/wpilibc/src/test/native/cpp/AnalogPotentiometerTest.cpp
index 1f1fad930a..9d02abeae0 100644
--- a/wpilibc/src/test/native/cpp/AnalogPotentiometerTest.cpp
+++ b/wpilibc/src/test/native/cpp/AnalogPotentiometerTest.cpp
@@ -9,8 +9,8 @@
 #include "wpi/simulation/AnalogInputSim.hpp"
 #include "wpi/simulation/RoboRioSim.hpp"
 
-namespace frc {
-using namespace frc::sim;
+namespace wpi {
+using namespace wpi::sim;
 TEST(AnalogPotentiometerTest, InitializeWithAnalogInput) {
   HAL_Initialize(500, 0);
 
@@ -78,7 +78,7 @@ TEST(AnalogPotentiometerTest, WithModifiedBatteryVoltage) {
   EXPECT_EQ(90, pot.Get());
 
   // Simulate a lower battery voltage
-  RoboRioSim::SetUserVoltage3V3(units::volt_t{2.5});
+  RoboRioSim::SetUserVoltage3V3(wpi::units::volt_t{2.5});
 
   sim.SetVoltage(2.5);
   EXPECT_EQ(270.0, pot.Get());
@@ -89,4 +89,4 @@ TEST(AnalogPotentiometerTest, WithModifiedBatteryVoltage) {
   sim.SetVoltage(0.0);
   EXPECT_EQ(90.0, pot.Get());
 }
-}  // namespace frc
+}  // namespace wpi
diff --git a/wpilibc/src/test/native/cpp/DoubleSolenoidTestCTRE.cpp b/wpilibc/src/test/native/cpp/DoubleSolenoidTestCTRE.cpp
index 6b31311886..b3aaa7c890 100644
--- a/wpilibc/src/test/native/cpp/DoubleSolenoidTestCTRE.cpp
+++ b/wpilibc/src/test/native/cpp/DoubleSolenoidTestCTRE.cpp
@@ -9,10 +9,10 @@
 #include "wpi/hardware/pneumatic/PneumaticsControlModule.hpp"
 #include "wpi/hardware/pneumatic/Solenoid.hpp"
 
-namespace frc {
+namespace wpi {
 
 TEST(DoubleSolenoidCTRETest, ValidInitialization) {
-  DoubleSolenoid solenoid{0, 3, frc::PneumaticsModuleType::CTREPCM, 2, 3};
+  DoubleSolenoid solenoid{0, 3, wpi::PneumaticsModuleType::CTREPCM, 2, 3};
   solenoid.Set(DoubleSolenoid::kReverse);
   EXPECT_EQ(DoubleSolenoid::kReverse, solenoid.Get());
 
@@ -25,29 +25,29 @@ TEST(DoubleSolenoidCTRETest, ValidInitialization) {
 
 TEST(DoubleSolenoidCTRETest, ThrowForwardPortAlreadyInitialized) {
   // Single solenoid that is reused for forward port
-  Solenoid solenoid{0, 5, frc::PneumaticsModuleType::CTREPCM, 2};
-  EXPECT_THROW(DoubleSolenoid(0, 5, frc::PneumaticsModuleType::CTREPCM, 2, 3),
+  Solenoid solenoid{0, 5, wpi::PneumaticsModuleType::CTREPCM, 2};
+  EXPECT_THROW(DoubleSolenoid(0, 5, wpi::PneumaticsModuleType::CTREPCM, 2, 3),
                std::runtime_error);
 }
 
 TEST(DoubleSolenoidCTRETest, ThrowReversePortAlreadyInitialized) {
   // Single solenoid that is reused for forward port
-  Solenoid solenoid{0, 6, frc::PneumaticsModuleType::CTREPCM, 3};
-  EXPECT_THROW(DoubleSolenoid(6, frc::PneumaticsModuleType::CTREPCM, 2, 3),
+  Solenoid solenoid{0, 6, wpi::PneumaticsModuleType::CTREPCM, 3};
+  EXPECT_THROW(DoubleSolenoid(6, wpi::PneumaticsModuleType::CTREPCM, 2, 3),
                std::runtime_error);
 }
 
 TEST(DoubleSolenoidCTRETest, ThrowBothPortsAlreadyInitialized) {
   PneumaticsControlModule pcm{0, 6};
   // Single solenoid that is reused for forward port
-  Solenoid solenoid0(0, 6, frc::PneumaticsModuleType::CTREPCM, 2);
-  Solenoid solenoid1(0, 6, frc::PneumaticsModuleType::CTREPCM, 3);
-  EXPECT_THROW(DoubleSolenoid(6, frc::PneumaticsModuleType::CTREPCM, 2, 3),
+  Solenoid solenoid0(0, 6, wpi::PneumaticsModuleType::CTREPCM, 2);
+  Solenoid solenoid1(0, 6, wpi::PneumaticsModuleType::CTREPCM, 3);
+  EXPECT_THROW(DoubleSolenoid(6, wpi::PneumaticsModuleType::CTREPCM, 2, 3),
                std::runtime_error);
 }
 
 TEST(DoubleSolenoidCTRETest, Toggle) {
-  DoubleSolenoid solenoid{0, 4, frc::PneumaticsModuleType::CTREPCM, 2, 3};
+  DoubleSolenoid solenoid{0, 4, wpi::PneumaticsModuleType::CTREPCM, 2, 3};
   // Bootstrap it into reverse
   solenoid.Set(DoubleSolenoid::kReverse);
 
@@ -64,12 +64,12 @@ TEST(DoubleSolenoidCTRETest, Toggle) {
 }
 
 TEST(DoubleSolenoidCTRETest, InvalidForwardPort) {
-  EXPECT_THROW(DoubleSolenoid(0, 0, frc::PneumaticsModuleType::CTREPCM, 100, 1),
+  EXPECT_THROW(DoubleSolenoid(0, 0, wpi::PneumaticsModuleType::CTREPCM, 100, 1),
                std::runtime_error);
 }
 
 TEST(DoubleSolenoidCTRETest, InvalidReversePort) {
-  EXPECT_THROW(DoubleSolenoid(0, 0, frc::PneumaticsModuleType::CTREPCM, 0, 100),
+  EXPECT_THROW(DoubleSolenoid(0, 0, wpi::PneumaticsModuleType::CTREPCM, 0, 100),
                std::runtime_error);
 }
-}  // namespace frc
+}  // namespace wpi
diff --git a/wpilibc/src/test/native/cpp/DoubleSolenoidTestREV.cpp b/wpilibc/src/test/native/cpp/DoubleSolenoidTestREV.cpp
index 079f6c0e1e..2dbfc738c9 100644
--- a/wpilibc/src/test/native/cpp/DoubleSolenoidTestREV.cpp
+++ b/wpilibc/src/test/native/cpp/DoubleSolenoidTestREV.cpp
@@ -9,10 +9,10 @@
 #include "wpi/hardware/pneumatic/PneumaticsControlModule.hpp"
 #include "wpi/hardware/pneumatic/Solenoid.hpp"
 
-namespace frc {
+namespace wpi {
 
 TEST(DoubleSolenoidREVTest, ValidInitialization) {
-  DoubleSolenoid solenoid{0, 3, frc::PneumaticsModuleType::CTREPCM, 2, 3};
+  DoubleSolenoid solenoid{0, 3, wpi::PneumaticsModuleType::CTREPCM, 2, 3};
   solenoid.Set(DoubleSolenoid::kReverse);
   EXPECT_EQ(DoubleSolenoid::kReverse, solenoid.Get());
 
@@ -25,29 +25,29 @@ TEST(DoubleSolenoidREVTest, ValidInitialization) {
 
 TEST(DoubleSolenoidREVTest, ThrowForwardPortAlreadyInitialized) {
   // Single solenoid that is reused for forward port
-  Solenoid solenoid{0, 5, frc::PneumaticsModuleType::CTREPCM, 2};
-  EXPECT_THROW(DoubleSolenoid(5, frc::PneumaticsModuleType::CTREPCM, 2, 3),
+  Solenoid solenoid{0, 5, wpi::PneumaticsModuleType::CTREPCM, 2};
+  EXPECT_THROW(DoubleSolenoid(5, wpi::PneumaticsModuleType::CTREPCM, 2, 3),
                std::runtime_error);
 }
 
 TEST(DoubleSolenoidREVTest, ThrowReversePortAlreadyInitialized) {
   // Single solenoid that is reused for forward port
-  Solenoid solenoid{0, 6, frc::PneumaticsModuleType::CTREPCM, 3};
-  EXPECT_THROW(DoubleSolenoid(6, frc::PneumaticsModuleType::CTREPCM, 2, 3),
+  Solenoid solenoid{0, 6, wpi::PneumaticsModuleType::CTREPCM, 3};
+  EXPECT_THROW(DoubleSolenoid(6, wpi::PneumaticsModuleType::CTREPCM, 2, 3),
                std::runtime_error);
 }
 
 TEST(DoubleSolenoidREVTest, ThrowBothPortsAlreadyInitialized) {
   PneumaticsControlModule pcm{0, 6};
   // Single solenoid that is reused for forward port
-  Solenoid solenoid0(0, 6, frc::PneumaticsModuleType::CTREPCM, 2);
-  Solenoid solenoid1(0, 6, frc::PneumaticsModuleType::CTREPCM, 3);
-  EXPECT_THROW(DoubleSolenoid(6, frc::PneumaticsModuleType::CTREPCM, 2, 3),
+  Solenoid solenoid0(0, 6, wpi::PneumaticsModuleType::CTREPCM, 2);
+  Solenoid solenoid1(0, 6, wpi::PneumaticsModuleType::CTREPCM, 3);
+  EXPECT_THROW(DoubleSolenoid(6, wpi::PneumaticsModuleType::CTREPCM, 2, 3),
                std::runtime_error);
 }
 
 TEST(DoubleSolenoidREVTest, Toggle) {
-  DoubleSolenoid solenoid{0, 4, frc::PneumaticsModuleType::CTREPCM, 2, 3};
+  DoubleSolenoid solenoid{0, 4, wpi::PneumaticsModuleType::CTREPCM, 2, 3};
   // Bootstrap it into reverse
   solenoid.Set(DoubleSolenoid::kReverse);
 
@@ -64,12 +64,12 @@ TEST(DoubleSolenoidREVTest, Toggle) {
 }
 
 TEST(DoubleSolenoidREVTest, InvalidForwardPort) {
-  EXPECT_THROW(DoubleSolenoid(0, 0, frc::PneumaticsModuleType::CTREPCM, 100, 1),
+  EXPECT_THROW(DoubleSolenoid(0, 0, wpi::PneumaticsModuleType::CTREPCM, 100, 1),
                std::runtime_error);
 }
 
 TEST(DoubleSolenoidREVTest, InvalidReversePort) {
-  EXPECT_THROW(DoubleSolenoid(0, 0, frc::PneumaticsModuleType::CTREPCM, 0, 100),
+  EXPECT_THROW(DoubleSolenoid(0, 0, wpi::PneumaticsModuleType::CTREPCM, 0, 100),
                std::runtime_error);
 }
-}  // namespace frc
+}  // namespace wpi
diff --git a/wpilibc/src/test/native/cpp/DriverStationTest.cpp b/wpilibc/src/test/native/cpp/DriverStationTest.cpp
index 1f70ac3ce4..92742bebae 100644
--- a/wpilibc/src/test/native/cpp/DriverStationTest.cpp
+++ b/wpilibc/src/test/native/cpp/DriverStationTest.cpp
@@ -16,16 +16,16 @@ class IsJoystickConnectedParametersTest
     : public ::testing::TestWithParam> {};
 
 TEST_P(IsJoystickConnectedParametersTest, IsJoystickConnected) {
-  frc::sim::DriverStationSim::SetJoystickAxesMaximumIndex(
+  wpi::sim::DriverStationSim::SetJoystickAxesMaximumIndex(
       1, std::get<0>(GetParam()));
-  frc::sim::DriverStationSim::SetJoystickButtonsMaximumIndex(
+  wpi::sim::DriverStationSim::SetJoystickButtonsMaximumIndex(
       1, std::get<1>(GetParam()));
-  frc::sim::DriverStationSim::SetJoystickPOVsMaximumIndex(
+  wpi::sim::DriverStationSim::SetJoystickPOVsMaximumIndex(
       1, std::get<2>(GetParam()));
-  frc::sim::DriverStationSim::NotifyNewData();
+  wpi::sim::DriverStationSim::NotifyNewData();
 
   ASSERT_EQ(std::get<3>(GetParam()),
-            frc::DriverStation::IsJoystickConnected(1));
+            wpi::DriverStation::IsJoystickConnected(1));
 }
 
 INSTANTIATE_TEST_SUITE_P(IsConnectedTests, IsJoystickConnectedParametersTest,
@@ -44,16 +44,16 @@ TEST_P(JoystickConnectionWarningTest, JoystickConnectionWarnings) {
   ::testing::internal::CaptureStderr();
 
   // Set FMS and Silence settings
-  frc::sim::DriverStationSim::SetFmsAttached(std::get<0>(GetParam()));
-  frc::sim::DriverStationSim::NotifyNewData();
-  frc::DriverStation::SilenceJoystickConnectionWarning(std::get<1>(GetParam()));
+  wpi::sim::DriverStationSim::SetFmsAttached(std::get<0>(GetParam()));
+  wpi::sim::DriverStationSim::NotifyNewData();
+  wpi::DriverStation::SilenceJoystickConnectionWarning(std::get<1>(GetParam()));
 
   // Create joystick and attempt to retrieve button.
-  frc::Joystick joystick(0);
+  wpi::Joystick joystick(0);
   joystick.GetRawButton(1);
 
-  frc::sim::StepTiming(1_s);
-  EXPECT_EQ(frc::DriverStation::IsJoystickConnectionWarningSilenced(),
+  wpi::sim::StepTiming(1_s);
+  EXPECT_EQ(wpi::DriverStation::IsJoystickConnectionWarningSilenced(),
             std::get<2>(GetParam()));
   EXPECT_EQ(::testing::internal::GetCapturedStderr().substr(
                 0, std::get<3>(GetParam()).size()),
diff --git a/wpilibc/src/test/native/cpp/GenericHIDTest.cpp b/wpilibc/src/test/native/cpp/GenericHIDTest.cpp
index 388b9db69e..a7a7cb2e3f 100644
--- a/wpilibc/src/test/native/cpp/GenericHIDTest.cpp
+++ b/wpilibc/src/test/native/cpp/GenericHIDTest.cpp
@@ -7,7 +7,7 @@
 #include "wpi/driverstation/GenericHID.hpp"
 #include "wpi/simulation/GenericHIDSim.hpp"
 
-using namespace frc;
+using namespace wpi;
 using RumbleType = GenericHID::RumbleType;
 static constexpr double kEpsilon = 0.0001;
 TEST(GenericHIDTest, RumbleRange) {
diff --git a/wpilibc/src/test/native/cpp/JoystickTest.cpp b/wpilibc/src/test/native/cpp/JoystickTest.cpp
index 4454d5da81..d4fc628cb1 100644
--- a/wpilibc/src/test/native/cpp/JoystickTest.cpp
+++ b/wpilibc/src/test/native/cpp/JoystickTest.cpp
@@ -9,7 +9,7 @@
 #include "JoystickTestMacros.hpp"
 #include "wpi/simulation/JoystickSim.hpp"
 
-using namespace frc;
+using namespace wpi;
 
 // https://github.com/wpilibsuite/allwpilib/issues/1550
 TEST(JoystickTest, FastDeconstruction) {
@@ -52,18 +52,18 @@ TEST(JoystickTest, GetDirection) {
   joysim.SetX(0.5);
   joysim.SetY(0);
   joysim.NotifyNewData();
-  ASSERT_NEAR(units::radian_t{90_deg}.value(), joy.GetDirection().value(),
+  ASSERT_NEAR(wpi::units::radian_t{90_deg}.value(), joy.GetDirection().value(),
               0.001);
 
   joysim.SetX(0);
   joysim.SetY(-.5);
   joysim.NotifyNewData();
-  ASSERT_NEAR(units::radian_t{0_deg}.value(), joy.GetDirection().value(),
+  ASSERT_NEAR(wpi::units::radian_t{0_deg}.value(), joy.GetDirection().value(),
               0.001);
 
   joysim.SetX(0.5);
   joysim.SetY(-0.5);
   joysim.NotifyNewData();
-  ASSERT_NEAR(units::radian_t{45_deg}.value(), joy.GetDirection().value(),
+  ASSERT_NEAR(wpi::units::radian_t{45_deg}.value(), joy.GetDirection().value(),
               0.001);
 }
diff --git a/wpilibc/src/test/native/cpp/LEDPatternTest.cpp b/wpilibc/src/test/native/cpp/LEDPatternTest.cpp
index e0bd6a009a..4057e2c774 100644
--- a/wpilibc/src/test/native/cpp/LEDPatternTest.cpp
+++ b/wpilibc/src/test/native/cpp/LEDPatternTest.cpp
@@ -9,7 +9,7 @@
 #include "wpi/util/MathExtras.hpp"
 #include "wpi/util/timestamp.h"
 
-namespace frc {
+namespace wpi {
 
 static LEDPattern whiteYellowPurple{[](auto data, auto writer) {
   for (size_t led = 0; led < data.size(); led++) {
@@ -187,7 +187,7 @@ TEST(LEDPatternTest, ScrollRelativeForward) {
 
   // Scrolling at 1/256th of the buffer per second,
   // or 1 individual diode per second
-  auto scroll = pattern.ScrollAtRelativeSpeed(units::hertz_t{1 / 256.0});
+  auto scroll = pattern.ScrollAtRelativeSpeed(wpi::units::hertz_t{1 / 256.0});
 
   static uint64_t now = 0ull;
   WPI_SetNowImpl([] { return now; });
@@ -210,7 +210,7 @@ TEST(LEDPatternTest, ScrollRelativeForward) {
       // t=2,   channel value = (254, 255, 0, ..., 252, 253)
       // t=255, channel value = (1, 2, 3, ..., 255, 0)
       // t=256, channel value = (0, 1, 2, ..., 254, 255)
-      int ch = frc::FloorMod(static_cast(led - time), 256);
+      int ch = wpi::math::FloorMod(static_cast(led - time), 256);
       AssertIndexColor(buffer, led, Color{ch, ch, ch});
     }
   }
@@ -230,7 +230,7 @@ TEST(LEDPatternTest, ScrollRelativeBackward) {
 
   // Scrolling at 1/256th of the buffer per second,
   // or 1 individual diode per second
-  auto scroll = pattern.ScrollAtRelativeSpeed(units::hertz_t{-1 / 256.0});
+  auto scroll = pattern.ScrollAtRelativeSpeed(wpi::units::hertz_t{-1 / 256.0});
 
   static uint64_t now = 0ull;
   WPI_SetNowImpl([] { return now; });
@@ -253,7 +253,7 @@ TEST(LEDPatternTest, ScrollRelativeBackward) {
       // t=2,   channel value = (254, 255, 0, ..., 252, 253)
       // t=255, channel value = (1, 2, 3, ..., 255, 0)
       // t=256, channel value = (0, 1, 2, ..., 254, 255)
-      int ch = frc::FloorMod(static_cast(led + time), 256);
+      int ch = wpi::math::FloorMod(static_cast(led + time), 256);
       AssertIndexColor(buffer, led, Color{ch, ch, ch});
     }
   }
@@ -297,7 +297,7 @@ TEST(LEDPatternTest, ScrollAbsoluteForward) {
       // t=2,   channel value = (254, 255, 0, ..., 252, 253)
       // t=255, channel value = (1, 2, 3, ..., 255, 0)
       // t=256, channel value = (0, 1, 2, ..., 254, 255)
-      int ch = frc::FloorMod(static_cast(led - time), 256);
+      int ch = wpi::math::FloorMod(static_cast(led - time), 256);
       AssertIndexColor(buffer, led, Color{ch, ch, ch});
     }
   }
@@ -341,7 +341,7 @@ TEST(LEDPatternTest, ScrollAbsoluteBackward) {
       // t=2,   channel value = (254, 255, 0, ..., 252, 253)
       // t=255, channel value = (1, 2, 3, ..., 255, 0)
       // t=256, channel value = (0, 1, 2, ..., 254, 255)
-      int ch = frc::FloorMod(static_cast(led + time), 256);
+      int ch = wpi::math::FloorMod(static_cast(led + time), 256);
       AssertIndexColor(buffer, led, Color{ch, ch, ch});
     }
   }
@@ -874,7 +874,7 @@ TEST(LEDPatternTest, RelativeScrollingMask) {
 
   auto pattern = LEDPattern::Steps(colorSteps)
                      .Mask(LEDPattern::Steps(maskSteps))
-                     .ScrollAtRelativeSpeed(units::hertz_t{1e6 / 8.0});
+                     .ScrollAtRelativeSpeed(wpi::units::hertz_t{1e6 / 8.0});
 
   pattern.ApplyTo(buffer);
 
@@ -1029,7 +1029,7 @@ TEST(LEDPatternTest, AbsoluteScrollingMask) {
 
 void AssertIndexColor(std::span data, int index,
                       Color color) {
-  frc::Color8Bit color8bit{color};
+  wpi::Color8Bit color8bit{color};
 
   EXPECT_EQ(color8bit.red, data[index].r & 0xFF);
   EXPECT_EQ(color8bit.green, data[index].g & 0xFF);
@@ -1037,7 +1037,7 @@ void AssertIndexColor(std::span data, int index,
 }
 
 Color LerpColors(Color a, Color b, double t) {
-  return Color{wpi::Lerp(a.red, b.red, t), wpi::Lerp(a.green, b.green, t),
-               wpi::Lerp(a.blue, b.blue, t)};
+  return Color{wpi::util::Lerp(a.red, b.red, t), wpi::util::Lerp(a.green, b.green, t),
+               wpi::util::Lerp(a.blue, b.blue, t)};
 }
-}  // namespace frc
+}  // namespace wpi
diff --git a/wpilibc/src/test/native/cpp/NotifierTest.cpp b/wpilibc/src/test/native/cpp/NotifierTest.cpp
index 2af8892574..64fe065c91 100644
--- a/wpilibc/src/test/native/cpp/NotifierTest.cpp
+++ b/wpilibc/src/test/native/cpp/NotifierTest.cpp
@@ -9,7 +9,7 @@
 #include "wpi/simulation/SimHooks.hpp"
 #include "wpi/system/Notifier.hpp"
 
-using namespace frc;
+using namespace wpi;
 
 namespace {
 
diff --git a/wpilibc/src/test/native/cpp/PS4ControllerTest.cpp b/wpilibc/src/test/native/cpp/PS4ControllerTest.cpp
index 09dc06517a..6e7bae8b89 100644
--- a/wpilibc/src/test/native/cpp/PS4ControllerTest.cpp
+++ b/wpilibc/src/test/native/cpp/PS4ControllerTest.cpp
@@ -9,7 +9,7 @@
 #include "JoystickTestMacros.hpp"
 #include "wpi/simulation/PS4ControllerSim.hpp"
 
-using namespace frc;
+using namespace wpi;
 
 BUTTON_TEST(PS4Controller, SquareButton)
 BUTTON_TEST(PS4Controller, CrossButton)
diff --git a/wpilibc/src/test/native/cpp/PS5ControllerTest.cpp b/wpilibc/src/test/native/cpp/PS5ControllerTest.cpp
index 11b6fd59f3..1a6a5b905b 100644
--- a/wpilibc/src/test/native/cpp/PS5ControllerTest.cpp
+++ b/wpilibc/src/test/native/cpp/PS5ControllerTest.cpp
@@ -9,7 +9,7 @@
 #include "JoystickTestMacros.hpp"
 #include "wpi/simulation/PS5ControllerSim.hpp"
 
-using namespace frc;
+using namespace wpi;
 
 BUTTON_TEST(PS5Controller, SquareButton)
 BUTTON_TEST(PS5Controller, CrossButton)
diff --git a/wpilibc/src/test/native/cpp/ScopedTracerTest.cpp b/wpilibc/src/test/native/cpp/ScopedTracerTest.cpp
index b1fce42b8e..49f391a8f7 100644
--- a/wpilibc/src/test/native/cpp/ScopedTracerTest.cpp
+++ b/wpilibc/src/test/native/cpp/ScopedTracerTest.cpp
@@ -13,16 +13,16 @@
 #include "wpi/util/raw_ostream.hpp"
 
 TEST(ScopedTracerTest, Timing) {
-  wpi::SmallString<128> buf;
-  wpi::raw_svector_ostream os(buf);
+  wpi::util::SmallString<128> buf;
+  wpi::util::raw_svector_ostream os(buf);
 
-  frc::sim::PauseTiming();
+  wpi::sim::PauseTiming();
   {
-    frc::ScopedTracer tracer("timing_test", os);
-    frc::sim::StepTiming(1.5_s);
+    wpi::ScopedTracer tracer("timing_test", os);
+    wpi::sim::StepTiming(1.5_s);
   }
-  frc::sim::ResumeTiming();
+  wpi::sim::ResumeTiming();
 
   std::string_view out = os.str();
-  EXPECT_TRUE(wpi::starts_with(out, "\ttiming_test: 1.5"));
+  EXPECT_TRUE(wpi::util::starts_with(out, "\ttiming_test: 1.5"));
 }
diff --git a/wpilibc/src/test/native/cpp/SharpIRTest.cpp b/wpilibc/src/test/native/cpp/SharpIRTest.cpp
index 84074a08d9..6ebc8046ea 100644
--- a/wpilibc/src/test/native/cpp/SharpIRTest.cpp
+++ b/wpilibc/src/test/native/cpp/SharpIRTest.cpp
@@ -7,7 +7,7 @@
 #include "wpi/hardware/range/SharpIR.hpp"
 #include "wpi/simulation/SharpIRSim.hpp"
 
-using namespace frc;
+using namespace wpi;
 
 TEST(SharpIRTest, SimDevices) {
   SharpIR s = SharpIR::GP2Y0A02YK0F(1);
diff --git a/wpilibc/src/test/native/cpp/SolenoidTestCTRE.cpp b/wpilibc/src/test/native/cpp/SolenoidTestCTRE.cpp
index 83676caf30..516bc708ac 100644
--- a/wpilibc/src/test/native/cpp/SolenoidTestCTRE.cpp
+++ b/wpilibc/src/test/native/cpp/SolenoidTestCTRE.cpp
@@ -9,9 +9,9 @@
 #include "wpi/hardware/pneumatic/PneumaticsControlModule.hpp"
 #include "wpi/hardware/pneumatic/Solenoid.hpp"
 
-namespace frc {
+namespace wpi {
 TEST(SolenoidCTRETest, ValidInitialization) {
-  Solenoid solenoid{0, 3, frc::PneumaticsModuleType::CTREPCM, 2};
+  Solenoid solenoid{0, 3, wpi::PneumaticsModuleType::CTREPCM, 2};
   EXPECT_EQ(2, solenoid.GetChannel());
 
   solenoid.Set(true);
@@ -22,24 +22,24 @@ TEST(SolenoidCTRETest, ValidInitialization) {
 }
 
 TEST(SolenoidCTRETest, DoubleInitialization) {
-  Solenoid solenoid{0, 3, frc::PneumaticsModuleType::CTREPCM, 2};
-  EXPECT_THROW(Solenoid(0, 3, frc::PneumaticsModuleType::CTREPCM, 2),
+  Solenoid solenoid{0, 3, wpi::PneumaticsModuleType::CTREPCM, 2};
+  EXPECT_THROW(Solenoid(0, 3, wpi::PneumaticsModuleType::CTREPCM, 2),
                std::runtime_error);
 }
 
 TEST(SolenoidCTRETest, DoubleInitializationFromDoubleSolenoid) {
-  DoubleSolenoid solenoid{0, 3, frc::PneumaticsModuleType::CTREPCM, 2, 3};
-  EXPECT_THROW(Solenoid(0, 3, frc::PneumaticsModuleType::CTREPCM, 2),
+  DoubleSolenoid solenoid{0, 3, wpi::PneumaticsModuleType::CTREPCM, 2, 3};
+  EXPECT_THROW(Solenoid(0, 3, wpi::PneumaticsModuleType::CTREPCM, 2),
                std::runtime_error);
 }
 
 TEST(SolenoidCTRETest, InvalidChannel) {
-  EXPECT_THROW(Solenoid(0, 3, frc::PneumaticsModuleType::CTREPCM, 100),
+  EXPECT_THROW(Solenoid(0, 3, wpi::PneumaticsModuleType::CTREPCM, 100),
                std::runtime_error);
 }
 
 TEST(SolenoidCTRETest, Toggle) {
-  Solenoid solenoid{0, 3, frc::PneumaticsModuleType::CTREPCM, 2};
+  Solenoid solenoid{0, 3, wpi::PneumaticsModuleType::CTREPCM, 2};
   solenoid.Set(true);
   EXPECT_TRUE(solenoid.Get());
 
@@ -49,4 +49,4 @@ TEST(SolenoidCTRETest, Toggle) {
   solenoid.Toggle();
   EXPECT_TRUE(solenoid.Get());
 }
-}  // namespace frc
+}  // namespace wpi
diff --git a/wpilibc/src/test/native/cpp/SolenoidTestREV.cpp b/wpilibc/src/test/native/cpp/SolenoidTestREV.cpp
index e899a9ad2b..4042e274b4 100644
--- a/wpilibc/src/test/native/cpp/SolenoidTestREV.cpp
+++ b/wpilibc/src/test/native/cpp/SolenoidTestREV.cpp
@@ -9,9 +9,9 @@
 #include "wpi/hardware/pneumatic/PneumaticsControlModule.hpp"
 #include "wpi/hardware/pneumatic/Solenoid.hpp"
 
-namespace frc {
+namespace wpi {
 TEST(SolenoidREVTest, ValidInitialization) {
-  Solenoid solenoid{0, 3, frc::PneumaticsModuleType::REVPH, 2};
+  Solenoid solenoid{0, 3, wpi::PneumaticsModuleType::REVPH, 2};
   EXPECT_EQ(2, solenoid.GetChannel());
 
   solenoid.Set(true);
@@ -22,24 +22,24 @@ TEST(SolenoidREVTest, ValidInitialization) {
 }
 
 TEST(SolenoidREVTest, DoubleInitialization) {
-  Solenoid solenoid{0, 3, frc::PneumaticsModuleType::REVPH, 2};
-  EXPECT_THROW(Solenoid(0, 3, frc::PneumaticsModuleType::REVPH, 2),
+  Solenoid solenoid{0, 3, wpi::PneumaticsModuleType::REVPH, 2};
+  EXPECT_THROW(Solenoid(0, 3, wpi::PneumaticsModuleType::REVPH, 2),
                std::runtime_error);
 }
 
 TEST(SolenoidREVTest, DoubleInitializationFromDoubleSolenoid) {
-  DoubleSolenoid solenoid{0, 3, frc::PneumaticsModuleType::REVPH, 2, 3};
-  EXPECT_THROW(Solenoid(0, 3, frc::PneumaticsModuleType::REVPH, 2),
+  DoubleSolenoid solenoid{0, 3, wpi::PneumaticsModuleType::REVPH, 2, 3};
+  EXPECT_THROW(Solenoid(0, 3, wpi::PneumaticsModuleType::REVPH, 2),
                std::runtime_error);
 }
 
 TEST(SolenoidREVTest, InvalidChannel) {
-  EXPECT_THROW(Solenoid(0, 3, frc::PneumaticsModuleType::REVPH, 100),
+  EXPECT_THROW(Solenoid(0, 3, wpi::PneumaticsModuleType::REVPH, 100),
                std::runtime_error);
 }
 
 TEST(SolenoidREVTest, Toggle) {
-  Solenoid solenoid{0, 3, frc::PneumaticsModuleType::REVPH, 2};
+  Solenoid solenoid{0, 3, wpi::PneumaticsModuleType::REVPH, 2};
   solenoid.Set(true);
   EXPECT_TRUE(solenoid.Get());
 
@@ -49,4 +49,4 @@ TEST(SolenoidREVTest, Toggle) {
   solenoid.Toggle();
   EXPECT_TRUE(solenoid.Get());
 }
-}  // namespace frc
+}  // namespace wpi
diff --git a/wpilibc/src/test/native/cpp/TestCallbackHelpers.cpp b/wpilibc/src/test/native/cpp/TestCallbackHelpers.cpp
index f639adc5e8..e9fc2e08f8 100644
--- a/wpilibc/src/test/native/cpp/TestCallbackHelpers.cpp
+++ b/wpilibc/src/test/native/cpp/TestCallbackHelpers.cpp
@@ -6,7 +6,7 @@
 
 #include 
 
-namespace frc::sim {
+namespace wpi::sim {
 
 void BooleanCallback::HandleCallback(std::string_view name,
                                      const HAL_Value* value) {
@@ -82,4 +82,4 @@ void DoubleCallback::HandleCallback(std::string_view name,
   m_lastValue = value->data.v_double;
 }
 
-}  // namespace frc::sim
+}  // namespace wpi::sim
diff --git a/wpilibc/src/test/native/cpp/TimedRobotTest.cpp b/wpilibc/src/test/native/cpp/TimedRobotTest.cpp
index 967604be45..8cf5057ee2 100644
--- a/wpilibc/src/test/native/cpp/TimedRobotTest.cpp
+++ b/wpilibc/src/test/native/cpp/TimedRobotTest.cpp
@@ -14,16 +14,16 @@
 #include "wpi/simulation/DriverStationSim.hpp"
 #include "wpi/simulation/SimHooks.hpp"
 
-using namespace frc;
+using namespace wpi;
 
 inline constexpr auto kPeriod = 20_ms;
 
 namespace {
 class TimedRobotTest : public ::testing::Test {
  protected:
-  void SetUp() override { frc::sim::PauseTiming(); }
+  void SetUp() override { wpi::sim::PauseTiming(); }
 
-  void TearDown() override { frc::sim::ResumeTiming(); }
+  void TearDown() override { wpi::sim::ResumeTiming(); }
 };
 
 class MockRobot : public TimedRobot {
@@ -85,9 +85,9 @@ TEST_F(TimedRobotTest, DisabledMode) {
 
   std::thread robotThread{[&] { robot.StartCompetition(); }};
 
-  frc::sim::DriverStationSim::SetEnabled(false);
-  frc::sim::DriverStationSim::NotifyNewData();
-  frc::sim::StepTiming(0_ms);  // Wait for Notifiers
+  wpi::sim::DriverStationSim::SetEnabled(false);
+  wpi::sim::DriverStationSim::NotifyNewData();
+  wpi::sim::StepTiming(0_ms);  // Wait for Notifiers
 
   EXPECT_EQ(1u, robot.m_simulationInitCount);
   EXPECT_EQ(0u, robot.m_disabledInitCount);
@@ -107,7 +107,7 @@ TEST_F(TimedRobotTest, DisabledMode) {
   EXPECT_EQ(0u, robot.m_teleopExitCount);
   EXPECT_EQ(0u, robot.m_testExitCount);
 
-  frc::sim::StepTiming(kPeriod);
+  wpi::sim::StepTiming(kPeriod);
 
   EXPECT_EQ(1u, robot.m_simulationInitCount);
   EXPECT_EQ(1u, robot.m_disabledInitCount);
@@ -127,7 +127,7 @@ TEST_F(TimedRobotTest, DisabledMode) {
   EXPECT_EQ(0u, robot.m_teleopExitCount);
   EXPECT_EQ(0u, robot.m_testExitCount);
 
-  frc::sim::StepTiming(kPeriod);
+  wpi::sim::StepTiming(kPeriod);
 
   EXPECT_EQ(1u, robot.m_simulationInitCount);
   EXPECT_EQ(1u, robot.m_disabledInitCount);
@@ -156,11 +156,11 @@ TEST_F(TimedRobotTest, AutonomousMode) {
 
   std::thread robotThread{[&] { robot.StartCompetition(); }};
 
-  frc::sim::DriverStationSim::SetEnabled(true);
-  frc::sim::DriverStationSim::SetAutonomous(true);
-  frc::sim::DriverStationSim::SetTest(false);
-  frc::sim::DriverStationSim::NotifyNewData();
-  frc::sim::StepTiming(0_ms);  // Wait for Notifiers
+  wpi::sim::DriverStationSim::SetEnabled(true);
+  wpi::sim::DriverStationSim::SetAutonomous(true);
+  wpi::sim::DriverStationSim::SetTest(false);
+  wpi::sim::DriverStationSim::NotifyNewData();
+  wpi::sim::StepTiming(0_ms);  // Wait for Notifiers
 
   EXPECT_EQ(1u, robot.m_simulationInitCount);
   EXPECT_EQ(0u, robot.m_disabledInitCount);
@@ -180,7 +180,7 @@ TEST_F(TimedRobotTest, AutonomousMode) {
   EXPECT_EQ(0u, robot.m_teleopExitCount);
   EXPECT_EQ(0u, robot.m_testExitCount);
 
-  frc::sim::StepTiming(kPeriod);
+  wpi::sim::StepTiming(kPeriod);
 
   EXPECT_EQ(1u, robot.m_simulationInitCount);
   EXPECT_EQ(0u, robot.m_disabledInitCount);
@@ -200,7 +200,7 @@ TEST_F(TimedRobotTest, AutonomousMode) {
   EXPECT_EQ(0u, robot.m_teleopExitCount);
   EXPECT_EQ(0u, robot.m_testExitCount);
 
-  frc::sim::StepTiming(kPeriod);
+  wpi::sim::StepTiming(kPeriod);
 
   EXPECT_EQ(1u, robot.m_simulationInitCount);
   EXPECT_EQ(0u, robot.m_disabledInitCount);
@@ -229,11 +229,11 @@ TEST_F(TimedRobotTest, TeleopMode) {
 
   std::thread robotThread{[&] { robot.StartCompetition(); }};
 
-  frc::sim::DriverStationSim::SetEnabled(true);
-  frc::sim::DriverStationSim::SetAutonomous(false);
-  frc::sim::DriverStationSim::SetTest(false);
-  frc::sim::DriverStationSim::NotifyNewData();
-  frc::sim::StepTiming(0_ms);  // Wait for Notifiers
+  wpi::sim::DriverStationSim::SetEnabled(true);
+  wpi::sim::DriverStationSim::SetAutonomous(false);
+  wpi::sim::DriverStationSim::SetTest(false);
+  wpi::sim::DriverStationSim::NotifyNewData();
+  wpi::sim::StepTiming(0_ms);  // Wait for Notifiers
 
   EXPECT_EQ(1u, robot.m_simulationInitCount);
   EXPECT_EQ(0u, robot.m_disabledInitCount);
@@ -253,7 +253,7 @@ TEST_F(TimedRobotTest, TeleopMode) {
   EXPECT_EQ(0u, robot.m_teleopExitCount);
   EXPECT_EQ(0u, robot.m_testExitCount);
 
-  frc::sim::StepTiming(kPeriod);
+  wpi::sim::StepTiming(kPeriod);
 
   EXPECT_EQ(1u, robot.m_simulationInitCount);
   EXPECT_EQ(0u, robot.m_disabledInitCount);
@@ -273,7 +273,7 @@ TEST_F(TimedRobotTest, TeleopMode) {
   EXPECT_EQ(0u, robot.m_teleopExitCount);
   EXPECT_EQ(0u, robot.m_testExitCount);
 
-  frc::sim::StepTiming(kPeriod);
+  wpi::sim::StepTiming(kPeriod);
 
   EXPECT_EQ(1u, robot.m_simulationInitCount);
   EXPECT_EQ(0u, robot.m_disabledInitCount);
@@ -301,11 +301,11 @@ TEST_F(TimedRobotTest, TestMode) {
   MockRobot robot;
   std::thread robotThread{[&] { robot.StartCompetition(); }};
 
-  frc::sim::DriverStationSim::SetEnabled(true);
-  frc::sim::DriverStationSim::SetAutonomous(false);
-  frc::sim::DriverStationSim::SetTest(true);
-  frc::sim::DriverStationSim::NotifyNewData();
-  frc::sim::StepTiming(0_ms);  // Wait for Notifiers
+  wpi::sim::DriverStationSim::SetEnabled(true);
+  wpi::sim::DriverStationSim::SetAutonomous(false);
+  wpi::sim::DriverStationSim::SetTest(true);
+  wpi::sim::DriverStationSim::NotifyNewData();
+  wpi::sim::StepTiming(0_ms);  // Wait for Notifiers
 
   EXPECT_EQ(1u, robot.m_simulationInitCount);
   EXPECT_EQ(0u, robot.m_disabledInitCount);
@@ -325,7 +325,7 @@ TEST_F(TimedRobotTest, TestMode) {
   EXPECT_EQ(0u, robot.m_teleopExitCount);
   EXPECT_EQ(0u, robot.m_testExitCount);
 
-  frc::sim::StepTiming(kPeriod);
+  wpi::sim::StepTiming(kPeriod);
 
   EXPECT_EQ(1u, robot.m_simulationInitCount);
   EXPECT_EQ(0u, robot.m_disabledInitCount);
@@ -345,7 +345,7 @@ TEST_F(TimedRobotTest, TestMode) {
   EXPECT_EQ(0u, robot.m_teleopExitCount);
   EXPECT_EQ(0u, robot.m_testExitCount);
 
-  frc::sim::StepTiming(kPeriod);
+  wpi::sim::StepTiming(kPeriod);
 
   EXPECT_EQ(1u, robot.m_simulationInitCount);
   EXPECT_EQ(0u, robot.m_disabledInitCount);
@@ -365,11 +365,11 @@ TEST_F(TimedRobotTest, TestMode) {
   EXPECT_EQ(0u, robot.m_teleopExitCount);
   EXPECT_EQ(0u, robot.m_testExitCount);
 
-  frc::sim::DriverStationSim::SetEnabled(false);
-  frc::sim::DriverStationSim::SetAutonomous(false);
-  frc::sim::DriverStationSim::SetTest(false);
-  frc::sim::DriverStationSim::NotifyNewData();
-  frc::sim::StepTiming(20_ms);  // Wait for Notifiers
+  wpi::sim::DriverStationSim::SetEnabled(false);
+  wpi::sim::DriverStationSim::SetAutonomous(false);
+  wpi::sim::DriverStationSim::SetTest(false);
+  wpi::sim::DriverStationSim::NotifyNewData();
+  wpi::sim::StepTiming(20_ms);  // Wait for Notifiers
 
   EXPECT_EQ(1u, robot.m_simulationInitCount);
   EXPECT_EQ(1u, robot.m_disabledInitCount);
@@ -399,11 +399,11 @@ TEST_F(TimedRobotTest, ModeChange) {
   std::thread robotThread{[&] { robot.StartCompetition(); }};
 
   // Start in disabled
-  frc::sim::DriverStationSim::SetEnabled(false);
-  frc::sim::DriverStationSim::SetAutonomous(false);
-  frc::sim::DriverStationSim::SetTest(false);
-  frc::sim::DriverStationSim::NotifyNewData();
-  frc::sim::StepTiming(0_ms);  // Wait for Notifiers
+  wpi::sim::DriverStationSim::SetEnabled(false);
+  wpi::sim::DriverStationSim::SetAutonomous(false);
+  wpi::sim::DriverStationSim::SetTest(false);
+  wpi::sim::DriverStationSim::NotifyNewData();
+  wpi::sim::StepTiming(0_ms);  // Wait for Notifiers
 
   EXPECT_EQ(0u, robot.m_disabledInitCount);
   EXPECT_EQ(0u, robot.m_autonomousInitCount);
@@ -415,7 +415,7 @@ TEST_F(TimedRobotTest, ModeChange) {
   EXPECT_EQ(0u, robot.m_teleopExitCount);
   EXPECT_EQ(0u, robot.m_testExitCount);
 
-  frc::sim::StepTiming(kPeriod);
+  wpi::sim::StepTiming(kPeriod);
 
   EXPECT_EQ(1u, robot.m_disabledInitCount);
   EXPECT_EQ(0u, robot.m_autonomousInitCount);
@@ -428,12 +428,12 @@ TEST_F(TimedRobotTest, ModeChange) {
   EXPECT_EQ(0u, robot.m_testExitCount);
 
   // Transition to autonomous
-  frc::sim::DriverStationSim::SetEnabled(true);
-  frc::sim::DriverStationSim::SetAutonomous(true);
-  frc::sim::DriverStationSim::SetTest(false);
-  frc::sim::DriverStationSim::NotifyNewData();
+  wpi::sim::DriverStationSim::SetEnabled(true);
+  wpi::sim::DriverStationSim::SetAutonomous(true);
+  wpi::sim::DriverStationSim::SetTest(false);
+  wpi::sim::DriverStationSim::NotifyNewData();
 
-  frc::sim::StepTiming(kPeriod);
+  wpi::sim::StepTiming(kPeriod);
 
   EXPECT_EQ(1u, robot.m_disabledInitCount);
   EXPECT_EQ(1u, robot.m_autonomousInitCount);
@@ -446,12 +446,12 @@ TEST_F(TimedRobotTest, ModeChange) {
   EXPECT_EQ(0u, robot.m_testExitCount);
 
   // Transition to teleop
-  frc::sim::DriverStationSim::SetEnabled(true);
-  frc::sim::DriverStationSim::SetAutonomous(false);
-  frc::sim::DriverStationSim::SetTest(false);
-  frc::sim::DriverStationSim::NotifyNewData();
+  wpi::sim::DriverStationSim::SetEnabled(true);
+  wpi::sim::DriverStationSim::SetAutonomous(false);
+  wpi::sim::DriverStationSim::SetTest(false);
+  wpi::sim::DriverStationSim::NotifyNewData();
 
-  frc::sim::StepTiming(kPeriod);
+  wpi::sim::StepTiming(kPeriod);
 
   EXPECT_EQ(1u, robot.m_disabledInitCount);
   EXPECT_EQ(1u, robot.m_autonomousInitCount);
@@ -464,12 +464,12 @@ TEST_F(TimedRobotTest, ModeChange) {
   EXPECT_EQ(0u, robot.m_testExitCount);
 
   // Transition to test
-  frc::sim::DriverStationSim::SetEnabled(true);
-  frc::sim::DriverStationSim::SetAutonomous(false);
-  frc::sim::DriverStationSim::SetTest(true);
-  frc::sim::DriverStationSim::NotifyNewData();
+  wpi::sim::DriverStationSim::SetEnabled(true);
+  wpi::sim::DriverStationSim::SetAutonomous(false);
+  wpi::sim::DriverStationSim::SetTest(true);
+  wpi::sim::DriverStationSim::NotifyNewData();
 
-  frc::sim::StepTiming(kPeriod);
+  wpi::sim::StepTiming(kPeriod);
 
   EXPECT_EQ(1u, robot.m_disabledInitCount);
   EXPECT_EQ(1u, robot.m_autonomousInitCount);
@@ -482,12 +482,12 @@ TEST_F(TimedRobotTest, ModeChange) {
   EXPECT_EQ(0u, robot.m_testExitCount);
 
   // Transition to disabled
-  frc::sim::DriverStationSim::SetEnabled(false);
-  frc::sim::DriverStationSim::SetAutonomous(false);
-  frc::sim::DriverStationSim::SetTest(false);
-  frc::sim::DriverStationSim::NotifyNewData();
+  wpi::sim::DriverStationSim::SetEnabled(false);
+  wpi::sim::DriverStationSim::SetAutonomous(false);
+  wpi::sim::DriverStationSim::SetTest(false);
+  wpi::sim::DriverStationSim::NotifyNewData();
 
-  frc::sim::StepTiming(kPeriod);
+  wpi::sim::StepTiming(kPeriod);
 
   EXPECT_EQ(2u, robot.m_disabledInitCount);
   EXPECT_EQ(1u, robot.m_autonomousInitCount);
@@ -511,21 +511,21 @@ TEST_F(TimedRobotTest, AddPeriodic) {
 
   std::thread robotThread{[&] { robot.StartCompetition(); }};
 
-  frc::sim::DriverStationSim::SetEnabled(false);
-  frc::sim::DriverStationSim::NotifyNewData();
-  frc::sim::StepTiming(0_ms);  // Wait for Notifiers
+  wpi::sim::DriverStationSim::SetEnabled(false);
+  wpi::sim::DriverStationSim::NotifyNewData();
+  wpi::sim::StepTiming(0_ms);  // Wait for Notifiers
 
   EXPECT_EQ(0u, robot.m_disabledInitCount);
   EXPECT_EQ(0u, robot.m_disabledPeriodicCount);
   EXPECT_EQ(0u, callbackCount);
 
-  frc::sim::StepTiming(kPeriod / 2.0);
+  wpi::sim::StepTiming(kPeriod / 2.0);
 
   EXPECT_EQ(0u, robot.m_disabledInitCount);
   EXPECT_EQ(0u, robot.m_disabledPeriodicCount);
   EXPECT_EQ(1u, callbackCount);
 
-  frc::sim::StepTiming(kPeriod / 2.0);
+  wpi::sim::StepTiming(kPeriod / 2.0);
 
   EXPECT_EQ(1u, robot.m_disabledInitCount);
   EXPECT_EQ(1u, robot.m_disabledPeriodicCount);
@@ -550,33 +550,33 @@ TEST_F(TimedRobotTest, AddPeriodicWithOffset) {
 
   std::thread robotThread{[&] { robot.StartCompetition(); }};
 
-  frc::sim::DriverStationSim::SetEnabled(false);
-  frc::sim::DriverStationSim::NotifyNewData();
-  frc::sim::StepTiming(0_ms);  // Wait for Notifiers
+  wpi::sim::DriverStationSim::SetEnabled(false);
+  wpi::sim::DriverStationSim::NotifyNewData();
+  wpi::sim::StepTiming(0_ms);  // Wait for Notifiers
 
   EXPECT_EQ(0u, robot.m_disabledInitCount);
   EXPECT_EQ(0u, robot.m_disabledPeriodicCount);
   EXPECT_EQ(0u, callbackCount);
 
-  frc::sim::StepTiming(kPeriod * 3.0 / 8.0);
+  wpi::sim::StepTiming(kPeriod * 3.0 / 8.0);
 
   EXPECT_EQ(0u, robot.m_disabledInitCount);
   EXPECT_EQ(0u, robot.m_disabledPeriodicCount);
   EXPECT_EQ(0u, callbackCount);
 
-  frc::sim::StepTiming(kPeriod * 3.0 / 8.0);
+  wpi::sim::StepTiming(kPeriod * 3.0 / 8.0);
 
   EXPECT_EQ(0u, robot.m_disabledInitCount);
   EXPECT_EQ(0u, robot.m_disabledPeriodicCount);
   EXPECT_EQ(1u, callbackCount);
 
-  frc::sim::StepTiming(kPeriod / 4.0);
+  wpi::sim::StepTiming(kPeriod / 4.0);
 
   EXPECT_EQ(1u, robot.m_disabledInitCount);
   EXPECT_EQ(1u, robot.m_disabledPeriodicCount);
   EXPECT_EQ(1u, callbackCount);
 
-  frc::sim::StepTiming(kPeriod / 4.0);
+  wpi::sim::StepTiming(kPeriod / 4.0);
 
   EXPECT_EQ(1u, robot.m_disabledInitCount);
   EXPECT_EQ(1u, robot.m_disabledPeriodicCount);
diff --git a/wpilibc/src/test/native/cpp/TimerTest.cpp b/wpilibc/src/test/native/cpp/TimerTest.cpp
index 120aaf2504..c3a9b13b55 100644
--- a/wpilibc/src/test/native/cpp/TimerTest.cpp
+++ b/wpilibc/src/test/native/cpp/TimerTest.cpp
@@ -8,17 +8,17 @@
 
 #include "wpi/simulation/SimHooks.hpp"
 
-using namespace frc;
+using namespace wpi;
 
 namespace {
 class TimerTest : public ::testing::Test {
  protected:
   void SetUp() override {
-    frc::sim::PauseTiming();
-    frc::sim::RestartTiming();
+    wpi::sim::PauseTiming();
+    wpi::sim::RestartTiming();
   }
 
-  void TearDown() override { frc::sim::ResumeTiming(); }
+  void TearDown() override { wpi::sim::ResumeTiming(); }
 };
 
 }  // namespace
@@ -29,19 +29,19 @@ TEST_F(TimerTest, StartStop) {
   // Verify timer is initialized as stopped
   EXPECT_EQ(timer.Get(), 0_s);
   EXPECT_FALSE(timer.IsRunning());
-  frc::sim::StepTiming(500_ms);
+  wpi::sim::StepTiming(500_ms);
   EXPECT_EQ(timer.Get(), 0_s);
   EXPECT_FALSE(timer.IsRunning());
 
   // Verify timer increments after it's started
   timer.Start();
-  frc::sim::StepTiming(500_ms);
+  wpi::sim::StepTiming(500_ms);
   EXPECT_EQ(timer.Get(), 500_ms);
   EXPECT_TRUE(timer.IsRunning());
 
   // Verify timer stops incrementing after it's stopped
   timer.Stop();
-  frc::sim::StepTiming(500_ms);
+  wpi::sim::StepTiming(500_ms);
   EXPECT_EQ(timer.Get(), 500_ms);
   EXPECT_FALSE(timer.IsRunning());
 }
@@ -52,7 +52,7 @@ TEST_F(TimerTest, Reset) {
 
   // Advance timer to 500 ms
   EXPECT_EQ(timer.Get(), 0_s);
-  frc::sim::StepTiming(500_ms);
+  wpi::sim::StepTiming(500_ms);
   EXPECT_EQ(timer.Get(), 500_ms);
 
   // Verify timer reports 0 ms after reset
@@ -60,13 +60,13 @@ TEST_F(TimerTest, Reset) {
   EXPECT_EQ(timer.Get(), 0_s);
 
   // Verify timer continues incrementing
-  frc::sim::StepTiming(500_ms);
+  wpi::sim::StepTiming(500_ms);
   EXPECT_EQ(timer.Get(), 500_ms);
 
   // Verify timer doesn't start incrementing after reset if it was stopped
   timer.Stop();
   timer.Reset();
-  frc::sim::StepTiming(500_ms);
+  wpi::sim::StepTiming(500_ms);
   EXPECT_EQ(timer.Get(), 0_ms);
 }
 
@@ -77,13 +77,13 @@ TEST_F(TimerTest, HasElapsed) {
   EXPECT_TRUE(timer.HasElapsed(0_s));
 
   // Verify timer doesn't report elapsed time when stopped
-  frc::sim::StepTiming(500_ms);
+  wpi::sim::StepTiming(500_ms);
   EXPECT_FALSE(timer.HasElapsed(400_ms));
 
   timer.Start();
 
   // Verify timer reports >= 400 ms has elapsed after multiple calls
-  frc::sim::StepTiming(500_ms);
+  wpi::sim::StepTiming(500_ms);
   EXPECT_TRUE(timer.HasElapsed(400_ms));
   EXPECT_TRUE(timer.HasElapsed(400_ms));
 }
@@ -95,26 +95,26 @@ TEST_F(TimerTest, AdvanceIfElapsed) {
   EXPECT_TRUE(timer.AdvanceIfElapsed(0_s));
 
   // Verify timer doesn't report elapsed time when stopped
-  frc::sim::StepTiming(500_ms);
+  wpi::sim::StepTiming(500_ms);
   EXPECT_FALSE(timer.AdvanceIfElapsed(400_ms));
 
   timer.Start();
 
   // Verify timer reports >= 400 ms has elapsed for only first call
-  frc::sim::StepTiming(500_ms);
+  wpi::sim::StepTiming(500_ms);
   EXPECT_TRUE(timer.AdvanceIfElapsed(400_ms));
   EXPECT_FALSE(timer.AdvanceIfElapsed(400_ms));
 
   // Verify timer reports >= 400 ms has elapsed for two calls
-  frc::sim::StepTiming(1_s);
+  wpi::sim::StepTiming(1_s);
   EXPECT_TRUE(timer.AdvanceIfElapsed(400_ms));
   EXPECT_TRUE(timer.AdvanceIfElapsed(400_ms));
   EXPECT_FALSE(timer.AdvanceIfElapsed(400_ms));
 }
 
 TEST_F(TimerTest, GetFPGATimestamp) {
-  auto start = frc::Timer::GetFPGATimestamp();
-  frc::sim::StepTiming(500_ms);
-  auto end = frc::Timer::GetFPGATimestamp();
+  auto start = wpi::Timer::GetFPGATimestamp();
+  wpi::sim::StepTiming(500_ms);
+  auto end = wpi::Timer::GetFPGATimestamp();
   EXPECT_EQ(start + 500_ms, end);
 }
diff --git a/wpilibc/src/test/native/cpp/TimesliceRobotTest.cpp b/wpilibc/src/test/native/cpp/TimesliceRobotTest.cpp
index ae52e53bed..d9d119245b 100644
--- a/wpilibc/src/test/native/cpp/TimesliceRobotTest.cpp
+++ b/wpilibc/src/test/native/cpp/TimesliceRobotTest.cpp
@@ -14,14 +14,14 @@
 #include "wpi/simulation/DriverStationSim.hpp"
 #include "wpi/simulation/SimHooks.hpp"
 
-using namespace frc;
+using namespace wpi;
 
 namespace {
 class TimesliceRobotTest : public ::testing::Test {
  protected:
-  void SetUp() override { frc::sim::PauseTiming(); }
+  void SetUp() override { wpi::sim::PauseTiming(); }
 
-  void TearDown() override { frc::sim::ResumeTiming(); }
+  void TearDown() override { wpi::sim::ResumeTiming(); }
 };
 
 class MockRobot : public TimesliceRobot {
@@ -52,33 +52,33 @@ TEST_F(TimesliceRobotTest, Schedule) {
 
   std::thread robotThread{[&] { robot.StartCompetition(); }};
 
-  frc::sim::DriverStationSim::SetEnabled(false);
-  frc::sim::DriverStationSim::NotifyNewData();
-  frc::sim::StepTiming(0_ms);  // Wait for Notifiers
+  wpi::sim::DriverStationSim::SetEnabled(false);
+  wpi::sim::DriverStationSim::NotifyNewData();
+  wpi::sim::StepTiming(0_ms);  // Wait for Notifiers
 
   // Functions scheduled with addPeriodic() are delayed by one period before
   // their first run (5 ms for this test's callbacks here and 20 ms for
   // robotPeriodic()).
-  frc::sim::StepTiming(5_ms);
+  wpi::sim::StepTiming(5_ms);
 
   EXPECT_EQ(0u, robot.m_robotPeriodicCount);
   EXPECT_EQ(0u, callbackCount1);
   EXPECT_EQ(0u, callbackCount2);
 
   // Step to 1.5 ms
-  frc::sim::StepTiming(1.5_ms);
+  wpi::sim::StepTiming(1.5_ms);
   EXPECT_EQ(0u, robot.m_robotPeriodicCount);
   EXPECT_EQ(0u, callbackCount1);
   EXPECT_EQ(0u, callbackCount2);
 
   // Step to 2.25 ms
-  frc::sim::StepTiming(0.75_ms);
+  wpi::sim::StepTiming(0.75_ms);
   EXPECT_EQ(0u, robot.m_robotPeriodicCount);
   EXPECT_EQ(1u, callbackCount1);
   EXPECT_EQ(0u, callbackCount2);
 
   // Step to 2.75 ms
-  frc::sim::StepTiming(0.5_ms);
+  wpi::sim::StepTiming(0.5_ms);
   EXPECT_EQ(0u, robot.m_robotPeriodicCount);
   EXPECT_EQ(1u, callbackCount1);
   EXPECT_EQ(1u, callbackCount2);
diff --git a/wpilibc/src/test/native/cpp/UnitNetworkTablesTest.cpp b/wpilibc/src/test/native/cpp/UnitNetworkTablesTest.cpp
index 1ef9b775e8..bcac069008 100644
--- a/wpilibc/src/test/native/cpp/UnitNetworkTablesTest.cpp
+++ b/wpilibc/src/test/native/cpp/UnitNetworkTablesTest.cpp
@@ -11,13 +11,13 @@
 
 class UnitNetworkTablesTest : public ::testing::Test {
  public:
-  UnitNetworkTablesTest() : inst{nt::NetworkTableInstance::Create()} {}
-  ~UnitNetworkTablesTest() override { nt::NetworkTableInstance::Destroy(inst); }
-  nt::NetworkTableInstance inst;
+  UnitNetworkTablesTest() : inst{wpi::nt::NetworkTableInstance::Create()} {}
+  ~UnitNetworkTablesTest() override { wpi::nt::NetworkTableInstance::Destroy(inst); }
+  wpi::nt::NetworkTableInstance inst;
 };
 
 TEST_F(UnitNetworkTablesTest, Publish) {
-  auto topic = nt::UnitTopic{inst.GetTopic("meterTest")};
+  auto topic = wpi::nt::UnitTopic{inst.GetTopic("meterTest")};
   auto pub = topic.Publish();
   pub.Set(2_m);
   ASSERT_EQ(topic.GetProperty("unit"), "meter");
@@ -25,7 +25,7 @@ TEST_F(UnitNetworkTablesTest, Publish) {
 }
 
 TEST_F(UnitNetworkTablesTest, SubscribeDouble) {
-  auto topic = nt::UnitTopic{inst.GetTopic("meterTest")};
+  auto topic = wpi::nt::UnitTopic{inst.GetTopic("meterTest")};
   auto pub = topic.Publish();
   auto sub = inst.GetDoubleTopic("meterTest").Subscribe(0);
   ASSERT_EQ(sub.Get(), 0);
@@ -35,7 +35,7 @@ TEST_F(UnitNetworkTablesTest, SubscribeDouble) {
 }
 
 TEST_F(UnitNetworkTablesTest, SubscribeUnit) {
-  auto topic = nt::UnitTopic{inst.GetTopic("meterTest")};
+  auto topic = wpi::nt::UnitTopic{inst.GetTopic("meterTest")};
   auto pub = topic.Publish();
   auto sub = topic.Subscribe(0_m);
   ASSERT_EQ(sub.Get(), 0_m);
diff --git a/wpilibc/src/test/native/cpp/WatchdogTest.cpp b/wpilibc/src/test/native/cpp/WatchdogTest.cpp
index 4adab69f0e..4db08d836c 100644
--- a/wpilibc/src/test/native/cpp/WatchdogTest.cpp
+++ b/wpilibc/src/test/native/cpp/WatchdogTest.cpp
@@ -10,14 +10,14 @@
 
 #include "wpi/simulation/SimHooks.hpp"
 
-using namespace frc;
+using namespace wpi;
 
 namespace {
 class WatchdogTest : public ::testing::Test {
  protected:
-  void SetUp() override { frc::sim::PauseTiming(); }
+  void SetUp() override { wpi::sim::PauseTiming(); }
 
-  void TearDown() override { frc::sim::ResumeTiming(); }
+  void TearDown() override { wpi::sim::ResumeTiming(); }
 };
 
 }  // namespace
@@ -29,7 +29,7 @@ TEST_F(WatchdogTest, EnableDisable) {
 
   // Run 1
   watchdog.Enable();
-  frc::sim::StepTiming(0.2_s);
+  wpi::sim::StepTiming(0.2_s);
   watchdog.Disable();
 
   EXPECT_EQ(0u, watchdogCounter) << "Watchdog triggered early";
@@ -37,7 +37,7 @@ TEST_F(WatchdogTest, EnableDisable) {
   // Run 2
   watchdogCounter = 0;
   watchdog.Enable();
-  frc::sim::StepTiming(0.4_s);
+  wpi::sim::StepTiming(0.4_s);
   watchdog.Disable();
 
   EXPECT_EQ(1u, watchdogCounter)
@@ -46,7 +46,7 @@ TEST_F(WatchdogTest, EnableDisable) {
   // Run 3
   watchdogCounter = 0;
   watchdog.Enable();
-  frc::sim::StepTiming(1_s);
+  wpi::sim::StepTiming(1_s);
   watchdog.Disable();
 
   EXPECT_EQ(1u, watchdogCounter)
@@ -59,9 +59,9 @@ TEST_F(WatchdogTest, Reset) {
   Watchdog watchdog(0.4_s, [&] { watchdogCounter++; });
 
   watchdog.Enable();
-  frc::sim::StepTiming(0.2_s);
+  wpi::sim::StepTiming(0.2_s);
   watchdog.Reset();
-  frc::sim::StepTiming(0.2_s);
+  wpi::sim::StepTiming(0.2_s);
   watchdog.Disable();
 
   EXPECT_EQ(0u, watchdogCounter) << "Watchdog triggered early";
@@ -73,13 +73,13 @@ TEST_F(WatchdogTest, SetTimeout) {
   Watchdog watchdog(1_s, [&] { watchdogCounter++; });
 
   watchdog.Enable();
-  frc::sim::StepTiming(0.2_s);
+  wpi::sim::StepTiming(0.2_s);
   watchdog.SetTimeout(0.2_s);
 
   EXPECT_EQ(0.2_s, watchdog.GetTimeout());
   EXPECT_EQ(0u, watchdogCounter) << "Watchdog triggered early";
 
-  frc::sim::StepTiming(0.3_s);
+  wpi::sim::StepTiming(0.3_s);
   watchdog.Disable();
 
   EXPECT_EQ(1u, watchdogCounter)
@@ -92,7 +92,7 @@ TEST_F(WatchdogTest, IsExpired) {
   watchdog.Enable();
 
   EXPECT_FALSE(watchdog.IsExpired());
-  frc::sim::StepTiming(0.3_s);
+  wpi::sim::StepTiming(0.3_s);
   EXPECT_TRUE(watchdog.IsExpired());
 
   watchdog.Disable();
@@ -110,9 +110,9 @@ TEST_F(WatchdogTest, Epochs) {
   // Run 1
   watchdog.Enable();
   watchdog.AddEpoch("Epoch 1");
-  frc::sim::StepTiming(0.1_s);
+  wpi::sim::StepTiming(0.1_s);
   watchdog.AddEpoch("Epoch 2");
-  frc::sim::StepTiming(0.1_s);
+  wpi::sim::StepTiming(0.1_s);
   watchdog.AddEpoch("Epoch 3");
   watchdog.Disable();
 
@@ -121,9 +121,9 @@ TEST_F(WatchdogTest, Epochs) {
   // Run 2
   watchdog.Enable();
   watchdog.AddEpoch("Epoch 1");
-  frc::sim::StepTiming(0.2_s);
+  wpi::sim::StepTiming(0.2_s);
   watchdog.Reset();
-  frc::sim::StepTiming(0.2_s);
+  wpi::sim::StepTiming(0.2_s);
   watchdog.AddEpoch("Epoch 2");
   watchdog.Disable();
 
@@ -138,13 +138,13 @@ TEST_F(WatchdogTest, MultiWatchdog) {
   Watchdog watchdog2(0.6_s, [&] { watchdogCounter2++; });
 
   watchdog2.Enable();
-  frc::sim::StepTiming(0.25_s);
+  wpi::sim::StepTiming(0.25_s);
   EXPECT_EQ(0u, watchdogCounter1) << "Watchdog triggered early";
   EXPECT_EQ(0u, watchdogCounter2) << "Watchdog triggered early";
 
   // Sleep enough such that only the watchdog enabled later times out first
   watchdog1.Enable();
-  frc::sim::StepTiming(0.25_s);
+  wpi::sim::StepTiming(0.25_s);
   watchdog1.Disable();
   watchdog2.Disable();
 
diff --git a/wpilibc/src/test/native/cpp/XboxControllerTest.cpp b/wpilibc/src/test/native/cpp/XboxControllerTest.cpp
index f68405de65..1308e5ba4d 100644
--- a/wpilibc/src/test/native/cpp/XboxControllerTest.cpp
+++ b/wpilibc/src/test/native/cpp/XboxControllerTest.cpp
@@ -9,7 +9,7 @@
 #include "JoystickTestMacros.hpp"
 #include "wpi/simulation/XboxControllerSim.hpp"
 
-using namespace frc;
+using namespace wpi;
 
 BUTTON_TEST(XboxController, LeftBumperButton)
 BUTTON_TEST(XboxController, RightBumperButton)
diff --git a/wpilibc/src/test/native/cpp/drive/DifferentialDriveTest.cpp b/wpilibc/src/test/native/cpp/drive/DifferentialDriveTest.cpp
index e12b3b82ab..b43fe505aa 100644
--- a/wpilibc/src/test/native/cpp/drive/DifferentialDriveTest.cpp
+++ b/wpilibc/src/test/native/cpp/drive/DifferentialDriveTest.cpp
@@ -9,240 +9,240 @@
 
 TEST(DifferentialDriveTest, ArcadeDriveIK) {
   // Forward
-  auto speeds = frc::DifferentialDrive::ArcadeDriveIK(1.0, 0.0, false);
+  auto speeds = wpi::DifferentialDrive::ArcadeDriveIK(1.0, 0.0, false);
   EXPECT_DOUBLE_EQ(1.0, speeds.left);
   EXPECT_DOUBLE_EQ(1.0, speeds.right);
 
   // Forward left turn
-  speeds = frc::DifferentialDrive::ArcadeDriveIK(0.5, 0.5, false);
+  speeds = wpi::DifferentialDrive::ArcadeDriveIK(0.5, 0.5, false);
   EXPECT_DOUBLE_EQ(0.0, speeds.left);
   EXPECT_DOUBLE_EQ(0.5, speeds.right);
 
   // Forward right turn
-  speeds = frc::DifferentialDrive::ArcadeDriveIK(0.5, -0.5, false);
+  speeds = wpi::DifferentialDrive::ArcadeDriveIK(0.5, -0.5, false);
   EXPECT_DOUBLE_EQ(0.5, speeds.left);
   EXPECT_DOUBLE_EQ(0.0, speeds.right);
 
   // Backward
-  speeds = frc::DifferentialDrive::ArcadeDriveIK(-1.0, 0.0, false);
+  speeds = wpi::DifferentialDrive::ArcadeDriveIK(-1.0, 0.0, false);
   EXPECT_DOUBLE_EQ(-1.0, speeds.left);
   EXPECT_DOUBLE_EQ(-1.0, speeds.right);
 
   // Backward left turn
-  speeds = frc::DifferentialDrive::ArcadeDriveIK(-0.5, 0.5, false);
+  speeds = wpi::DifferentialDrive::ArcadeDriveIK(-0.5, 0.5, false);
   EXPECT_DOUBLE_EQ(-0.5, speeds.left);
   EXPECT_DOUBLE_EQ(0.0, speeds.right);
 
   // Backward right turn
-  speeds = frc::DifferentialDrive::ArcadeDriveIK(-0.5, -0.5, false);
+  speeds = wpi::DifferentialDrive::ArcadeDriveIK(-0.5, -0.5, false);
   EXPECT_DOUBLE_EQ(0.0, speeds.left);
   EXPECT_DOUBLE_EQ(-0.5, speeds.right);
 
   // Left turn (xSpeed with negative sign)
-  speeds = frc::DifferentialDrive::ArcadeDriveIK(-0.0, 1.0, false);
+  speeds = wpi::DifferentialDrive::ArcadeDriveIK(-0.0, 1.0, false);
   EXPECT_DOUBLE_EQ(-1.0, speeds.left);
   EXPECT_DOUBLE_EQ(1.0, speeds.right);
 
   // Left turn (xSpeed with positive sign)
-  speeds = frc::DifferentialDrive::ArcadeDriveIK(0.0, 1.0, false);
+  speeds = wpi::DifferentialDrive::ArcadeDriveIK(0.0, 1.0, false);
   EXPECT_DOUBLE_EQ(-1.0, speeds.left);
   EXPECT_DOUBLE_EQ(1.0, speeds.right);
 
   // Right turn (xSpeed with negative sign)
-  speeds = frc::DifferentialDrive::ArcadeDriveIK(-0.0, -1.0, false);
+  speeds = wpi::DifferentialDrive::ArcadeDriveIK(-0.0, -1.0, false);
   EXPECT_DOUBLE_EQ(1.0, speeds.left);
   EXPECT_DOUBLE_EQ(-1.0, speeds.right);
 
   // Right turn (xSpeed with positive sign)
-  speeds = frc::DifferentialDrive::ArcadeDriveIK(0.0, -1.0, false);
+  speeds = wpi::DifferentialDrive::ArcadeDriveIK(0.0, -1.0, false);
   EXPECT_DOUBLE_EQ(1.0, speeds.left);
   EXPECT_DOUBLE_EQ(-1.0, speeds.right);
 }
 
 TEST(DifferentialDriveTest, ArcadeDriveIKSquared) {
   // Forward
-  auto speeds = frc::DifferentialDrive::ArcadeDriveIK(1.0, 0.0, true);
+  auto speeds = wpi::DifferentialDrive::ArcadeDriveIK(1.0, 0.0, true);
   EXPECT_DOUBLE_EQ(1.0, speeds.left);
   EXPECT_DOUBLE_EQ(1.0, speeds.right);
 
   // Forward left turn
-  speeds = frc::DifferentialDrive::ArcadeDriveIK(0.5, 0.5, true);
+  speeds = wpi::DifferentialDrive::ArcadeDriveIK(0.5, 0.5, true);
   EXPECT_DOUBLE_EQ(0.0, speeds.left);
   EXPECT_DOUBLE_EQ(0.25, speeds.right);
 
   // Forward right turn
-  speeds = frc::DifferentialDrive::ArcadeDriveIK(0.5, -0.5, true);
+  speeds = wpi::DifferentialDrive::ArcadeDriveIK(0.5, -0.5, true);
   EXPECT_DOUBLE_EQ(0.25, speeds.left);
   EXPECT_DOUBLE_EQ(0.0, speeds.right);
 
   // Backward
-  speeds = frc::DifferentialDrive::ArcadeDriveIK(-1.0, 0.0, true);
+  speeds = wpi::DifferentialDrive::ArcadeDriveIK(-1.0, 0.0, true);
   EXPECT_DOUBLE_EQ(-1.0, speeds.left);
   EXPECT_DOUBLE_EQ(-1.0, speeds.right);
 
   // Backward left turn
-  speeds = frc::DifferentialDrive::ArcadeDriveIK(-0.5, 0.5, true);
+  speeds = wpi::DifferentialDrive::ArcadeDriveIK(-0.5, 0.5, true);
   EXPECT_DOUBLE_EQ(-0.25, speeds.left);
   EXPECT_DOUBLE_EQ(0.0, speeds.right);
 
   // Backward right turn
-  speeds = frc::DifferentialDrive::ArcadeDriveIK(-0.5, -0.5, true);
+  speeds = wpi::DifferentialDrive::ArcadeDriveIK(-0.5, -0.5, true);
   EXPECT_DOUBLE_EQ(0.0, speeds.left);
   EXPECT_DOUBLE_EQ(-0.25, speeds.right);
 
   // Left turn (xSpeed with negative sign)
-  speeds = frc::DifferentialDrive::ArcadeDriveIK(-0.0, 1.0, false);
+  speeds = wpi::DifferentialDrive::ArcadeDriveIK(-0.0, 1.0, false);
   EXPECT_DOUBLE_EQ(-1.0, speeds.left);
   EXPECT_DOUBLE_EQ(1.0, speeds.right);
 
   // Left turn (xSpeed with positive sign)
-  speeds = frc::DifferentialDrive::ArcadeDriveIK(0.0, 1.0, false);
+  speeds = wpi::DifferentialDrive::ArcadeDriveIK(0.0, 1.0, false);
   EXPECT_DOUBLE_EQ(-1.0, speeds.left);
   EXPECT_DOUBLE_EQ(1.0, speeds.right);
 
   // Right turn (xSpeed with negative sign)
-  speeds = frc::DifferentialDrive::ArcadeDriveIK(-0.0, -1.0, false);
+  speeds = wpi::DifferentialDrive::ArcadeDriveIK(-0.0, -1.0, false);
   EXPECT_DOUBLE_EQ(1.0, speeds.left);
   EXPECT_DOUBLE_EQ(-1.0, speeds.right);
 
   // Right turn (xSpeed with positive sign)
-  speeds = frc::DifferentialDrive::ArcadeDriveIK(0.0, -1.0, false);
+  speeds = wpi::DifferentialDrive::ArcadeDriveIK(0.0, -1.0, false);
   EXPECT_DOUBLE_EQ(1.0, speeds.left);
   EXPECT_DOUBLE_EQ(-1.0, speeds.right);
 }
 
 TEST(DifferentialDriveTest, CurvatureDriveIK) {
   // Forward
-  auto speeds = frc::DifferentialDrive::CurvatureDriveIK(1.0, 0.0, false);
+  auto speeds = wpi::DifferentialDrive::CurvatureDriveIK(1.0, 0.0, false);
   EXPECT_DOUBLE_EQ(1.0, speeds.left);
   EXPECT_DOUBLE_EQ(1.0, speeds.right);
 
   // Forward left turn
-  speeds = frc::DifferentialDrive::CurvatureDriveIK(0.5, 0.5, false);
+  speeds = wpi::DifferentialDrive::CurvatureDriveIK(0.5, 0.5, false);
   EXPECT_DOUBLE_EQ(0.25, speeds.left);
   EXPECT_DOUBLE_EQ(0.75, speeds.right);
 
   // Forward right turn
-  speeds = frc::DifferentialDrive::CurvatureDriveIK(0.5, -0.5, false);
+  speeds = wpi::DifferentialDrive::CurvatureDriveIK(0.5, -0.5, false);
   EXPECT_DOUBLE_EQ(0.75, speeds.left);
   EXPECT_DOUBLE_EQ(0.25, speeds.right);
 
   // Backward
-  speeds = frc::DifferentialDrive::CurvatureDriveIK(-1.0, 0.0, false);
+  speeds = wpi::DifferentialDrive::CurvatureDriveIK(-1.0, 0.0, false);
   EXPECT_DOUBLE_EQ(-1.0, speeds.left);
   EXPECT_DOUBLE_EQ(-1.0, speeds.right);
 
   // Backward left turn
-  speeds = frc::DifferentialDrive::CurvatureDriveIK(-0.5, 0.5, false);
+  speeds = wpi::DifferentialDrive::CurvatureDriveIK(-0.5, 0.5, false);
   EXPECT_DOUBLE_EQ(-0.75, speeds.left);
   EXPECT_DOUBLE_EQ(-0.25, speeds.right);
 
   // Backward right turn
-  speeds = frc::DifferentialDrive::CurvatureDriveIK(-0.5, -0.5, false);
+  speeds = wpi::DifferentialDrive::CurvatureDriveIK(-0.5, -0.5, false);
   EXPECT_DOUBLE_EQ(-0.25, speeds.left);
   EXPECT_DOUBLE_EQ(-0.75, speeds.right);
 }
 
 TEST(DifferentialDriveTest, CurvatureDriveIKTurnInPlace) {
   // Forward
-  auto speeds = frc::DifferentialDrive::CurvatureDriveIK(1.0, 0.0, true);
+  auto speeds = wpi::DifferentialDrive::CurvatureDriveIK(1.0, 0.0, true);
   EXPECT_DOUBLE_EQ(1.0, speeds.left);
   EXPECT_DOUBLE_EQ(1.0, speeds.right);
 
   // Forward left turn
-  speeds = frc::DifferentialDrive::CurvatureDriveIK(0.5, 0.5, true);
+  speeds = wpi::DifferentialDrive::CurvatureDriveIK(0.5, 0.5, true);
   EXPECT_DOUBLE_EQ(0.0, speeds.left);
   EXPECT_DOUBLE_EQ(1.0, speeds.right);
 
   // Forward right turn
-  speeds = frc::DifferentialDrive::CurvatureDriveIK(0.5, -0.5, true);
+  speeds = wpi::DifferentialDrive::CurvatureDriveIK(0.5, -0.5, true);
   EXPECT_DOUBLE_EQ(1.0, speeds.left);
   EXPECT_DOUBLE_EQ(0.0, speeds.right);
 
   // Backward
-  speeds = frc::DifferentialDrive::CurvatureDriveIK(-1.0, 0.0, true);
+  speeds = wpi::DifferentialDrive::CurvatureDriveIK(-1.0, 0.0, true);
   EXPECT_DOUBLE_EQ(-1.0, speeds.left);
   EXPECT_DOUBLE_EQ(-1.0, speeds.right);
 
   // Backward left turn
-  speeds = frc::DifferentialDrive::CurvatureDriveIK(-0.5, 0.5, true);
+  speeds = wpi::DifferentialDrive::CurvatureDriveIK(-0.5, 0.5, true);
   EXPECT_DOUBLE_EQ(-1.0, speeds.left);
   EXPECT_DOUBLE_EQ(0.0, speeds.right);
 
   // Backward right turn
-  speeds = frc::DifferentialDrive::CurvatureDriveIK(-0.5, -0.5, true);
+  speeds = wpi::DifferentialDrive::CurvatureDriveIK(-0.5, -0.5, true);
   EXPECT_DOUBLE_EQ(0.0, speeds.left);
   EXPECT_DOUBLE_EQ(-1.0, speeds.right);
 }
 
 TEST(DifferentialDriveTest, TankDriveIK) {
   // Forward
-  auto speeds = frc::DifferentialDrive::TankDriveIK(1.0, 1.0, false);
+  auto speeds = wpi::DifferentialDrive::TankDriveIK(1.0, 1.0, false);
   EXPECT_DOUBLE_EQ(1.0, speeds.left);
   EXPECT_DOUBLE_EQ(1.0, speeds.right);
 
   // Forward left turn
-  speeds = frc::DifferentialDrive::TankDriveIK(0.5, 1.0, false);
+  speeds = wpi::DifferentialDrive::TankDriveIK(0.5, 1.0, false);
   EXPECT_DOUBLE_EQ(0.5, speeds.left);
   EXPECT_DOUBLE_EQ(1.0, speeds.right);
 
   // Forward right turn
-  speeds = frc::DifferentialDrive::TankDriveIK(1.0, 0.5, false);
+  speeds = wpi::DifferentialDrive::TankDriveIK(1.0, 0.5, false);
   EXPECT_DOUBLE_EQ(1.0, speeds.left);
   EXPECT_DOUBLE_EQ(0.5, speeds.right);
 
   // Backward
-  speeds = frc::DifferentialDrive::TankDriveIK(-1.0, -1.0, false);
+  speeds = wpi::DifferentialDrive::TankDriveIK(-1.0, -1.0, false);
   EXPECT_DOUBLE_EQ(-1.0, speeds.left);
   EXPECT_DOUBLE_EQ(-1.0, speeds.right);
 
   // Backward left turn
-  speeds = frc::DifferentialDrive::TankDriveIK(-0.5, -1.0, false);
+  speeds = wpi::DifferentialDrive::TankDriveIK(-0.5, -1.0, false);
   EXPECT_DOUBLE_EQ(-0.5, speeds.left);
   EXPECT_DOUBLE_EQ(-1.0, speeds.right);
 
   // Backward right turn
-  speeds = frc::DifferentialDrive::TankDriveIK(-0.5, 1.0, false);
+  speeds = wpi::DifferentialDrive::TankDriveIK(-0.5, 1.0, false);
   EXPECT_DOUBLE_EQ(-0.5, speeds.left);
   EXPECT_DOUBLE_EQ(1.0, speeds.right);
 }
 
 TEST(DifferentialDriveTest, TankDriveIKSquared) {
   // Forward
-  auto speeds = frc::DifferentialDrive::TankDriveIK(1.0, 1.0, true);
+  auto speeds = wpi::DifferentialDrive::TankDriveIK(1.0, 1.0, true);
   EXPECT_DOUBLE_EQ(1.0, speeds.left);
   EXPECT_DOUBLE_EQ(1.0, speeds.right);
 
   // Forward left turn
-  speeds = frc::DifferentialDrive::TankDriveIK(0.5, 1.0, true);
+  speeds = wpi::DifferentialDrive::TankDriveIK(0.5, 1.0, true);
   EXPECT_DOUBLE_EQ(0.25, speeds.left);
   EXPECT_DOUBLE_EQ(1.0, speeds.right);
 
   // Forward right turn
-  speeds = frc::DifferentialDrive::TankDriveIK(1.0, 0.5, true);
+  speeds = wpi::DifferentialDrive::TankDriveIK(1.0, 0.5, true);
   EXPECT_DOUBLE_EQ(1.0, speeds.left);
   EXPECT_DOUBLE_EQ(0.25, speeds.right);
 
   // Backward
-  speeds = frc::DifferentialDrive::TankDriveIK(-1.0, -1.0, true);
+  speeds = wpi::DifferentialDrive::TankDriveIK(-1.0, -1.0, true);
   EXPECT_DOUBLE_EQ(-1.0, speeds.left);
   EXPECT_DOUBLE_EQ(-1.0, speeds.right);
 
   // Backward left turn
-  speeds = frc::DifferentialDrive::TankDriveIK(-0.5, -1.0, true);
+  speeds = wpi::DifferentialDrive::TankDriveIK(-0.5, -1.0, true);
   EXPECT_DOUBLE_EQ(-0.25, speeds.left);
   EXPECT_DOUBLE_EQ(-1.0, speeds.right);
 
   // Backward right turn
-  speeds = frc::DifferentialDrive::TankDriveIK(-1.0, -0.5, true);
+  speeds = wpi::DifferentialDrive::TankDriveIK(-1.0, -0.5, true);
   EXPECT_DOUBLE_EQ(-1.0, speeds.left);
   EXPECT_DOUBLE_EQ(-0.25, speeds.right);
 }
 
 TEST(DifferentialDriveTest, ArcadeDrive) {
-  frc::MockPWMMotorController left;
-  frc::MockPWMMotorController right;
-  frc::DifferentialDrive drive{[&](double output) { left.Set(output); },
+  wpi::MockPWMMotorController left;
+  wpi::MockPWMMotorController right;
+  wpi::DifferentialDrive drive{[&](double output) { left.Set(output); },
                                [&](double output) { right.Set(output); }};
   drive.SetDeadband(0.0);
 
@@ -278,9 +278,9 @@ TEST(DifferentialDriveTest, ArcadeDrive) {
 }
 
 TEST(DifferentialDriveTest, ArcadeDriveSquared) {
-  frc::MockPWMMotorController left;
-  frc::MockPWMMotorController right;
-  frc::DifferentialDrive drive{[&](double output) { left.Set(output); },
+  wpi::MockPWMMotorController left;
+  wpi::MockPWMMotorController right;
+  wpi::DifferentialDrive drive{[&](double output) { left.Set(output); },
                                [&](double output) { right.Set(output); }};
   drive.SetDeadband(0.0);
 
@@ -316,9 +316,9 @@ TEST(DifferentialDriveTest, ArcadeDriveSquared) {
 }
 
 TEST(DifferentialDriveTest, CurvatureDrive) {
-  frc::MockPWMMotorController left;
-  frc::MockPWMMotorController right;
-  frc::DifferentialDrive drive{[&](double output) { left.Set(output); },
+  wpi::MockPWMMotorController left;
+  wpi::MockPWMMotorController right;
+  wpi::DifferentialDrive drive{[&](double output) { left.Set(output); },
                                [&](double output) { right.Set(output); }};
   drive.SetDeadband(0.0);
 
@@ -354,9 +354,9 @@ TEST(DifferentialDriveTest, CurvatureDrive) {
 }
 
 TEST(DifferentialDriveTest, CurvatureDriveTurnInPlace) {
-  frc::MockPWMMotorController left;
-  frc::MockPWMMotorController right;
-  frc::DifferentialDrive drive{[&](double output) { left.Set(output); },
+  wpi::MockPWMMotorController left;
+  wpi::MockPWMMotorController right;
+  wpi::DifferentialDrive drive{[&](double output) { left.Set(output); },
                                [&](double output) { right.Set(output); }};
   drive.SetDeadband(0.0);
 
@@ -392,9 +392,9 @@ TEST(DifferentialDriveTest, CurvatureDriveTurnInPlace) {
 }
 
 TEST(DifferentialDriveTest, TankDrive) {
-  frc::MockPWMMotorController left;
-  frc::MockPWMMotorController right;
-  frc::DifferentialDrive drive{[&](double output) { left.Set(output); },
+  wpi::MockPWMMotorController left;
+  wpi::MockPWMMotorController right;
+  wpi::DifferentialDrive drive{[&](double output) { left.Set(output); },
                                [&](double output) { right.Set(output); }};
   drive.SetDeadband(0.0);
 
@@ -430,9 +430,9 @@ TEST(DifferentialDriveTest, TankDrive) {
 }
 
 TEST(DifferentialDriveTest, TankDriveSquared) {
-  frc::MockPWMMotorController left;
-  frc::MockPWMMotorController right;
-  frc::DifferentialDrive drive{[&](double output) { left.Set(output); },
+  wpi::MockPWMMotorController left;
+  wpi::MockPWMMotorController right;
+  wpi::DifferentialDrive drive{[&](double output) { left.Set(output); },
                                [&](double output) { right.Set(output); }};
   drive.SetDeadband(0.0);
 
diff --git a/wpilibc/src/test/native/cpp/drive/MecanumDriveTest.cpp b/wpilibc/src/test/native/cpp/drive/MecanumDriveTest.cpp
index 0a386641a0..55baf33288 100644
--- a/wpilibc/src/test/native/cpp/drive/MecanumDriveTest.cpp
+++ b/wpilibc/src/test/native/cpp/drive/MecanumDriveTest.cpp
@@ -9,35 +9,35 @@
 
 TEST(MecanumDriveTest, CartesianIK) {
   // Forward
-  auto speeds = frc::MecanumDrive::DriveCartesianIK(1.0, 0.0, 0.0);
+  auto speeds = wpi::MecanumDrive::DriveCartesianIK(1.0, 0.0, 0.0);
   EXPECT_DOUBLE_EQ(1.0, speeds.frontLeft);
   EXPECT_DOUBLE_EQ(1.0, speeds.frontRight);
   EXPECT_DOUBLE_EQ(1.0, speeds.rearLeft);
   EXPECT_DOUBLE_EQ(1.0, speeds.rearRight);
 
   // Left
-  speeds = frc::MecanumDrive::DriveCartesianIK(0.0, -1.0, 0.0);
+  speeds = wpi::MecanumDrive::DriveCartesianIK(0.0, -1.0, 0.0);
   EXPECT_DOUBLE_EQ(-1.0, speeds.frontLeft);
   EXPECT_DOUBLE_EQ(1.0, speeds.frontRight);
   EXPECT_DOUBLE_EQ(1.0, speeds.rearLeft);
   EXPECT_DOUBLE_EQ(-1.0, speeds.rearRight);
 
   // Right
-  speeds = frc::MecanumDrive::DriveCartesianIK(0.0, 1.0, 0.0);
+  speeds = wpi::MecanumDrive::DriveCartesianIK(0.0, 1.0, 0.0);
   EXPECT_DOUBLE_EQ(1.0, speeds.frontLeft);
   EXPECT_DOUBLE_EQ(-1.0, speeds.frontRight);
   EXPECT_DOUBLE_EQ(-1.0, speeds.rearLeft);
   EXPECT_DOUBLE_EQ(1.0, speeds.rearRight);
 
   // Rotate CCW
-  speeds = frc::MecanumDrive::DriveCartesianIK(0.0, 0.0, -1.0);
+  speeds = wpi::MecanumDrive::DriveCartesianIK(0.0, 0.0, -1.0);
   EXPECT_DOUBLE_EQ(-1.0, speeds.frontLeft);
   EXPECT_DOUBLE_EQ(1.0, speeds.frontRight);
   EXPECT_DOUBLE_EQ(-1.0, speeds.rearLeft);
   EXPECT_DOUBLE_EQ(1.0, speeds.rearRight);
 
   // Rotate CW
-  speeds = frc::MecanumDrive::DriveCartesianIK(0.0, 0.0, 1.0);
+  speeds = wpi::MecanumDrive::DriveCartesianIK(0.0, 0.0, 1.0);
   EXPECT_DOUBLE_EQ(1.0, speeds.frontLeft);
   EXPECT_DOUBLE_EQ(-1.0, speeds.frontRight);
   EXPECT_DOUBLE_EQ(1.0, speeds.rearLeft);
@@ -46,35 +46,35 @@ TEST(MecanumDriveTest, CartesianIK) {
 
 TEST(MecanumDriveTest, CartesianIKGyro90CW) {
   // Forward in global frame; left in robot frame
-  auto speeds = frc::MecanumDrive::DriveCartesianIK(1.0, 0.0, 0.0, 90_deg);
+  auto speeds = wpi::MecanumDrive::DriveCartesianIK(1.0, 0.0, 0.0, 90_deg);
   EXPECT_DOUBLE_EQ(-1.0, speeds.frontLeft);
   EXPECT_DOUBLE_EQ(1.0, speeds.frontRight);
   EXPECT_DOUBLE_EQ(1.0, speeds.rearLeft);
   EXPECT_DOUBLE_EQ(-1.0, speeds.rearRight);
 
   // Left in global frame; backward in robot frame
-  speeds = frc::MecanumDrive::DriveCartesianIK(0.0, -1.0, 0.0, 90_deg);
+  speeds = wpi::MecanumDrive::DriveCartesianIK(0.0, -1.0, 0.0, 90_deg);
   EXPECT_DOUBLE_EQ(-1.0, speeds.frontLeft);
   EXPECT_DOUBLE_EQ(-1.0, speeds.frontRight);
   EXPECT_DOUBLE_EQ(-1.0, speeds.rearLeft);
   EXPECT_DOUBLE_EQ(-1.0, speeds.rearRight);
 
   // Right in global frame; forward in robot frame
-  speeds = frc::MecanumDrive::DriveCartesianIK(0.0, 1.0, 0.0, 90_deg);
+  speeds = wpi::MecanumDrive::DriveCartesianIK(0.0, 1.0, 0.0, 90_deg);
   EXPECT_DOUBLE_EQ(1.0, speeds.frontLeft);
   EXPECT_DOUBLE_EQ(1.0, speeds.frontRight);
   EXPECT_DOUBLE_EQ(1.0, speeds.rearLeft);
   EXPECT_DOUBLE_EQ(1.0, speeds.rearRight);
 
   // Rotate CCW
-  speeds = frc::MecanumDrive::DriveCartesianIK(0.0, 0.0, -1.0, 90_deg);
+  speeds = wpi::MecanumDrive::DriveCartesianIK(0.0, 0.0, -1.0, 90_deg);
   EXPECT_DOUBLE_EQ(-1.0, speeds.frontLeft);
   EXPECT_DOUBLE_EQ(1.0, speeds.frontRight);
   EXPECT_DOUBLE_EQ(-1.0, speeds.rearLeft);
   EXPECT_DOUBLE_EQ(1.0, speeds.rearRight);
 
   // Rotate CW
-  speeds = frc::MecanumDrive::DriveCartesianIK(0.0, 0.0, 1.0, 90_deg);
+  speeds = wpi::MecanumDrive::DriveCartesianIK(0.0, 0.0, 1.0, 90_deg);
   EXPECT_DOUBLE_EQ(1.0, speeds.frontLeft);
   EXPECT_DOUBLE_EQ(-1.0, speeds.frontRight);
   EXPECT_DOUBLE_EQ(1.0, speeds.rearLeft);
@@ -82,11 +82,11 @@ TEST(MecanumDriveTest, CartesianIKGyro90CW) {
 }
 
 TEST(MecanumDriveTest, Cartesian) {
-  frc::MockPWMMotorController fl;
-  frc::MockPWMMotorController rl;
-  frc::MockPWMMotorController fr;
-  frc::MockPWMMotorController rr;
-  frc::MecanumDrive drive{[&](double output) { fl.Set(output); },
+  wpi::MockPWMMotorController fl;
+  wpi::MockPWMMotorController rl;
+  wpi::MockPWMMotorController fr;
+  wpi::MockPWMMotorController rr;
+  wpi::MecanumDrive drive{[&](double output) { fl.Set(output); },
                           [&](double output) { rl.Set(output); },
                           [&](double output) { fr.Set(output); },
                           [&](double output) { rr.Set(output); }};
@@ -129,11 +129,11 @@ TEST(MecanumDriveTest, Cartesian) {
 }
 
 TEST(MecanumDriveTest, CartesianGyro90CW) {
-  frc::MockPWMMotorController fl;
-  frc::MockPWMMotorController rl;
-  frc::MockPWMMotorController fr;
-  frc::MockPWMMotorController rr;
-  frc::MecanumDrive drive{[&](double output) { fl.Set(output); },
+  wpi::MockPWMMotorController fl;
+  wpi::MockPWMMotorController rl;
+  wpi::MockPWMMotorController fr;
+  wpi::MockPWMMotorController rr;
+  wpi::MecanumDrive drive{[&](double output) { fl.Set(output); },
                           [&](double output) { rl.Set(output); },
                           [&](double output) { fr.Set(output); },
                           [&](double output) { rr.Set(output); }};
@@ -176,11 +176,11 @@ TEST(MecanumDriveTest, CartesianGyro90CW) {
 }
 
 TEST(MecanumDriveTest, Polar) {
-  frc::MockPWMMotorController fl;
-  frc::MockPWMMotorController rl;
-  frc::MockPWMMotorController fr;
-  frc::MockPWMMotorController rr;
-  frc::MecanumDrive drive{[&](double output) { fl.Set(output); },
+  wpi::MockPWMMotorController fl;
+  wpi::MockPWMMotorController rl;
+  wpi::MockPWMMotorController fr;
+  wpi::MockPWMMotorController rr;
+  wpi::MecanumDrive drive{[&](double output) { fl.Set(output); },
                           [&](double output) { rl.Set(output); },
                           [&](double output) { fr.Set(output); },
                           [&](double output) { rr.Set(output); }};
diff --git a/wpilibc/src/test/native/cpp/event/BooleanEventTest.cpp b/wpilibc/src/test/native/cpp/event/BooleanEventTest.cpp
index 08a16c6fbd..ae048a6d0a 100644
--- a/wpilibc/src/test/native/cpp/event/BooleanEventTest.cpp
+++ b/wpilibc/src/test/native/cpp/event/BooleanEventTest.cpp
@@ -9,7 +9,7 @@
 #include "wpi/event/BooleanEvent.hpp"
 #include "wpi/event/EventLoop.hpp"
 
-using namespace frc;
+using namespace wpi;
 
 TEST(BooleanEventTest, BinaryCompositions) {
   EventLoop loop;
diff --git a/wpilibc/src/test/native/cpp/event/EventLoopTest.cpp b/wpilibc/src/test/native/cpp/event/EventLoopTest.cpp
index c15b2ca35b..895e483986 100644
--- a/wpilibc/src/test/native/cpp/event/EventLoopTest.cpp
+++ b/wpilibc/src/test/native/cpp/event/EventLoopTest.cpp
@@ -7,18 +7,18 @@
 #include "wpi/event/EventLoop.hpp"
 #include "wpi/system/Errors.hpp"
 
-using namespace frc;
+using namespace wpi;
 
 TEST(EventLoopTest, ConcurrentModification) {
   EventLoop loop;
 
-  loop.Bind([&loop] { ASSERT_THROW(loop.Bind([] {}), frc::RuntimeError); });
+  loop.Bind([&loop] { ASSERT_THROW(loop.Bind([] {}), wpi::RuntimeError); });
 
   loop.Poll();
 
   loop.Clear();
 
-  loop.Bind([&loop] { ASSERT_THROW(loop.Clear(), frc::RuntimeError); });
+  loop.Bind([&loop] { ASSERT_THROW(loop.Clear(), wpi::RuntimeError); });
 
   loop.Poll();
 }
diff --git a/wpilibc/src/test/native/cpp/event/NetworkBooleanEventTest.cpp b/wpilibc/src/test/native/cpp/event/NetworkBooleanEventTest.cpp
index ab926f14ee..091282014e 100644
--- a/wpilibc/src/test/native/cpp/event/NetworkBooleanEventTest.cpp
+++ b/wpilibc/src/test/native/cpp/event/NetworkBooleanEventTest.cpp
@@ -9,20 +9,20 @@
 #include "wpi/nt/BooleanTopic.hpp"
 #include "wpi/nt/NetworkTableInstance.hpp"
 
-using namespace frc;
+using namespace wpi;
 
 class NetworkBooleanEventTest : public ::testing::Test {
  public:
   NetworkBooleanEventTest() {
-    m_inst = nt::NetworkTableInstance::Create();
+    m_inst = wpi::nt::NetworkTableInstance::Create();
     m_inst.StartLocal();
   }
 
   ~NetworkBooleanEventTest() override {
-    nt::NetworkTableInstance::Destroy(m_inst);
+    wpi::nt::NetworkTableInstance::Destroy(m_inst);
   }
 
-  nt::NetworkTableInstance m_inst;
+  wpi::nt::NetworkTableInstance m_inst;
 };
 
 TEST_F(NetworkBooleanEventTest, Set) {
diff --git a/wpilibc/src/test/native/cpp/main.cpp b/wpilibc/src/test/native/cpp/main.cpp
index 1af368e2d5..9bea26b945 100644
--- a/wpilibc/src/test/native/cpp/main.cpp
+++ b/wpilibc/src/test/native/cpp/main.cpp
@@ -7,7 +7,7 @@
 #include "wpi/hal/HALBase.h"
 
 #ifndef __FRC_SYSTEMCORE__
-namespace frc::impl {
+namespace wpi::impl {
 void ResetMotorSafety();
 }
 #endif
@@ -17,7 +17,7 @@ int main(int argc, char** argv) {
   ::testing::InitGoogleTest(&argc, argv);
   int ret = RUN_ALL_TESTS();
 #ifndef __FRC_SYSTEMCORE__
-  frc::impl::ResetMotorSafety();
+  wpi::impl::ResetMotorSafety();
 #endif
   return ret;
 }
diff --git a/wpilibc/src/test/native/cpp/motorcontrol/MockMotorController.cpp b/wpilibc/src/test/native/cpp/motorcontrol/MockMotorController.cpp
index 868c199494..dd4f2bc281 100644
--- a/wpilibc/src/test/native/cpp/motorcontrol/MockMotorController.cpp
+++ b/wpilibc/src/test/native/cpp/motorcontrol/MockMotorController.cpp
@@ -4,7 +4,7 @@
 
 #include "motorcontrol/MockMotorController.hpp"
 
-using namespace frc;
+using namespace wpi;
 
 void MockMotorController::Set(double speed) {
   m_speed = m_isInverted ? -speed : speed;
diff --git a/wpilibc/src/test/native/cpp/motorcontrol/MockPWMMotorController.cpp b/wpilibc/src/test/native/cpp/motorcontrol/MockPWMMotorController.cpp
index 8cb6aa3723..877f2ed65a 100644
--- a/wpilibc/src/test/native/cpp/motorcontrol/MockPWMMotorController.cpp
+++ b/wpilibc/src/test/native/cpp/motorcontrol/MockPWMMotorController.cpp
@@ -4,7 +4,7 @@
 
 #include "motorcontrol/MockPWMMotorController.hpp"
 
-using namespace frc;
+using namespace wpi;
 
 void MockPWMMotorController::Set(double speed) {
   m_speed = m_isInverted ? -speed : speed;
diff --git a/wpilibc/src/test/native/cpp/motorcontrol/MotorControllerGroupTest.cpp b/wpilibc/src/test/native/cpp/motorcontrol/MotorControllerGroupTest.cpp
index bab0feb43e..6eeeae570c 100644
--- a/wpilibc/src/test/native/cpp/motorcontrol/MotorControllerGroupTest.cpp
+++ b/wpilibc/src/test/native/cpp/motorcontrol/MotorControllerGroupTest.cpp
@@ -12,7 +12,7 @@
 #include "motorcontrol/MockMotorController.hpp"
 #include "wpi/util/deprecated.hpp"
 
-using namespace frc;
+using namespace wpi;
 
 enum MotorControllerGroupTestType { TEST_ONE, TEST_TWO, TEST_THREE };
 
diff --git a/wpilibc/src/test/native/cpp/simulation/AddressableLEDSimTest.cpp b/wpilibc/src/test/native/cpp/simulation/AddressableLEDSimTest.cpp
index 2411bf6b3b..e84a8e3601 100644
--- a/wpilibc/src/test/native/cpp/simulation/AddressableLEDSimTest.cpp
+++ b/wpilibc/src/test/native/cpp/simulation/AddressableLEDSimTest.cpp
@@ -12,7 +12,7 @@
 #include "wpi/hal/HAL.h"
 #include "wpi/hardware/led/AddressableLED.hpp"
 
-namespace frc::sim {
+namespace wpi::sim {
 
 TEST(AddressableLEDSimTest, InitializationCallback) {
   HAL_Initialize(500, 0);
@@ -120,4 +120,4 @@ TEST(AddressableLEDSimTest, SetData) {
   EXPECT_EQ(0xFF, simData[2].b);
 }
 
-}  // namespace frc::sim
+}  // namespace wpi::sim
diff --git a/wpilibc/src/test/native/cpp/simulation/AnalogEncoderSimTest.cpp b/wpilibc/src/test/native/cpp/simulation/AnalogEncoderSimTest.cpp
index 441814d0d4..7756dc787c 100644
--- a/wpilibc/src/test/native/cpp/simulation/AnalogEncoderSimTest.cpp
+++ b/wpilibc/src/test/native/cpp/simulation/AnalogEncoderSimTest.cpp
@@ -13,12 +13,12 @@
 #include "wpi/units/math.hpp"
 
 #define EXPECT_NEAR_UNITS(val1, val2, eps) \
-  EXPECT_LE(units::math::abs(val1 - val2), eps)
+  EXPECT_LE(wpi::units::math::abs(val1 - val2), eps)
 
 TEST(AnalogEncoderSimTest, Basic) {
-  frc::AnalogInput ai(0);
-  frc::AnalogEncoder encoder{ai, 360, 0};
-  frc::sim::AnalogEncoderSim encoderSim{encoder};
+  wpi::AnalogInput ai(0);
+  wpi::AnalogEncoder encoder{ai, 360, 0};
+  wpi::sim::AnalogEncoderSim encoderSim{encoder};
 
   encoderSim.Set(180);
   EXPECT_NEAR(encoder.Get(), 180, 1E-8);
diff --git a/wpilibc/src/test/native/cpp/simulation/AnalogInputSimTest.cpp b/wpilibc/src/test/native/cpp/simulation/AnalogInputSimTest.cpp
index b413e01603..3fc8005108 100644
--- a/wpilibc/src/test/native/cpp/simulation/AnalogInputSimTest.cpp
+++ b/wpilibc/src/test/native/cpp/simulation/AnalogInputSimTest.cpp
@@ -10,7 +10,7 @@
 #include "wpi/hal/HAL.h"
 #include "wpi/hardware/discrete/AnalogInput.hpp"
 
-namespace frc::sim {
+namespace wpi::sim {
 
 TEST(AnalogInputSimTest, SetInitialized) {
   HAL_Initialize(500, 0);
@@ -92,4 +92,4 @@ TEST(AnalogInputSimTest, SetAverageBits) {
   EXPECT_EQ(3504, callback.GetLastValue());
 }
 
-}  // namespace frc::sim
+}  // namespace wpi::sim
diff --git a/wpilibc/src/test/native/cpp/simulation/CTREPCMSimTest.cpp b/wpilibc/src/test/native/cpp/simulation/CTREPCMSimTest.cpp
index c84985714b..301ff1885c 100644
--- a/wpilibc/src/test/native/cpp/simulation/CTREPCMSimTest.cpp
+++ b/wpilibc/src/test/native/cpp/simulation/CTREPCMSimTest.cpp
@@ -11,7 +11,7 @@
 #include "wpi/hardware/pneumatic/DoubleSolenoid.hpp"
 #include "wpi/hardware/pneumatic/PneumaticsControlModule.hpp"
 
-namespace frc::sim {
+namespace wpi::sim {
 
 TEST(CTREPCMSimTest, InitializedCallback) {
   CTREPCMSim sim;
@@ -33,7 +33,7 @@ TEST(CTREPCMSimTest, SolenoidOutput) {
   CTREPCMSim sim(pcm);
   sim.ResetData();
 
-  DoubleSolenoid doubleSolenoid{0, frc::PneumaticsModuleType::CTREPCM, 3, 4};
+  DoubleSolenoid doubleSolenoid{0, wpi::PneumaticsModuleType::CTREPCM, 3, 4};
 
   BooleanCallback callback3;
   BooleanCallback callback4;
@@ -147,4 +147,4 @@ TEST(CTREPCMSimTest, SetCompressorCurrent) {
   EXPECT_TRUE(callback.WasTriggered());
   EXPECT_EQ(35.04, callback.GetLastValue());
 }
-}  // namespace frc::sim
+}  // namespace wpi::sim
diff --git a/wpilibc/src/test/native/cpp/simulation/DCMotorSimTest.cpp b/wpilibc/src/test/native/cpp/simulation/DCMotorSimTest.cpp
index a52758d5f8..ec67dfdbe0 100644
--- a/wpilibc/src/test/native/cpp/simulation/DCMotorSimTest.cpp
+++ b/wpilibc/src/test/native/cpp/simulation/DCMotorSimTest.cpp
@@ -15,16 +15,16 @@
 #include "wpi/system/RobotController.hpp"
 
 TEST(DCMotorSimTest, VoltageSteadyState) {
-  frc::DCMotor gearbox = frc::DCMotor::NEO(1);
-  auto plant = frc::LinearSystemId::DCMotorSystem(
-      frc::DCMotor::NEO(1), units::kilogram_square_meter_t{0.0005}, 1.0);
-  frc::sim::DCMotorSim sim{plant, gearbox};
+  wpi::math::DCMotor gearbox = wpi::math::DCMotor::NEO(1);
+  auto plant = wpi::math::LinearSystemId::DCMotorSystem(
+      wpi::math::DCMotor::NEO(1), wpi::units::kilogram_square_meter_t{0.0005}, 1.0);
+  wpi::sim::DCMotorSim sim{plant, gearbox};
 
-  frc::Encoder encoder{0, 1};
-  frc::sim::EncoderSim encoderSim{encoder};
-  frc::PWMVictorSPX motor{0};
+  wpi::Encoder encoder{0, 1};
+  wpi::sim::EncoderSim encoderSim{encoder};
+  wpi::PWMVictorSPX motor{0};
 
-  frc::sim::RoboRioSim::ResetData();
+  wpi::sim::RoboRioSim::ResetData();
   encoderSim.ResetData();
 
   // Spin-up
@@ -33,10 +33,10 @@ TEST(DCMotorSimTest, VoltageSteadyState) {
     motor.SetVoltage(12_V);
 
     // Then, SimulationPeriodic runs
-    frc::sim::RoboRioSim::SetVInVoltage(
-        frc::sim::BatterySim::Calculate({sim.GetCurrentDraw()}));
+    wpi::sim::RoboRioSim::SetVInVoltage(
+        wpi::sim::BatterySim::Calculate({sim.GetCurrentDraw()}));
     sim.SetInputVoltage(motor.Get() *
-                        frc::RobotController::GetBatteryVoltage());
+                        wpi::RobotController::GetBatteryVoltage());
     sim.Update(20_ms);
     encoderSim.SetRate(sim.GetAngularVelocity().value());
   }
@@ -49,10 +49,10 @@ TEST(DCMotorSimTest, VoltageSteadyState) {
     motor.SetVoltage(0_V);
 
     // Then, SimulationPeriodic runs
-    frc::sim::RoboRioSim::SetVInVoltage(
-        frc::sim::BatterySim::Calculate({sim.GetCurrentDraw()}));
+    wpi::sim::RoboRioSim::SetVInVoltage(
+        wpi::sim::BatterySim::Calculate({sim.GetCurrentDraw()}));
     sim.SetInputVoltage(motor.Get() *
-                        frc::RobotController::GetBatteryVoltage());
+                        wpi::RobotController::GetBatteryVoltage());
     sim.Update(20_ms);
     encoderSim.SetRate(sim.GetAngularVelocity().value());
   }
@@ -61,18 +61,18 @@ TEST(DCMotorSimTest, VoltageSteadyState) {
 }
 
 TEST(DCMotorSimTest, PositionFeedbackControl) {
-  frc::DCMotor gearbox = frc::DCMotor::NEO(1);
-  auto plant = frc::LinearSystemId::DCMotorSystem(
-      frc::DCMotor::NEO(1), units::kilogram_square_meter_t{0.0005}, 1.0);
-  frc::sim::DCMotorSim sim{plant, gearbox};
+  wpi::math::DCMotor gearbox = wpi::math::DCMotor::NEO(1);
+  auto plant = wpi::math::LinearSystemId::DCMotorSystem(
+      wpi::math::DCMotor::NEO(1), wpi::units::kilogram_square_meter_t{0.0005}, 1.0);
+  wpi::sim::DCMotorSim sim{plant, gearbox};
 
-  frc::PIDController controller{0.04, 0.0, 0.001};
+  wpi::math::PIDController controller{0.04, 0.0, 0.001};
 
-  frc::Encoder encoder{0, 1};
-  frc::sim::EncoderSim encoderSim{encoder};
-  frc::PWMVictorSPX motor{0};
+  wpi::Encoder encoder{0, 1};
+  wpi::sim::EncoderSim encoderSim{encoder};
+  wpi::PWMVictorSPX motor{0};
 
-  frc::sim::RoboRioSim::ResetData();
+  wpi::sim::RoboRioSim::ResetData();
   encoderSim.ResetData();
 
   for (int i = 0; i < 140; i++) {
@@ -80,10 +80,10 @@ TEST(DCMotorSimTest, PositionFeedbackControl) {
     motor.Set(controller.Calculate(encoder.GetDistance(), 750));
 
     // Then, SimulationPeriodic runs
-    frc::sim::RoboRioSim::SetVInVoltage(
-        frc::sim::BatterySim::Calculate({sim.GetCurrentDraw()}));
+    wpi::sim::RoboRioSim::SetVInVoltage(
+        wpi::sim::BatterySim::Calculate({sim.GetCurrentDraw()}));
     sim.SetInputVoltage(motor.Get() *
-                        frc::RobotController::GetBatteryVoltage());
+                        wpi::RobotController::GetBatteryVoltage());
     sim.Update(20_ms);
     encoderSim.SetDistance(sim.GetAngularPosition().value());
     encoderSim.SetRate(sim.GetAngularVelocity().value());
diff --git a/wpilibc/src/test/native/cpp/simulation/DIOSimTest.cpp b/wpilibc/src/test/native/cpp/simulation/DIOSimTest.cpp
index 906db14322..2df96dad0a 100644
--- a/wpilibc/src/test/native/cpp/simulation/DIOSimTest.cpp
+++ b/wpilibc/src/test/native/cpp/simulation/DIOSimTest.cpp
@@ -11,7 +11,7 @@
 #include "wpi/hardware/discrete/DigitalInput.hpp"
 #include "wpi/hardware/discrete/DigitalOutput.hpp"
 
-namespace frc::sim {
+namespace wpi::sim {
 
 TEST(DIOSimTest, Initialization) {
   HAL_Initialize(500, 0);
@@ -77,4 +77,4 @@ TEST(DIOSimTest, Output) {
   EXPECT_TRUE(valueCallback.WasTriggered());
   EXPECT_FALSE(valueCallback.GetLastValue());
 }
-}  // namespace frc::sim
+}  // namespace wpi::sim
diff --git a/wpilibc/src/test/native/cpp/simulation/DifferentialDrivetrainSimTest.cpp b/wpilibc/src/test/native/cpp/simulation/DifferentialDrivetrainSimTest.cpp
index 504f062607..2567378170 100644
--- a/wpilibc/src/test/native/cpp/simulation/DifferentialDrivetrainSimTest.cpp
+++ b/wpilibc/src/test/native/cpp/simulation/DifferentialDrivetrainSimTest.cpp
@@ -18,29 +18,29 @@
 #include "wpi/units/moment_of_inertia.hpp"
 
 TEST(DifferentialDrivetrainSimTest, Convergence) {
-  auto motor = frc::DCMotor::NEO(2);
-  auto plant = frc::LinearSystemId::DrivetrainVelocitySystem(
+  auto motor = wpi::math::DCMotor::NEO(2);
+  auto plant = wpi::math::LinearSystemId::DrivetrainVelocitySystem(
       motor, 50_kg, 2_in, 12_in, 0.5_kg_sq_m, 1.0);
 
-  frc::DifferentialDriveKinematics kinematics{24_in};
-  frc::sim::DifferentialDrivetrainSim sim{
+  wpi::math::DifferentialDriveKinematics kinematics{24_in};
+  wpi::sim::DifferentialDrivetrainSim sim{
       plant, 24_in, motor,
       1.0,   2_in,  {0.001, 0.001, 0.0001, 0.1, 0.1, 0.005, 0.005}};
 
-  frc::LinearPlantInversionFeedforward feedforward{plant, 20_ms};
-  frc::LTVUnicycleController feedback{20_ms};
+  wpi::math::LinearPlantInversionFeedforward feedforward{plant, 20_ms};
+  wpi::math::LTVUnicycleController feedback{20_ms};
 
-  feedforward.Reset(frc::Vectord<2>{0.0, 0.0});
+  feedforward.Reset(wpi::math::Vectord<2>{0.0, 0.0});
 
   // Ground truth.
-  frc::Vectord<7> groundTruthX = frc::Vectord<7>::Zero();
+  wpi::math::Vectord<7> groundTruthX = wpi::math::Vectord<7>::Zero();
 
-  frc::TrajectoryConfig config{1_mps, 1_mps_sq};
+  wpi::math::TrajectoryConfig config{1_mps, 1_mps_sq};
   config.AddConstraint(
-      frc::DifferentialDriveKinematicsConstraint(kinematics, 1_mps));
+      wpi::math::DifferentialDriveKinematicsConstraint(kinematics, 1_mps));
 
-  auto trajectory = frc::TrajectoryGenerator::GenerateTrajectory(
-      frc::Pose2d{}, {}, frc::Pose2d{2_m, 2_m, 0_rad}, config);
+  auto trajectory = wpi::math::TrajectoryGenerator::GenerateTrajectory(
+      wpi::math::Pose2d{}, {}, wpi::math::Pose2d{2_m, 2_m, 0_rad}, config);
 
   for (auto t = 0_s; t < trajectory.TotalTime(); t += 20_ms) {
     auto state = trajectory.Sample(t);
@@ -48,34 +48,34 @@ TEST(DifferentialDrivetrainSimTest, Convergence) {
 
     auto [l, r] = kinematics.ToWheelSpeeds(feedbackOut);
     auto voltages =
-        feedforward.Calculate(frc::Vectord<2>{l.value(), r.value()});
+        feedforward.Calculate(wpi::math::Vectord<2>{l.value(), r.value()});
 
     // Sim periodic code.
-    sim.SetInputs(units::volt_t{voltages(0, 0)}, units::volt_t{voltages(1, 0)});
+    sim.SetInputs(wpi::units::volt_t{voltages(0, 0)}, wpi::units::volt_t{voltages(1, 0)});
     sim.Update(20_ms);
 
     // Update ground truth.
-    groundTruthX = frc::RKDP(
-        [&sim](const auto& x, const auto& u) -> frc::Vectord<7> {
+    groundTruthX = wpi::math::RKDP(
+        [&sim](const auto& x, const auto& u) -> wpi::math::Vectord<7> {
           return sim.Dynamics(x, u);
         },
         groundTruthX, voltages, 20_ms);
   }
 
   // 2 inch tolerance is OK since our ground truth is an approximation of the
-  // ODE solution using RKDP anyway
+  // ODE solution using wpi::math::RKDP anyway
   EXPECT_NEAR(groundTruthX(0, 0), sim.GetPose().X().value(), 0.05);
   EXPECT_NEAR(groundTruthX(1, 0), sim.GetPose().Y().value(), 0.05);
   EXPECT_NEAR(groundTruthX(2, 0), sim.GetHeading().Radians().value(), 0.01);
 }
 
 TEST(DifferentialDrivetrainSimTest, Current) {
-  auto motor = frc::DCMotor::NEO(2);
-  auto plant = frc::LinearSystemId::DrivetrainVelocitySystem(
+  auto motor = wpi::math::DCMotor::NEO(2);
+  auto plant = wpi::math::LinearSystemId::DrivetrainVelocitySystem(
       motor, 50_kg, 2_in, 12_in, 0.5_kg_sq_m, 1.0);
 
-  frc::DifferentialDriveKinematics kinematics{24_in};
-  frc::sim::DifferentialDrivetrainSim sim{plant, 24_in, motor, 1.0, 2_in};
+  wpi::math::DifferentialDriveKinematics kinematics{24_in};
+  wpi::sim::DifferentialDrivetrainSim sim{plant, 24_in, motor, 1.0, 2_in};
 
   sim.SetInputs(-12_V, 12_V);
   for (int i = 0; i < 10; ++i) {
@@ -97,12 +97,12 @@ TEST(DifferentialDrivetrainSimTest, Current) {
 }
 
 TEST(DifferentialDrivetrainSimTest, ModelStability) {
-  auto motor = frc::DCMotor::NEO(2);
-  auto plant = frc::LinearSystemId::DrivetrainVelocitySystem(
+  auto motor = wpi::math::DCMotor::NEO(2);
+  auto plant = wpi::math::LinearSystemId::DrivetrainVelocitySystem(
       motor, 50_kg, 2_in, 12_in, 2_kg_sq_m, 5.0);
 
-  frc::DifferentialDriveKinematics kinematics{24_in};
-  frc::sim::DifferentialDrivetrainSim sim{plant, 24_in, motor, 1.0, 2_in};
+  wpi::math::DifferentialDriveKinematics kinematics{24_in};
+  wpi::sim::DifferentialDrivetrainSim sim{plant, 24_in, motor, 1.0, 2_in};
 
   sim.SetInputs(2_V, 4_V);
 
@@ -111,5 +111,5 @@ TEST(DifferentialDrivetrainSimTest, ModelStability) {
     sim.Update(20_ms);
   }
 
-  EXPECT_LT(units::math::abs(sim.GetPose().Translation().Norm()), 100_m);
+  EXPECT_LT(wpi::units::math::abs(sim.GetPose().Translation().Norm()), 100_m);
 }
diff --git a/wpilibc/src/test/native/cpp/simulation/DigitalPWMSimTest.cpp b/wpilibc/src/test/native/cpp/simulation/DigitalPWMSimTest.cpp
index ae598cb3ef..2e32d1ba0f 100644
--- a/wpilibc/src/test/native/cpp/simulation/DigitalPWMSimTest.cpp
+++ b/wpilibc/src/test/native/cpp/simulation/DigitalPWMSimTest.cpp
@@ -10,7 +10,7 @@
 #include "wpi/hal/HAL.h"
 #include "wpi/hardware/discrete/DigitalOutput.hpp"
 
-namespace frc::sim {
+namespace wpi::sim {
 
 TEST(DigitalPWMSimTest, Initialize) {
   HAL_Initialize(500, 0);
@@ -54,4 +54,4 @@ TEST(DigitalPWMSimTest, SetPin) {
   EXPECT_EQ(191, callback.GetLastValue());
 }
 
-}  // namespace frc::sim
+}  // namespace wpi::sim
diff --git a/wpilibc/src/test/native/cpp/simulation/DriverStationSimTest.cpp b/wpilibc/src/test/native/cpp/simulation/DriverStationSimTest.cpp
index 31b03d9ffc..d2f4926602 100644
--- a/wpilibc/src/test/native/cpp/simulation/DriverStationSimTest.cpp
+++ b/wpilibc/src/test/native/cpp/simulation/DriverStationSimTest.cpp
@@ -14,8 +14,8 @@
 #include "wpi/simulation/DriverStationSim.hpp"
 #include "wpi/simulation/SimHooks.hpp"
 
-using namespace frc;
-using namespace frc::sim;
+using namespace wpi;
+using namespace wpi::sim;
 
 TEST(DriverStationTest, Enabled) {
   HAL_Initialize(500, 0);
@@ -138,7 +138,7 @@ TEST(DriverStationTest, AllianceStationId) {
   // Unknown
   allianceStation = HAL_AllianceStationID_kUnknown;
   DriverStationSim::SetAllianceStationId(allianceStation);
-  frc::sim::DriverStationSim::NotifyNewData();
+  wpi::sim::DriverStationSim::NotifyNewData();
   EXPECT_EQ(allianceStation, DriverStationSim::GetAllianceStationId());
   EXPECT_FALSE(DriverStation::GetAlliance().has_value());
   EXPECT_FALSE(DriverStation::GetLocation().has_value());
@@ -148,7 +148,7 @@ TEST(DriverStationTest, AllianceStationId) {
   // B1
   allianceStation = HAL_AllianceStationID_kBlue1;
   DriverStationSim::SetAllianceStationId(allianceStation);
-  frc::sim::DriverStationSim::NotifyNewData();
+  wpi::sim::DriverStationSim::NotifyNewData();
   EXPECT_EQ(allianceStation, DriverStationSim::GetAllianceStationId());
   EXPECT_EQ(DriverStation::kBlue, DriverStation::GetAlliance());
   EXPECT_EQ(1, DriverStation::GetLocation());
@@ -158,7 +158,7 @@ TEST(DriverStationTest, AllianceStationId) {
   // B2
   allianceStation = HAL_AllianceStationID_kBlue2;
   DriverStationSim::SetAllianceStationId(allianceStation);
-  frc::sim::DriverStationSim::NotifyNewData();
+  wpi::sim::DriverStationSim::NotifyNewData();
   EXPECT_EQ(allianceStation, DriverStationSim::GetAllianceStationId());
   EXPECT_EQ(DriverStation::kBlue, DriverStation::GetAlliance());
   EXPECT_EQ(2, DriverStation::GetLocation());
@@ -168,7 +168,7 @@ TEST(DriverStationTest, AllianceStationId) {
   // B3
   allianceStation = HAL_AllianceStationID_kBlue3;
   DriverStationSim::SetAllianceStationId(allianceStation);
-  frc::sim::DriverStationSim::NotifyNewData();
+  wpi::sim::DriverStationSim::NotifyNewData();
   EXPECT_EQ(allianceStation, DriverStationSim::GetAllianceStationId());
   EXPECT_EQ(DriverStation::kBlue, DriverStation::GetAlliance());
   EXPECT_EQ(3, DriverStation::GetLocation());
@@ -178,7 +178,7 @@ TEST(DriverStationTest, AllianceStationId) {
   // R1
   allianceStation = HAL_AllianceStationID_kRed1;
   DriverStationSim::SetAllianceStationId(allianceStation);
-  frc::sim::DriverStationSim::NotifyNewData();
+  wpi::sim::DriverStationSim::NotifyNewData();
   EXPECT_EQ(allianceStation, DriverStationSim::GetAllianceStationId());
   EXPECT_EQ(DriverStation::kRed, DriverStation::GetAlliance());
   EXPECT_EQ(1, DriverStation::GetLocation());
@@ -188,7 +188,7 @@ TEST(DriverStationTest, AllianceStationId) {
   // R2
   allianceStation = HAL_AllianceStationID_kRed2;
   DriverStationSim::SetAllianceStationId(allianceStation);
-  frc::sim::DriverStationSim::NotifyNewData();
+  wpi::sim::DriverStationSim::NotifyNewData();
   EXPECT_EQ(allianceStation, DriverStationSim::GetAllianceStationId());
   EXPECT_EQ(DriverStation::kRed, DriverStation::GetAlliance());
   EXPECT_EQ(2, DriverStation::GetLocation());
@@ -198,7 +198,7 @@ TEST(DriverStationTest, AllianceStationId) {
   // R3
   allianceStation = HAL_AllianceStationID_kRed3;
   DriverStationSim::SetAllianceStationId(allianceStation);
-  frc::sim::DriverStationSim::NotifyNewData();
+  wpi::sim::DriverStationSim::NotifyNewData();
   EXPECT_EQ(allianceStation, DriverStationSim::GetAllianceStationId());
   EXPECT_EQ(DriverStation::kRed, DriverStation::GetAlliance());
   EXPECT_EQ(3, DriverStation::GetLocation());
@@ -233,7 +233,7 @@ TEST(DriverStationTest, MatchTime) {
                                                         false);
   constexpr double kTestTime = 19.174;
   DriverStationSim::SetMatchTime(kTestTime);
-  frc::sim::DriverStationSim::NotifyNewData();
+  wpi::sim::DriverStationSim::NotifyNewData();
   EXPECT_EQ(kTestTime, DriverStationSim::GetMatchTime());
   EXPECT_EQ(kTestTime, DriverStation::GetMatchTime().value());
   EXPECT_TRUE(callback.WasTriggered());
diff --git a/wpilibc/src/test/native/cpp/simulation/DutyCycleEncoderSimTest.cpp b/wpilibc/src/test/native/cpp/simulation/DutyCycleEncoderSimTest.cpp
index 571934ce60..f08497c22f 100644
--- a/wpilibc/src/test/native/cpp/simulation/DutyCycleEncoderSimTest.cpp
+++ b/wpilibc/src/test/native/cpp/simulation/DutyCycleEncoderSimTest.cpp
@@ -10,7 +10,7 @@
 #include "wpi/hal/HAL.h"
 #include "wpi/hardware/rotation/DutyCycleEncoder.hpp"
 
-namespace frc::sim {
+namespace wpi::sim {
 
 TEST(DutyCycleEncoderSimTest, Set) {
   HAL_Initialize(500, 0);
@@ -34,4 +34,4 @@ TEST(DutyCycleEncoderSimTest, SetIsConnected) {
   EXPECT_FALSE(enc.IsConnected());
 }
 
-}  // namespace frc::sim
+}  // namespace wpi::sim
diff --git a/wpilibc/src/test/native/cpp/simulation/DutyCycleSimTest.cpp b/wpilibc/src/test/native/cpp/simulation/DutyCycleSimTest.cpp
index 0373ab3372..eadfc8fd3a 100644
--- a/wpilibc/src/test/native/cpp/simulation/DutyCycleSimTest.cpp
+++ b/wpilibc/src/test/native/cpp/simulation/DutyCycleSimTest.cpp
@@ -11,7 +11,7 @@
 #include "wpi/hardware/discrete/DigitalInput.hpp"
 #include "wpi/hardware/rotation/DutyCycle.hpp"
 
-namespace frc::sim {
+namespace wpi::sim {
 
 TEST(DutyCycleSimTest, Initialization) {
   HAL_Initialize(500, 0);
@@ -64,4 +64,4 @@ TEST(DutyCycleSimTest, SetOutput) {
   EXPECT_EQ(229.174, callback.GetLastValue());
 }
 
-}  // namespace frc::sim
+}  // namespace wpi::sim
diff --git a/wpilibc/src/test/native/cpp/simulation/ElevatorSimTest.cpp b/wpilibc/src/test/native/cpp/simulation/ElevatorSimTest.cpp
index cdd426a1da..d1d7b382f5 100644
--- a/wpilibc/src/test/native/cpp/simulation/ElevatorSimTest.cpp
+++ b/wpilibc/src/test/native/cpp/simulation/ElevatorSimTest.cpp
@@ -17,23 +17,23 @@
 #include "wpi/units/time.hpp"
 
 #define EXPECT_NEAR_UNITS(val1, val2, eps) \
-  EXPECT_LE(units::math::abs(val1 - val2), eps)
+  EXPECT_LE(wpi::units::math::abs(val1 - val2), eps)
 
 TEST(ElevatorSimTest, StateSpaceSim) {
-  frc::sim::ElevatorSim sim(frc::DCMotor::Vex775Pro(4), 14.67, 8_kg, 0.75_in,
+  wpi::sim::ElevatorSim sim(wpi::math::DCMotor::Vex775Pro(4), 14.67, 8_kg, 0.75_in,
                             0_m, 3_m, true, 0_m, {0.01});
-  frc::PIDController controller(10, 0.0, 0.0);
+  wpi::math::PIDController controller(10, 0.0, 0.0);
 
-  frc::PWMVictorSPX motor(0);
-  frc::Encoder encoder(0, 1);
-  frc::sim::EncoderSim encoderSim(encoder);
+  wpi::PWMVictorSPX motor(0);
+  wpi::Encoder encoder(0, 1);
+  wpi::sim::EncoderSim encoderSim(encoder);
 
   for (size_t i = 0; i < 100; ++i) {
     controller.SetSetpoint(2.0);
     auto nextVoltage = controller.Calculate(encoderSim.GetDistance());
-    motor.Set(nextVoltage / frc::RobotController::GetInputVoltage());
+    motor.Set(nextVoltage / wpi::RobotController::GetInputVoltage());
 
-    frc::Vectord<1> u{motor.Get() * frc::RobotController::GetInputVoltage()};
+    wpi::math::Vectord<1> u{motor.Get() * wpi::RobotController::GetInputVoltage()};
     sim.SetInput(u);
     sim.Update(20_ms);
 
@@ -46,7 +46,7 @@ TEST(ElevatorSimTest, StateSpaceSim) {
 
 TEST(ElevatorSimTest, InitialState) {
   constexpr auto startingHeight = 0.5_m;
-  frc::sim::ElevatorSim sim(frc::DCMotor::KrakenX60(2), 20, 8_kg, 0.1_m, 0_m,
+  wpi::sim::ElevatorSim sim(wpi::math::DCMotor::KrakenX60(2), 20, 8_kg, 0.1_m, 0_m,
                             1_m, true, startingHeight, {0.01, 0.0});
 
   EXPECT_DOUBLE_EQ(startingHeight.value(), sim.GetPosition().value());
@@ -54,10 +54,10 @@ TEST(ElevatorSimTest, InitialState) {
 }
 
 TEST(ElevatorSimTest, MinMax) {
-  frc::sim::ElevatorSim sim(frc::DCMotor::Vex775Pro(4), 14.67, 8_kg, 0.75_in,
+  wpi::sim::ElevatorSim sim(wpi::math::DCMotor::Vex775Pro(4), 14.67, 8_kg, 0.75_in,
                             0_m, 1_m, true, 0_m, {0.01});
   for (size_t i = 0; i < 100; ++i) {
-    sim.SetInput(frc::Vectord<1>{0.0});
+    sim.SetInput(wpi::math::Vectord<1>{0.0});
     sim.Update(20_ms);
 
     auto height = sim.GetPosition();
@@ -65,7 +65,7 @@ TEST(ElevatorSimTest, MinMax) {
   }
 
   for (size_t i = 0; i < 100; ++i) {
-    sim.SetInput(frc::Vectord<1>{12.0});
+    sim.SetInput(wpi::math::Vectord<1>{12.0});
     sim.Update(20_ms);
 
     auto height = sim.GetPosition();
@@ -74,21 +74,21 @@ TEST(ElevatorSimTest, MinMax) {
 }
 
 TEST(ElevatorSimTest, Stability) {
-  frc::sim::ElevatorSim sim{
-      frc::DCMotor::Vex775Pro(4), 100, 4_kg, 0.5_in, 0_m, 10_m, false, 0_m};
+  wpi::sim::ElevatorSim sim{
+      wpi::math::DCMotor::Vex775Pro(4), 100, 4_kg, 0.5_in, 0_m, 10_m, false, 0_m};
 
-  sim.SetState(frc::Vectord<2>{0.0, 0.0});
-  sim.SetInput(frc::Vectord<1>{12.0});
+  sim.SetState(wpi::math::Vectord<2>{0.0, 0.0});
+  sim.SetInput(wpi::math::Vectord<1>{12.0});
   for (int i = 0; i < 50; ++i) {
     sim.Update(20_ms);
   }
 
-  frc::LinearSystem<2, 1, 1> system =
-      frc::LinearSystemId::ElevatorSystem(frc::DCMotor::Vex775Pro(4), 4_kg,
+  wpi::math::LinearSystem<2, 1, 1> system =
+      wpi::math::LinearSystemId::ElevatorSystem(wpi::math::DCMotor::Vex775Pro(4), 4_kg,
                                           0.5_in, 100)
           .Slice(0);
   EXPECT_NEAR_UNITS(
-      units::meter_t{system.CalculateX(frc::Vectord<2>{0.0, 0.0},
-                                       frc::Vectord<1>{12.0}, 20_ms * 50)(0)},
+      wpi::units::meter_t{system.CalculateX(wpi::math::Vectord<2>{0.0, 0.0},
+                                       wpi::math::Vectord<1>{12.0}, 20_ms * 50)(0)},
       sim.GetPosition(), 1_cm);
 }
diff --git a/wpilibc/src/test/native/cpp/simulation/EncoderSimTest.cpp b/wpilibc/src/test/native/cpp/simulation/EncoderSimTest.cpp
index 17b5415137..97a578a229 100644
--- a/wpilibc/src/test/native/cpp/simulation/EncoderSimTest.cpp
+++ b/wpilibc/src/test/native/cpp/simulation/EncoderSimTest.cpp
@@ -11,7 +11,7 @@
 #include "wpi/hardware/rotation/Encoder.hpp"
 #include "wpi/util/deprecated.hpp"
 
-namespace frc::sim {
+namespace wpi::sim {
 
 namespace {
 constexpr double kDefaultDistancePerPulse = .0005;
@@ -232,4 +232,4 @@ TEST(EncoderSimTest, Reset) {
   EXPECT_EQ(0, encoder.GetDistance());
 }
 
-}  // namespace frc::sim
+}  // namespace wpi::sim
diff --git a/wpilibc/src/test/native/cpp/simulation/PDPSimTest.cpp b/wpilibc/src/test/native/cpp/simulation/PDPSimTest.cpp
index b6b724d298..3c329fcaf4 100644
--- a/wpilibc/src/test/native/cpp/simulation/PDPSimTest.cpp
+++ b/wpilibc/src/test/native/cpp/simulation/PDPSimTest.cpp
@@ -12,7 +12,7 @@
 #include "wpi/hal/HAL.h"
 #include "wpi/hardware/power/PowerDistribution.hpp"
 
-namespace frc::sim {
+namespace wpi::sim {
 
 TEST(PowerDistributionSimTest, Initialize) {
   HAL_Initialize(500, 0);
@@ -22,7 +22,7 @@ TEST(PowerDistributionSimTest, Initialize) {
   BooleanCallback callback;
 
   auto cb = sim.RegisterInitializedCallback(callback.GetCallback(), false);
-  PowerDistribution pdp(0, 2, frc::PowerDistribution::ModuleType::kCTRE);
+  PowerDistribution pdp(0, 2, wpi::PowerDistribution::ModuleType::kCTRE);
   EXPECT_TRUE(sim.GetInitialized());
   EXPECT_TRUE(callback.WasTriggered());
   EXPECT_TRUE(callback.GetLastValue());
@@ -35,7 +35,7 @@ TEST(PowerDistributionSimTest, Initialize) {
 
 TEST(PowerDistributionSimTest, SetTemperature) {
   HAL_Initialize(500, 0);
-  PowerDistribution pdp{0, 2, frc::PowerDistribution::ModuleType::kCTRE};
+  PowerDistribution pdp{0, 2, wpi::PowerDistribution::ModuleType::kCTRE};
   PowerDistributionSim sim(pdp);
 
   DoubleCallback callback;
@@ -50,7 +50,7 @@ TEST(PowerDistributionSimTest, SetTemperature) {
 
 TEST(PowerDistributionSimTest, SetVoltage) {
   HAL_Initialize(500, 0);
-  PowerDistribution pdp{0, 2, frc::PowerDistribution::ModuleType::kCTRE};
+  PowerDistribution pdp{0, 2, wpi::PowerDistribution::ModuleType::kCTRE};
   PowerDistributionSim sim(pdp);
 
   DoubleCallback callback;
@@ -65,7 +65,7 @@ TEST(PowerDistributionSimTest, SetVoltage) {
 
 TEST(PowerDistributionSimTest, SetCurrent) {
   HAL_Initialize(500, 0);
-  PowerDistribution pdp{0, 2, frc::PowerDistribution::ModuleType::kCTRE};
+  PowerDistribution pdp{0, 2, wpi::PowerDistribution::ModuleType::kCTRE};
   PowerDistributionSim sim(pdp);
 
   for (int channel = 0; channel < HAL_GetNumCTREPDPChannels(); ++channel) {
@@ -84,7 +84,7 @@ TEST(PowerDistributionSimTest, SetCurrent) {
 
 TEST(PowerDistributionSimTest, GetAllCurrents) {
   HAL_Initialize(500, 0);
-  PowerDistribution pdp{0, 2, frc::PowerDistribution::ModuleType::kRev};
+  PowerDistribution pdp{0, 2, wpi::PowerDistribution::ModuleType::kRev};
   PowerDistributionSim sim(pdp);
 
   // setup
@@ -103,4 +103,4 @@ TEST(PowerDistributionSimTest, GetAllCurrents) {
   }
 }
 
-}  // namespace frc::sim
+}  // namespace wpi::sim
diff --git a/wpilibc/src/test/native/cpp/simulation/PWMMotorControlllerSimTest.cpp b/wpilibc/src/test/native/cpp/simulation/PWMMotorControlllerSimTest.cpp
index a84a1216e3..310b54e212 100644
--- a/wpilibc/src/test/native/cpp/simulation/PWMMotorControlllerSimTest.cpp
+++ b/wpilibc/src/test/native/cpp/simulation/PWMMotorControlllerSimTest.cpp
@@ -9,10 +9,10 @@
 #include "wpi/hal/HAL.h"
 #include "wpi/hardware/motor/Spark.hpp"
 
-namespace frc::sim {
+namespace wpi::sim {
 TEST(PWMMotorControllerSimTest, TestMotor) {
-  frc::Spark spark{0};
-  frc::sim::PWMMotorControllerSim sim{spark};
+  wpi::Spark spark{0};
+  wpi::sim::PWMMotorControllerSim sim{spark};
 
   spark.Set(0);
   EXPECT_EQ(0, sim.GetSpeed());
@@ -23,4 +23,4 @@ TEST(PWMMotorControllerSimTest, TestMotor) {
   spark.Set(-0.785);
   EXPECT_EQ(-0.785, sim.GetSpeed());
 }
-}  // namespace frc::sim
+}  // namespace wpi::sim
diff --git a/wpilibc/src/test/native/cpp/simulation/PWMSimTest.cpp b/wpilibc/src/test/native/cpp/simulation/PWMSimTest.cpp
index 1d3638cecc..e9986541f0 100644
--- a/wpilibc/src/test/native/cpp/simulation/PWMSimTest.cpp
+++ b/wpilibc/src/test/native/cpp/simulation/PWMSimTest.cpp
@@ -10,7 +10,7 @@
 #include "wpi/hal/HAL.h"
 #include "wpi/hardware/discrete/PWM.hpp"
 
-namespace frc::sim {
+namespace wpi::sim {
 
 TEST(PWMSimTest, Initialize) {
   HAL_Initialize(500, 0);
@@ -61,4 +61,4 @@ TEST(PWMSimTest, SetOutputPeriod) {
   EXPECT_EQ(3504, callback.GetLastValue());
 }
 
-}  // namespace frc::sim
+}  // namespace wpi::sim
diff --git a/wpilibc/src/test/native/cpp/simulation/REVPHSimTest.cpp b/wpilibc/src/test/native/cpp/simulation/REVPHSimTest.cpp
index 55f43681af..0016d17c8e 100644
--- a/wpilibc/src/test/native/cpp/simulation/REVPHSimTest.cpp
+++ b/wpilibc/src/test/native/cpp/simulation/REVPHSimTest.cpp
@@ -11,7 +11,7 @@
 #include "wpi/hardware/pneumatic/DoubleSolenoid.hpp"
 #include "wpi/hardware/pneumatic/PneumaticHub.hpp"
 
-namespace frc::sim {
+namespace wpi::sim {
 
 TEST(REVPHSimTest, InitializedCallback) {
   REVPHSim sim;
@@ -33,7 +33,7 @@ TEST(REVPHSimTest, SolenoidOutput) {
   REVPHSim sim(ph);
   sim.ResetData();
 
-  DoubleSolenoid doubleSolenoid{0, 1, frc::PneumaticsModuleType::REVPH, 3, 4};
+  DoubleSolenoid doubleSolenoid{0, 1, wpi::PneumaticsModuleType::REVPH, 3, 4};
 
   BooleanCallback callback3;
   BooleanCallback callback4;
@@ -191,4 +191,4 @@ TEST(REVPHSimTest, SetCompressorCurrent) {
   EXPECT_TRUE(callback.WasTriggered());
   EXPECT_EQ(35.04, callback.GetLastValue());
 }
-}  // namespace frc::sim
+}  // namespace wpi::sim
diff --git a/wpilibc/src/test/native/cpp/simulation/RoboRioSimTest.cpp b/wpilibc/src/test/native/cpp/simulation/RoboRioSimTest.cpp
index 8e22650782..3dd4ba7c7d 100644
--- a/wpilibc/src/test/native/cpp/simulation/RoboRioSimTest.cpp
+++ b/wpilibc/src/test/native/cpp/simulation/RoboRioSimTest.cpp
@@ -13,7 +13,7 @@
 #include "wpi/hal/HALBase.h"
 #include "wpi/system/RobotController.hpp"
 
-namespace frc::sim {
+namespace wpi::sim {
 
 TEST(RoboRioSimTest, SetVin) {
   RoboRioSim::ResetData();
@@ -23,7 +23,7 @@ TEST(RoboRioSimTest, SetVin) {
       voltageCallback.GetCallback(), false);
   constexpr double kTestVoltage = 1.91;
 
-  RoboRioSim::SetVInVoltage(units::volt_t{kTestVoltage});
+  RoboRioSim::SetVInVoltage(wpi::units::volt_t{kTestVoltage});
   EXPECT_TRUE(voltageCallback.WasTriggered());
   EXPECT_EQ(kTestVoltage, voltageCallback.GetLastValue());
   EXPECT_EQ(kTestVoltage, RoboRioSim::GetVInVoltage().value());
@@ -38,7 +38,7 @@ TEST(RoboRioSimTest, SetBrownout) {
       voltageCallback.GetCallback(), false);
   constexpr double kTestVoltage = 1.91;
 
-  RoboRioSim::SetBrownoutVoltage(units::volt_t{kTestVoltage});
+  RoboRioSim::SetBrownoutVoltage(wpi::units::volt_t{kTestVoltage});
   EXPECT_TRUE(voltageCallback.WasTriggered());
   EXPECT_EQ(kTestVoltage, voltageCallback.GetLastValue());
   EXPECT_EQ(kTestVoltage, RoboRioSim::GetBrownoutVoltage().value());
@@ -64,13 +64,13 @@ TEST(RoboRioSimTest, Set3V3) {
   constexpr double kTestCurrent = 174;
   constexpr int kTestFaults = 229;
 
-  RoboRioSim::SetUserVoltage3V3(units::volt_t{kTestVoltage});
+  RoboRioSim::SetUserVoltage3V3(wpi::units::volt_t{kTestVoltage});
   EXPECT_TRUE(voltageCallback.WasTriggered());
   EXPECT_EQ(kTestVoltage, voltageCallback.GetLastValue());
   EXPECT_EQ(kTestVoltage, RoboRioSim::GetUserVoltage3V3().value());
   EXPECT_EQ(kTestVoltage, RobotController::GetVoltage3V3());
 
-  RoboRioSim::SetUserCurrent3V3(units::ampere_t{kTestCurrent});
+  RoboRioSim::SetUserCurrent3V3(wpi::units::ampere_t{kTestCurrent});
   EXPECT_TRUE(currentCallback.WasTriggered());
   EXPECT_EQ(kTestCurrent, currentCallback.GetLastValue());
   EXPECT_EQ(kTestCurrent, RoboRioSim::GetUserCurrent3V3().value());
@@ -97,7 +97,7 @@ TEST(RoboRioSimTest, SetCPUTemp) {
       RoboRioSim::RegisterCPUTempCallback(callback.GetCallback(), false);
   constexpr double kCPUTemp = 100.0;
 
-  RoboRioSim::SetCPUTemp(units::celsius_t{kCPUTemp});
+  RoboRioSim::SetCPUTemp(wpi::units::celsius_t{kCPUTemp});
   EXPECT_TRUE(callback.WasTriggered());
   EXPECT_EQ(kCPUTemp, callback.GetLastValue());
   EXPECT_EQ(kCPUTemp, RoboRioSim::GetCPUTemp().value());
@@ -156,4 +156,4 @@ TEST(RoboRioSimTest, SetComments) {
   EXPECT_EQ(kCommentsTruncated, RobotController::GetComments());
 }
 
-}  // namespace frc::sim
+}  // namespace wpi::sim
diff --git a/wpilibc/src/test/native/cpp/simulation/SimDeviceSimTest.cpp b/wpilibc/src/test/native/cpp/simulation/SimDeviceSimTest.cpp
index 9f14e65f6a..832d46c35b 100644
--- a/wpilibc/src/test/native/cpp/simulation/SimDeviceSimTest.cpp
+++ b/wpilibc/src/test/native/cpp/simulation/SimDeviceSimTest.cpp
@@ -9,14 +9,14 @@
 #include "wpi/hal/SimDevice.h"
 #include "wpi/simulation/SimDeviceSim.hpp"
 
-using namespace frc::sim;
+using namespace wpi::sim;
 
 TEST(SimDeviceSimTest, Basic) {
-  hal::SimDevice dev{"test"};
-  hal::SimBoolean devBool = dev.CreateBoolean("bool", false, false);
+  wpi::hal::SimDevice dev{"test"};
+  wpi::hal::SimBoolean devBool = dev.CreateBoolean("bool", false, false);
 
   SimDeviceSim sim{"test"};
-  hal::SimBoolean simBool = sim.GetBoolean("bool");
+  wpi::hal::SimBoolean simBool = sim.GetBoolean("bool");
   EXPECT_FALSE(simBool.Get());
   simBool.Set(true);
   EXPECT_TRUE(devBool.Get());
@@ -25,7 +25,7 @@ TEST(SimDeviceSimTest, Basic) {
 }
 
 TEST(SimDeviceSimTest, EnumerateDevices) {
-  hal::SimDevice dev{"test"};
+  wpi::hal::SimDevice dev{"test"};
 
   bool foundit = false;
   SimDeviceSim::EnumerateDevices(
diff --git a/wpilibc/src/test/native/cpp/simulation/SimInitializationTest.cpp b/wpilibc/src/test/native/cpp/simulation/SimInitializationTest.cpp
index ff58114ce3..2e3c2a6a20 100644
--- a/wpilibc/src/test/native/cpp/simulation/SimInitializationTest.cpp
+++ b/wpilibc/src/test/native/cpp/simulation/SimInitializationTest.cpp
@@ -19,7 +19,7 @@
 #include "wpi/simulation/PowerDistributionSim.hpp"
 #include "wpi/simulation/RoboRioSim.hpp"
 
-using namespace frc::sim;
+using namespace wpi::sim;
 
 TEST(SimInitializationTest, AllInitialize) {
   HAL_Initialize(500, 0);
diff --git a/wpilibc/src/test/native/cpp/simulation/SingleJointedArmSimTest.cpp b/wpilibc/src/test/native/cpp/simulation/SingleJointedArmSimTest.cpp
index dcc1b24325..29749a8290 100644
--- a/wpilibc/src/test/native/cpp/simulation/SingleJointedArmSimTest.cpp
+++ b/wpilibc/src/test/native/cpp/simulation/SingleJointedArmSimTest.cpp
@@ -9,12 +9,12 @@
 #include "wpi/simulation/SingleJointedArmSim.hpp"
 
 TEST(SingleJointedArmTest, Disabled) {
-  frc::sim::SingleJointedArmSim sim(frc::DCMotor::Vex775Pro(2), 300, 3_kg_sq_m,
+  wpi::sim::SingleJointedArmSim sim(wpi::math::DCMotor::Vex775Pro(2), 300, 3_kg_sq_m,
                                     30_in, -180_deg, 0_deg, true, 90_deg);
-  sim.SetState(frc::Vectord<2>{0.0, 0.0});
+  sim.SetState(wpi::math::Vectord<2>{0.0, 0.0});
 
   for (size_t i = 0; i < 12 / 0.02; ++i) {
-    sim.SetInput(frc::Vectord<1>{0.0});
+    sim.SetInput(wpi::math::Vectord<1>{0.0});
     sim.Update(20_ms);
   }
 
@@ -24,7 +24,7 @@ TEST(SingleJointedArmTest, Disabled) {
 
 TEST(SingleJointedArmTest, InitialState) {
   constexpr auto startingAngle = 45_deg;
-  frc::sim::SingleJointedArmSim sim(frc::DCMotor::KrakenX60(2), 125, 3_kg_sq_m,
+  wpi::sim::SingleJointedArmSim sim(wpi::math::DCMotor::KrakenX60(2), 125, 3_kg_sq_m,
                                     30_in, 0_deg, 90_deg, true, startingAngle);
 
   EXPECT_EQ(startingAngle, sim.GetAngle());
diff --git a/wpilibc/src/test/native/cpp/simulation/StateSpaceSimTest.cpp b/wpilibc/src/test/native/cpp/simulation/StateSpaceSimTest.cpp
index 1bb974c16a..2bc7ffa1d1 100644
--- a/wpilibc/src/test/native/cpp/simulation/StateSpaceSimTest.cpp
+++ b/wpilibc/src/test/native/cpp/simulation/StateSpaceSimTest.cpp
@@ -22,31 +22,31 @@
 #include "wpi/units/angular_velocity.hpp"
 
 TEST(StateSpaceSimTest, FlywheelSim) {
-  const frc::LinearSystem<1, 1, 1> plant =
-      frc::LinearSystemId::IdentifyVelocitySystem(
+  const wpi::math::LinearSystem<1, 1, 1> plant =
+      wpi::math::LinearSystemId::IdentifyVelocitySystem(
           0.02_V / 1_rad_per_s, 0.01_V / 1_rad_per_s_sq);
-  frc::sim::FlywheelSim sim{plant, frc::DCMotor::NEO(2)};
-  frc::PIDController controller{0.2, 0.0, 0.0};
-  frc::SimpleMotorFeedforward feedforward{
+  wpi::sim::FlywheelSim sim{plant, wpi::math::DCMotor::NEO(2)};
+  wpi::math::PIDController controller{0.2, 0.0, 0.0};
+  wpi::math::SimpleMotorFeedforward feedforward{
       0_V, 0.02_V / 1_rad_per_s, 0.01_V / 1_rad_per_s_sq};
-  frc::Encoder encoder{0, 1};
-  frc::sim::EncoderSim encoderSim{encoder};
-  frc::PWMVictorSPX motor{0};
+  wpi::Encoder encoder{0, 1};
+  wpi::sim::EncoderSim encoderSim{encoder};
+  wpi::PWMVictorSPX motor{0};
 
-  frc::sim::RoboRioSim::ResetData();
+  wpi::sim::RoboRioSim::ResetData();
   encoderSim.ResetData();
 
   for (int i = 0; i < 100; i++) {
     // RobotPeriodic runs first
     auto voltageOut = controller.Calculate(encoder.GetRate(), 200.0);
-    motor.SetVoltage(units::volt_t{voltageOut} +
+    motor.SetVoltage(wpi::units::volt_t{voltageOut} +
                      feedforward.Calculate(200_rad_per_s));
 
     // Then, SimulationPeriodic runs
-    frc::sim::RoboRioSim::SetVInVoltage(
-        frc::sim::BatterySim::Calculate({sim.GetCurrentDraw()}));
+    wpi::sim::RoboRioSim::SetVInVoltage(
+        wpi::sim::BatterySim::Calculate({sim.GetCurrentDraw()}));
     sim.SetInput(
-        frc::Vectord<1>{motor.Get() * frc::RobotController::GetInputVoltage()});
+        wpi::math::Vectord<1>{motor.Get() * wpi::RobotController::GetInputVoltage()});
     sim.Update(20_ms);
     encoderSim.SetRate(sim.GetAngularVelocity().value());
   }
diff --git a/wpilibc/src/test/native/cpp/smartdashboard/Mechanism2dTest.cpp b/wpilibc/src/test/native/cpp/smartdashboard/Mechanism2dTest.cpp
index 510fd50156..7d764cd55d 100644
--- a/wpilibc/src/test/native/cpp/smartdashboard/Mechanism2dTest.cpp
+++ b/wpilibc/src/test/native/cpp/smartdashboard/Mechanism2dTest.cpp
@@ -14,61 +14,61 @@
 class Mechanism2dTest;
 
 TEST(Mechanism2dTest, Canvas) {
-  frc::Mechanism2d mechanism{5, 10};
-  auto dimsEntry = nt::NetworkTableInstance::GetDefault().GetEntry(
+  wpi::Mechanism2d mechanism{5, 10};
+  auto dimsEntry = wpi::nt::NetworkTableInstance::GetDefault().GetEntry(
       "/SmartDashboard/mechanism/dims");
-  auto colorEntry = nt::NetworkTableInstance::GetDefault().GetEntry(
+  auto colorEntry = wpi::nt::NetworkTableInstance::GetDefault().GetEntry(
       "/SmartDashboard/mechanism/backgroundColor");
-  frc::SmartDashboard::PutData("mechanism", &mechanism);
-  frc::SmartDashboard::UpdateValues();
+  wpi::SmartDashboard::PutData("mechanism", &mechanism);
+  wpi::SmartDashboard::UpdateValues();
   EXPECT_EQ(5.0, dimsEntry.GetDoubleArray({})[0]);
   EXPECT_EQ(10.0, dimsEntry.GetDoubleArray({})[1]);
   EXPECT_EQ("#000020", colorEntry.GetString(""));
   mechanism.SetBackgroundColor({255, 255, 255});
-  frc::SmartDashboard::UpdateValues();
+  wpi::SmartDashboard::UpdateValues();
   EXPECT_EQ("#FFFFFF", colorEntry.GetString(""));
 }
 
 TEST(Mechanism2dTest, Root) {
-  frc::Mechanism2d mechanism{5, 10};
-  auto xEntry = nt::NetworkTableInstance::GetDefault().GetEntry(
+  wpi::Mechanism2d mechanism{5, 10};
+  auto xEntry = wpi::nt::NetworkTableInstance::GetDefault().GetEntry(
       "/SmartDashboard/mechanism/root/x");
-  auto yEntry = nt::NetworkTableInstance::GetDefault().GetEntry(
+  auto yEntry = wpi::nt::NetworkTableInstance::GetDefault().GetEntry(
       "/SmartDashboard/mechanism/root/y");
-  frc::MechanismRoot2d* root = mechanism.GetRoot("root", 1, 2);
-  frc::SmartDashboard::PutData("mechanism", &mechanism);
-  frc::SmartDashboard::UpdateValues();
+  wpi::MechanismRoot2d* root = mechanism.GetRoot("root", 1, 2);
+  wpi::SmartDashboard::PutData("mechanism", &mechanism);
+  wpi::SmartDashboard::UpdateValues();
   EXPECT_EQ(1.0, xEntry.GetDouble(0.0));
   EXPECT_EQ(2.0, yEntry.GetDouble(0.0));
   root->SetPosition(2, 4);
-  frc::SmartDashboard::UpdateValues();
+  wpi::SmartDashboard::UpdateValues();
   EXPECT_EQ(2.0, xEntry.GetDouble(0.0));
   EXPECT_EQ(4.0, yEntry.GetDouble(0.0));
 }
 
 TEST(Mechanism2dTest, Ligament) {
-  frc::Mechanism2d mechanism{5, 10};
-  auto angleEntry = nt::NetworkTableInstance::GetDefault().GetEntry(
+  wpi::Mechanism2d mechanism{5, 10};
+  auto angleEntry = wpi::nt::NetworkTableInstance::GetDefault().GetEntry(
       "/SmartDashboard/mechanism/root/ligament/angle");
-  auto colorEntry = nt::NetworkTableInstance::GetDefault().GetEntry(
+  auto colorEntry = wpi::nt::NetworkTableInstance::GetDefault().GetEntry(
       "/SmartDashboard/mechanism/root/ligament/color");
-  auto lengthEntry = nt::NetworkTableInstance::GetDefault().GetEntry(
+  auto lengthEntry = wpi::nt::NetworkTableInstance::GetDefault().GetEntry(
       "/SmartDashboard/mechanism/root/ligament/length");
-  auto weightEntry = nt::NetworkTableInstance::GetDefault().GetEntry(
+  auto weightEntry = wpi::nt::NetworkTableInstance::GetDefault().GetEntry(
       "/SmartDashboard/mechanism/root/ligament/weight");
-  frc::MechanismRoot2d* root = mechanism.GetRoot("root", 1, 2);
-  frc::MechanismLigament2d* ligament = root->Append(
-      "ligament", 3, units::degree_t{90}, 1, frc::Color8Bit{255, 255, 255});
-  frc::SmartDashboard::PutData("mechanism", &mechanism);
+  wpi::MechanismRoot2d* root = mechanism.GetRoot("root", 1, 2);
+  wpi::MechanismLigament2d* ligament = root->Append(
+      "ligament", 3, wpi::units::degree_t{90}, 1, wpi::Color8Bit{255, 255, 255});
+  wpi::SmartDashboard::PutData("mechanism", &mechanism);
   EXPECT_EQ(ligament->GetAngle(), angleEntry.GetDouble(0.0));
   EXPECT_EQ(ligament->GetColor().HexString(), colorEntry.GetString(""));
   EXPECT_EQ(ligament->GetLength(), lengthEntry.GetDouble(0.0));
   EXPECT_EQ(ligament->GetLineWeight(), weightEntry.GetDouble(0.0));
-  ligament->SetAngle(units::degree_t{45});
+  ligament->SetAngle(wpi::units::degree_t{45});
   ligament->SetColor({0, 0, 0});
   ligament->SetLength(2);
   ligament->SetLineWeight(4);
-  frc::SmartDashboard::UpdateValues();
+  wpi::SmartDashboard::UpdateValues();
   EXPECT_EQ(ligament->GetAngle(), angleEntry.GetDouble(0.0));
   EXPECT_EQ(ligament->GetColor().HexString(), colorEntry.GetString(""));
   EXPECT_EQ(ligament->GetLength(), lengthEntry.GetDouble(0.0));
@@ -77,7 +77,7 @@ TEST(Mechanism2dTest, Ligament) {
   colorEntry.SetString("#FF00FF");
   lengthEntry.SetDouble(4.0);
   weightEntry.SetDouble(6.0);
-  frc::SmartDashboard::UpdateValues();
+  wpi::SmartDashboard::UpdateValues();
   EXPECT_EQ(ligament->GetAngle(), angleEntry.GetDouble(0.0));
   EXPECT_EQ(ligament->GetColor().HexString(), colorEntry.GetString(""));
   EXPECT_EQ(ligament->GetLength(), lengthEntry.GetDouble(0.0));
diff --git a/wpilibc/src/test/native/cpp/smartdashboard/SendableChooserTest.cpp b/wpilibc/src/test/native/cpp/smartdashboard/SendableChooserTest.cpp
index e2c37a048e..3cc09862d5 100644
--- a/wpilibc/src/test/native/cpp/smartdashboard/SendableChooserTest.cpp
+++ b/wpilibc/src/test/native/cpp/smartdashboard/SendableChooserTest.cpp
@@ -16,8 +16,8 @@
 class SendableChooserTest : public ::testing::TestWithParam {};
 
 TEST_P(SendableChooserTest, ReturnsSelected) {
-  frc::SendableChooser chooser;
-  frc::sim::SendableChooserSim chooserSim{
+  wpi::SendableChooser chooser;
+  wpi::sim::SendableChooserSim chooserSim{
       fmt::format("/SmartDashboard/ReturnsSelectedChooser{}/", GetParam())};
 
   for (int i = 1; i <= 3; i++) {
@@ -25,16 +25,16 @@ TEST_P(SendableChooserTest, ReturnsSelected) {
   }
   chooser.SetDefaultOption("0", 0);
 
-  frc::SmartDashboard::PutData(
+  wpi::SmartDashboard::PutData(
       fmt::format("ReturnsSelectedChooser{}", GetParam()), &chooser);
-  frc::SmartDashboard::UpdateValues();
+  wpi::SmartDashboard::UpdateValues();
   chooserSim.SetSelected(std::to_string(GetParam()));
-  frc::SmartDashboard::UpdateValues();
+  wpi::SmartDashboard::UpdateValues();
   EXPECT_EQ(GetParam(), chooser.GetSelected());
 }
 
 TEST(SendableChooserTest, DefaultIsReturnedOnNoSelect) {
-  frc::SendableChooser chooser;
+  wpi::SendableChooser chooser;
 
   for (int i = 1; i <= 3; i++) {
     chooser.AddOption(std::to_string(i), i);
@@ -48,7 +48,7 @@ TEST(SendableChooserTest, DefaultIsReturnedOnNoSelect) {
 
 TEST(SendableChooserTest,
      DefaultConstructableIsReturnedOnNoSelectAndNoDefault) {
-  frc::SendableChooser chooser;
+  wpi::SendableChooser chooser;
 
   for (int i = 1; i <= 3; i++) {
     chooser.AddOption(std::to_string(i), i);
@@ -58,8 +58,8 @@ TEST(SendableChooserTest,
 }
 
 TEST(SendableChooserTest, ChangeListener) {
-  frc::SendableChooser chooser;
-  frc::sim::SendableChooserSim chooserSim{
+  wpi::SendableChooser chooser;
+  wpi::sim::SendableChooserSim chooserSim{
       "/SmartDashboard/ChangeListenerChooser/"};
 
   for (int i = 1; i <= 3; i++) {
@@ -68,10 +68,10 @@ TEST(SendableChooserTest, ChangeListener) {
   int currentVal = 0;
   chooser.OnChange([&](int val) { currentVal = val; });
 
-  frc::SmartDashboard::PutData("ChangeListenerChooser", &chooser);
-  frc::SmartDashboard::UpdateValues();
+  wpi::SmartDashboard::PutData("ChangeListenerChooser", &chooser);
+  wpi::SmartDashboard::UpdateValues();
   chooserSim.SetSelected("3");
-  frc::SmartDashboard::UpdateValues();
+  wpi::SmartDashboard::UpdateValues();
 
   EXPECT_EQ(3, currentVal);
 }
diff --git a/wpilibc/src/test/native/cpp/util/Color8BitTest.cpp b/wpilibc/src/test/native/cpp/util/Color8BitTest.cpp
index 8c6fb18466..08b834a6d2 100644
--- a/wpilibc/src/test/native/cpp/util/Color8BitTest.cpp
+++ b/wpilibc/src/test/native/cpp/util/Color8BitTest.cpp
@@ -9,7 +9,7 @@
 #include "wpi/util/Color8Bit.hpp"
 
 TEST(Color8BitTest, ConstructDefault) {
-  constexpr frc::Color8Bit color;
+  constexpr wpi::Color8Bit color;
 
   EXPECT_EQ(0, color.red);
   EXPECT_EQ(0, color.green);
@@ -17,7 +17,7 @@ TEST(Color8BitTest, ConstructDefault) {
 }
 
 TEST(Color8BitTest, ConstructFromInts) {
-  constexpr frc::Color8Bit color{255, 128, 64};
+  constexpr wpi::Color8Bit color{255, 128, 64};
 
   EXPECT_EQ(255, color.red);
   EXPECT_EQ(128, color.green);
@@ -25,7 +25,7 @@ TEST(Color8BitTest, ConstructFromInts) {
 }
 
 TEST(Color8BitTest, ConstructFromColor) {
-  constexpr frc::Color8Bit color{frc::Color{255, 128, 64}};
+  constexpr wpi::Color8Bit color{wpi::Color{255, 128, 64}};
 
   EXPECT_EQ(255, color.red);
   EXPECT_EQ(128, color.green);
@@ -33,24 +33,24 @@ TEST(Color8BitTest, ConstructFromColor) {
 }
 
 TEST(Color8BitTest, ConstructFromHexString) {
-  constexpr frc::Color8Bit color{"#FF8040"};
+  constexpr wpi::Color8Bit color{"#FF8040"};
 
   EXPECT_EQ(255, color.red);
   EXPECT_EQ(128, color.green);
   EXPECT_EQ(64, color.blue);
 
   // No leading #
-  EXPECT_THROW(frc::Color8Bit{"112233"}, std::invalid_argument);
+  EXPECT_THROW(wpi::Color8Bit{"112233"}, std::invalid_argument);
 
   // Too long
-  EXPECT_THROW(frc::Color8Bit{"#11223344"}, std::invalid_argument);
+  EXPECT_THROW(wpi::Color8Bit{"#11223344"}, std::invalid_argument);
 
   // Invalid hex characters
-  EXPECT_THROW(frc::Color8Bit{"#$$$$$$"}, std::invalid_argument);
+  EXPECT_THROW(wpi::Color8Bit{"#$$$$$$"}, std::invalid_argument);
 }
 
 TEST(Color8BitTest, ImplicitConversionToColor) {
-  frc::Color color = frc::Color8Bit{255, 128, 64};
+  wpi::Color color = wpi::Color8Bit{255, 128, 64};
 
   EXPECT_NEAR(1.0, color.red, 1e-2);
   EXPECT_NEAR(0.5, color.green, 1e-2);
@@ -58,13 +58,13 @@ TEST(Color8BitTest, ImplicitConversionToColor) {
 }
 
 TEST(Color8BitTest, ToHexString) {
-  constexpr frc::Color8Bit color1{255, 128, 64};
+  constexpr wpi::Color8Bit color1{255, 128, 64};
   EXPECT_EQ("#FF8040", color1.HexString());
 
   // Ensure conversion to std::string works
   [[maybe_unused]]
   std::string str = color1.HexString();
 
-  frc::Color8Bit color2{255, 128, 64};
+  wpi::Color8Bit color2{255, 128, 64};
   EXPECT_EQ("#FF8040", color2.HexString());
 }
diff --git a/wpilibc/src/test/native/cpp/util/ColorTest.cpp b/wpilibc/src/test/native/cpp/util/ColorTest.cpp
index c352bb14b9..2d06cc8e1b 100644
--- a/wpilibc/src/test/native/cpp/util/ColorTest.cpp
+++ b/wpilibc/src/test/native/cpp/util/ColorTest.cpp
@@ -9,7 +9,7 @@
 #include "wpi/util/Color.hpp"
 
 TEST(ColorTest, ConstructDefault) {
-  constexpr frc::Color color;
+  constexpr wpi::Color color;
 
   EXPECT_DOUBLE_EQ(0.0, color.red);
   EXPECT_DOUBLE_EQ(0.0, color.green);
@@ -18,7 +18,7 @@ TEST(ColorTest, ConstructDefault) {
 
 TEST(ColorTest, ConstructFromDoubles) {
   {
-    constexpr frc::Color color{1.0, 0.5, 0.25};
+    constexpr wpi::Color color{1.0, 0.5, 0.25};
 
     EXPECT_NEAR(1.0, color.red, 1e-2);
     EXPECT_NEAR(0.5, color.green, 1e-2);
@@ -26,7 +26,7 @@ TEST(ColorTest, ConstructFromDoubles) {
   }
 
   {
-    constexpr frc::Color color{1.0, 0.0, 0.0};
+    constexpr wpi::Color color{1.0, 0.0, 0.0};
 
     // Check for exact match to ensure round-and-clamp is correct
     EXPECT_EQ(1.0, color.red);
@@ -36,7 +36,7 @@ TEST(ColorTest, ConstructFromDoubles) {
 }
 
 TEST(ColorTest, ConstructFromInts) {
-  constexpr frc::Color color{255, 128, 64};
+  constexpr wpi::Color color{255, 128, 64};
 
   EXPECT_NEAR(1.0, color.red, 1e-2);
   EXPECT_NEAR(0.5, color.green, 1e-2);
@@ -44,24 +44,24 @@ TEST(ColorTest, ConstructFromInts) {
 }
 
 TEST(ColorTest, ConstructFromHexString) {
-  constexpr frc::Color color{"#FF8040"};
+  constexpr wpi::Color color{"#FF8040"};
 
   EXPECT_NEAR(1.0, color.red, 1e-2);
   EXPECT_NEAR(0.5, color.green, 1e-2);
   EXPECT_NEAR(0.25, color.blue, 1e-2);
 
   // No leading #
-  EXPECT_THROW(frc::Color{"112233"}, std::invalid_argument);
+  EXPECT_THROW(wpi::Color{"112233"}, std::invalid_argument);
 
   // Too long
-  EXPECT_THROW(frc::Color{"#11223344"}, std::invalid_argument);
+  EXPECT_THROW(wpi::Color{"#11223344"}, std::invalid_argument);
 
   // Invalid hex characters
-  EXPECT_THROW(frc::Color{"#$$$$$$"}, std::invalid_argument);
+  EXPECT_THROW(wpi::Color{"#$$$$$$"}, std::invalid_argument);
 }
 
 TEST(ColorTest, FromHSV) {
-  constexpr frc::Color color = frc::Color::FromHSV(90, 128, 64);
+  constexpr wpi::Color color = wpi::Color::FromHSV(90, 128, 64);
 
   EXPECT_DOUBLE_EQ(0.125732421875, color.red);
   EXPECT_DOUBLE_EQ(0.251220703125, color.green);
@@ -69,13 +69,13 @@ TEST(ColorTest, FromHSV) {
 }
 
 TEST(ColorTest, ToHexString) {
-  constexpr frc::Color color1{255, 128, 64};
+  constexpr wpi::Color color1{255, 128, 64};
   EXPECT_EQ("#FF8040", color1.HexString());
 
   // Ensure conversion to std::string works
   [[maybe_unused]]
   std::string str = color1.HexString();
 
-  frc::Color color2{255, 128, 64};
+  wpi::Color color2{255, 128, 64};
   EXPECT_EQ("#FF8040", color2.HexString());
 }
diff --git a/wpilibc/src/test/native/include/callback_helpers/TestCallbackHelpers.hpp b/wpilibc/src/test/native/include/callback_helpers/TestCallbackHelpers.hpp
index 348bd15d92..7ea903b906 100644
--- a/wpilibc/src/test/native/include/callback_helpers/TestCallbackHelpers.hpp
+++ b/wpilibc/src/test/native/include/callback_helpers/TestCallbackHelpers.hpp
@@ -9,7 +9,7 @@
 
 #include "wpi/hal/Value.h"
 
-namespace frc::sim {
+namespace wpi::sim {
 
 template 
 class BaseCallbackHelper {
@@ -61,4 +61,4 @@ class DoubleCallback : public BaseCallbackHelper {
   void HandleCallback(std::string_view name, const HAL_Value* value) override;
 };
 
-}  // namespace frc::sim
+}  // namespace wpi::sim
diff --git a/wpilibc/src/test/native/include/motorcontrol/MockMotorController.hpp b/wpilibc/src/test/native/include/motorcontrol/MockMotorController.hpp
index 1d14727780..5eabe930e7 100644
--- a/wpilibc/src/test/native/include/motorcontrol/MockMotorController.hpp
+++ b/wpilibc/src/test/native/include/motorcontrol/MockMotorController.hpp
@@ -7,7 +7,7 @@
 #include "wpi/hardware/motor/MotorController.hpp"
 #include "wpi/util/deprecated.hpp"
 
-namespace frc {
+namespace wpi {
 
 WPI_IGNORE_DEPRECATED
 
@@ -27,4 +27,4 @@ class MockMotorController : public MotorController {
 
 WPI_UNIGNORE_DEPRECATED
 
-}  // namespace frc
+}  // namespace wpi
diff --git a/wpilibc/src/test/native/include/motorcontrol/MockPWMMotorController.hpp b/wpilibc/src/test/native/include/motorcontrol/MockPWMMotorController.hpp
index 18bd1f5615..a839c9aedc 100644
--- a/wpilibc/src/test/native/include/motorcontrol/MockPWMMotorController.hpp
+++ b/wpilibc/src/test/native/include/motorcontrol/MockPWMMotorController.hpp
@@ -4,7 +4,7 @@
 
 #pragma once
 
-namespace frc {
+namespace wpi {
 
 class MockPWMMotorController {
  public:
@@ -20,4 +20,4 @@ class MockPWMMotorController {
   bool m_isInverted = false;
 };
 
-}  // namespace frc
+}  // namespace wpi
diff --git a/wpilibcExamples/src/main/cpp/commands/command2/ReplaceMeCommand2.hpp b/wpilibcExamples/src/main/cpp/commands/command2/ReplaceMeCommand2.hpp
index 8b480207df..73acebd179 100644
--- a/wpilibcExamples/src/main/cpp/commands/command2/ReplaceMeCommand2.hpp
+++ b/wpilibcExamples/src/main/cpp/commands/command2/ReplaceMeCommand2.hpp
@@ -15,7 +15,7 @@
  * Command will *not* work!
  */
 class ReplaceMeCommand2
-    : public frc2::CommandHelper {
+    : public wpi::cmd::CommandHelper {
  public:
   /* You should consider using the more terse Command factories API instead
    * https://docs.wpilib.org/en/stable/docs/software/commandbased/organizing-command-based.html#defining-commands
diff --git a/wpilibcExamples/src/main/cpp/commands/instantcommand/ReplaceMeInstantCommand2.hpp b/wpilibcExamples/src/main/cpp/commands/instantcommand/ReplaceMeInstantCommand2.hpp
index 9114cb6e6c..4369e0aabd 100644
--- a/wpilibcExamples/src/main/cpp/commands/instantcommand/ReplaceMeInstantCommand2.hpp
+++ b/wpilibcExamples/src/main/cpp/commands/instantcommand/ReplaceMeInstantCommand2.hpp
@@ -11,7 +11,7 @@
 // For more information, see:
 // https://docs.wpilib.org/en/stable/docs/software/commandbased/convenience-features.html
 class ReplaceMeInstantCommand2
-    : public frc2::CommandHelper {
  public:
   ReplaceMeInstantCommand2();
diff --git a/wpilibcExamples/src/main/cpp/commands/parallelcommandgroup/ReplaceMeParallelCommandGroup.hpp b/wpilibcExamples/src/main/cpp/commands/parallelcommandgroup/ReplaceMeParallelCommandGroup.hpp
index baa00521b0..4405659dd1 100644
--- a/wpilibcExamples/src/main/cpp/commands/parallelcommandgroup/ReplaceMeParallelCommandGroup.hpp
+++ b/wpilibcExamples/src/main/cpp/commands/parallelcommandgroup/ReplaceMeParallelCommandGroup.hpp
@@ -11,7 +11,7 @@
 // For more information, see:
 // https://docs.wpilib.org/en/stable/docs/software/commandbased/convenience-features.html
 class ReplaceMeParallelCommandGroup
-    : public frc2::CommandHelper {
  public:
   ReplaceMeParallelCommandGroup();
diff --git a/wpilibcExamples/src/main/cpp/commands/paralleldeadlinegroup/ReplaceMeParallelDeadlineGroup.cpp b/wpilibcExamples/src/main/cpp/commands/paralleldeadlinegroup/ReplaceMeParallelDeadlineGroup.cpp
index b7b65e40ca..c0fcc57cb2 100644
--- a/wpilibcExamples/src/main/cpp/commands/paralleldeadlinegroup/ReplaceMeParallelDeadlineGroup.cpp
+++ b/wpilibcExamples/src/main/cpp/commands/paralleldeadlinegroup/ReplaceMeParallelDeadlineGroup.cpp
@@ -11,7 +11,7 @@
 // https://docs.wpilib.org/en/stable/docs/software/commandbased/convenience-features.html
 ReplaceMeParallelDeadlineGroup::ReplaceMeParallelDeadlineGroup()
     // The deadline command
-    : CommandHelper{frc2::InstantCommand{[] {}}} {
+    : CommandHelper{wpi::cmd::InstantCommand{[] {}}} {
   // Add your commands here, e.g.
   // AddCommands(FooCommand{}, BarCommand{});
 }
diff --git a/wpilibcExamples/src/main/cpp/commands/paralleldeadlinegroup/ReplaceMeParallelDeadlineGroup.hpp b/wpilibcExamples/src/main/cpp/commands/paralleldeadlinegroup/ReplaceMeParallelDeadlineGroup.hpp
index 2ec4a7bd6a..6ed5c7d21a 100644
--- a/wpilibcExamples/src/main/cpp/commands/paralleldeadlinegroup/ReplaceMeParallelDeadlineGroup.hpp
+++ b/wpilibcExamples/src/main/cpp/commands/paralleldeadlinegroup/ReplaceMeParallelDeadlineGroup.hpp
@@ -11,7 +11,7 @@
 // For more information, see:
 // https://docs.wpilib.org/en/stable/docs/software/commandbased/convenience-features.html
 class ReplaceMeParallelDeadlineGroup
-    : public frc2::CommandHelper {
  public:
   ReplaceMeParallelDeadlineGroup();
diff --git a/wpilibcExamples/src/main/cpp/commands/parallelracegroup/ReplaceMeParallelRaceGroup.hpp b/wpilibcExamples/src/main/cpp/commands/parallelracegroup/ReplaceMeParallelRaceGroup.hpp
index 635ef64176..866e2916d2 100644
--- a/wpilibcExamples/src/main/cpp/commands/parallelracegroup/ReplaceMeParallelRaceGroup.hpp
+++ b/wpilibcExamples/src/main/cpp/commands/parallelracegroup/ReplaceMeParallelRaceGroup.hpp
@@ -11,7 +11,7 @@
 // For more information, see:
 // https://docs.wpilib.org/en/stable/docs/software/commandbased/convenience-features.html
 class ReplaceMeParallelRaceGroup
-    : public frc2::CommandHelper {
  public:
   ReplaceMeParallelRaceGroup();
diff --git a/wpilibcExamples/src/main/cpp/commands/sequentialcommandgroup/ReplaceMeSequentialCommandGroup.hpp b/wpilibcExamples/src/main/cpp/commands/sequentialcommandgroup/ReplaceMeSequentialCommandGroup.hpp
index fd02c378e6..d15902cdd4 100644
--- a/wpilibcExamples/src/main/cpp/commands/sequentialcommandgroup/ReplaceMeSequentialCommandGroup.hpp
+++ b/wpilibcExamples/src/main/cpp/commands/sequentialcommandgroup/ReplaceMeSequentialCommandGroup.hpp
@@ -11,7 +11,7 @@
 // For more information, see:
 // https://docs.wpilib.org/en/stable/docs/software/commandbased/convenience-features.html
 class ReplaceMeSequentialCommandGroup
-    : public frc2::CommandHelper {
  public:
   ReplaceMeSequentialCommandGroup();
diff --git a/wpilibcExamples/src/main/cpp/commands/subsystem2/ReplaceMeSubsystem2.hpp b/wpilibcExamples/src/main/cpp/commands/subsystem2/ReplaceMeSubsystem2.hpp
index c98e3c0141..8669026d35 100644
--- a/wpilibcExamples/src/main/cpp/commands/subsystem2/ReplaceMeSubsystem2.hpp
+++ b/wpilibcExamples/src/main/cpp/commands/subsystem2/ReplaceMeSubsystem2.hpp
@@ -6,7 +6,7 @@
 
 #include 
 
-class ReplaceMeSubsystem2 : public frc2::SubsystemBase {
+class ReplaceMeSubsystem2 : public wpi::cmd::SubsystemBase {
  public:
   ReplaceMeSubsystem2();
 
diff --git a/wpilibcExamples/src/main/cpp/examples/AddressableLED/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/AddressableLED/cpp/Robot.cpp
index 4c47b07ae2..e2d3de4307 100644
--- a/wpilibcExamples/src/main/cpp/examples/AddressableLED/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/AddressableLED/cpp/Robot.cpp
@@ -19,6 +19,6 @@ void Robot::RobotPeriodic() {
 
 #ifndef RUNNING_FRC_TESTS
 int main() {
-  return frc::StartRobot();
+  return wpi::StartRobot();
 }
 #endif
diff --git a/wpilibcExamples/src/main/cpp/examples/AddressableLED/include/Robot.hpp b/wpilibcExamples/src/main/cpp/examples/AddressableLED/include/Robot.hpp
index 4c17cc6d21..b97cd31a88 100644
--- a/wpilibcExamples/src/main/cpp/examples/AddressableLED/include/Robot.hpp
+++ b/wpilibcExamples/src/main/cpp/examples/AddressableLED/include/Robot.hpp
@@ -10,7 +10,7 @@
 #include 
 #include 
 
-class Robot : public frc::TimedRobot {
+class Robot : public wpi::TimedRobot {
  public:
   Robot();
   void RobotPeriodic() override;
@@ -19,19 +19,19 @@ class Robot : public frc::TimedRobot {
   static constexpr int kLength = 60;
 
   // SmartIO port 1
-  frc::AddressableLED m_led{1};
-  std::array
+  wpi::AddressableLED m_led{1};
+  std::array
       m_ledBuffer;  // Reuse the buffer
 
   // Our LED strip has a density of 120 LEDs per meter
-  units::meter_t kLedSpacing{1 / 120.0};
+  wpi::units::meter_t kLedSpacing{1 / 120.0};
 
   // Create an LED pattern that will display a rainbow across
   // all hues at maximum saturation and half brightness
-  frc::LEDPattern m_rainbow = frc::LEDPattern::Rainbow(255, 128);
+  wpi::LEDPattern m_rainbow = wpi::LEDPattern::Rainbow(255, 128);
 
   // Create a new pattern that scrolls the rainbow pattern across the LED
   // strip, moving at a speed of 1 meter per second.
-  frc::LEDPattern m_scrollingRainbow =
+  wpi::LEDPattern m_scrollingRainbow =
       m_rainbow.ScrollAtAbsoluteSpeed(1_mps, kLedSpacing);
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/AprilTagsVision/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/AprilTagsVision/cpp/Robot.cpp
index 77cf206af0..0e071b248c 100644
--- a/wpilibcExamples/src/main/cpp/examples/AprilTagsVision/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/AprilTagsVision/cpp/Robot.cpp
@@ -31,7 +31,7 @@
  * Be aware that the performance on this is much worse than a coprocessor
  * solution!
  */
-class Robot : public frc::TimedRobot {
+class Robot : public wpi::TimedRobot {
  public:
   Robot() {
     // We need to run our vision program in a separate thread. If not, our robot
@@ -49,7 +49,7 @@ class Robot : public frc::TimedRobot {
 
  private:
   static void VisionThread() {
-    frc::AprilTagDetector detector;
+    wpi::apriltag::AprilTagDetector detector;
     // look for tag36h11, correct 1 error bit
     // hamming 1 allocates 781KB, 2 allocates 27.4 MB, 3 allocates 932 MB
     // max of 1 recommended for RoboRIO 1, while hamming 2 is feasible on the
@@ -58,24 +58,24 @@ class Robot : public frc::TimedRobot {
 
     // Set up Pose Estimator - parameters are for a Microsoft Lifecam HD-3000
     // (https://www.chiefdelphi.com/t/wpilib-apriltagdetector-sample-code/421411/21)
-    frc::AprilTagPoseEstimator::Config poseEstConfig = {
+    wpi::apriltag::AprilTagPoseEstimator::Config poseEstConfig = {
         .tagSize = 6.5_in,
         .fx = 699.3778103158814,
         .fy = 677.7161226393544,
         .cx = 345.6059345433618,
         .cy = 207.12741326228522};
-    frc::AprilTagPoseEstimator estimator(poseEstConfig);
+    wpi::apriltag::AprilTagPoseEstimator estimator(poseEstConfig);
 
     // Get the USB camera from CameraServer
-    cs::UsbCamera camera = frc::CameraServer::StartAutomaticCapture();
+    wpi::cs::UsbCamera camera = wpi::CameraServer::StartAutomaticCapture();
     // Set the resolution
     camera.SetResolution(640, 480);
 
     // Get a CvSink. This will capture Mats from the Camera
-    cs::CvSink cvSink = frc::CameraServer::GetVideo();
+    wpi::cs::CvSink cvSink = wpi::CameraServer::GetVideo();
     // Setup a CvSource. This will send images back to the Dashboard
-    cs::CvSource outputStream =
-        frc::CameraServer::PutVideo("Detected", 640, 480);
+    wpi::cs::CvSource outputStream =
+        wpi::CameraServer::PutVideo("Detected", 640, 480);
 
     // Mats are very memory expensive. Lets reuse this Mat.
     cv::Mat mat;
@@ -88,7 +88,7 @@ class Robot : public frc::TimedRobot {
 
     // We'll output to NT
     auto tagsTable =
-        nt::NetworkTableInstance::GetDefault().GetTable("apriltags");
+        wpi::nt::NetworkTableInstance::GetDefault().GetTable("apriltags");
     auto pubTags = tagsTable->GetIntegerArrayTopic("tags").Publish();
 
     while (true) {
@@ -105,27 +105,27 @@ class Robot : public frc::TimedRobot {
       cv::cvtColor(mat, grayMat, cv::COLOR_BGR2GRAY);
 
       cv::Size g_size = grayMat.size();
-      frc::AprilTagDetector::Results detections =
+      wpi::apriltag::AprilTagDetector::Results detections =
           detector.Detect(g_size.width, g_size.height, grayMat.data);
 
       // have not seen any tags yet
       tags.clear();
 
-      for (const frc::AprilTagDetection* detection : detections) {
+      for (const wpi::apriltag::AprilTagDetection* detection : detections) {
         // remember we saw this tag
         tags.push_back(detection->GetId());
 
         // draw lines around the tag
         for (int i = 0; i <= 3; i++) {
           int j = (i + 1) % 4;
-          const frc::AprilTagDetection::Point pti = detection->GetCorner(i);
-          const frc::AprilTagDetection::Point ptj = detection->GetCorner(j);
+          const wpi::apriltag::AprilTagDetection::Point pti = detection->GetCorner(i);
+          const wpi::apriltag::AprilTagDetection::Point ptj = detection->GetCorner(j);
           line(mat, cv::Point(pti.x, pti.y), cv::Point(ptj.x, ptj.y),
                outlineColor, 2);
         }
 
         // mark the center of the tag
-        const frc::AprilTagDetection::Point c = detection->GetCenter();
+        const wpi::apriltag::AprilTagDetection::Point c = detection->GetCenter();
         int ll = 10;
         line(mat, cv::Point(c.x - ll, c.y), cv::Point(c.x + ll, c.y),
              crossColor, 2);
@@ -138,10 +138,10 @@ class Robot : public frc::TimedRobot {
                 crossColor, 3);
 
         // determine pose
-        frc::Transform3d pose = estimator.Estimate(*detection);
+        wpi::math::Transform3d pose = estimator.Estimate(*detection);
 
         // put pose into NT
-        frc::Rotation3d rotation = pose.Rotation();
+        wpi::math::Rotation3d rotation = pose.Rotation();
         tagsTable->GetEntry(fmt::format("pose_{}", detection->GetId()))
             .SetDoubleArray(
                 {{ pose.X().value(),
@@ -164,6 +164,6 @@ class Robot : public frc::TimedRobot {
 
 #ifndef RUNNING_FRC_TESTS
 int main() {
-  return frc::StartRobot();
+  return wpi::StartRobot();
 }
 #endif
diff --git a/wpilibcExamples/src/main/cpp/examples/ArcadeDrive/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ArcadeDrive/cpp/Robot.cpp
index 9baa0905c0..d8509f4f42 100644
--- a/wpilibcExamples/src/main/cpp/examples/ArcadeDrive/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/ArcadeDrive/cpp/Robot.cpp
@@ -11,18 +11,18 @@
  * This is a demo program showing the use of the DifferentialDrive class.
  * Runs the motors with arcade steering.
  */
-class Robot : public frc::TimedRobot {
-  frc::PWMSparkMax m_leftMotor{0};
-  frc::PWMSparkMax m_rightMotor{1};
-  frc::DifferentialDrive m_robotDrive{
+class Robot : public wpi::TimedRobot {
+  wpi::PWMSparkMax m_leftMotor{0};
+  wpi::PWMSparkMax m_rightMotor{1};
+  wpi::DifferentialDrive m_robotDrive{
       [&](double output) { m_leftMotor.Set(output); },
       [&](double output) { m_rightMotor.Set(output); }};
-  frc::Joystick m_stick{0};
+  wpi::Joystick m_stick{0};
 
  public:
   Robot() {
-    wpi::SendableRegistry::AddChild(&m_robotDrive, &m_leftMotor);
-    wpi::SendableRegistry::AddChild(&m_robotDrive, &m_rightMotor);
+    wpi::util::SendableRegistry::AddChild(&m_robotDrive, &m_leftMotor);
+    wpi::util::SendableRegistry::AddChild(&m_robotDrive, &m_rightMotor);
 
     // We need to invert one side of the drivetrain so that positive voltages
     // result in both sides moving forward. Depending on how your robot's
@@ -38,6 +38,6 @@ class Robot : public frc::TimedRobot {
 
 #ifndef RUNNING_FRC_TESTS
 int main() {
-  return frc::StartRobot();
+  return wpi::StartRobot();
 }
 #endif
diff --git a/wpilibcExamples/src/main/cpp/examples/ArcadeDriveXboxController/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ArcadeDriveXboxController/cpp/Robot.cpp
index 58c319541c..6b428ee01f 100644
--- a/wpilibcExamples/src/main/cpp/examples/ArcadeDriveXboxController/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/ArcadeDriveXboxController/cpp/Robot.cpp
@@ -11,18 +11,18 @@
  * This is a demo program showing the use of the DifferentialDrive class.
  * Runs the motors with split arcade steering and an Xbox controller.
  */
-class Robot : public frc::TimedRobot {
-  frc::PWMSparkMax m_leftMotor{0};
-  frc::PWMSparkMax m_rightMotor{1};
-  frc::DifferentialDrive m_robotDrive{
+class Robot : public wpi::TimedRobot {
+  wpi::PWMSparkMax m_leftMotor{0};
+  wpi::PWMSparkMax m_rightMotor{1};
+  wpi::DifferentialDrive m_robotDrive{
       [&](double output) { m_leftMotor.Set(output); },
       [&](double output) { m_rightMotor.Set(output); }};
-  frc::XboxController m_driverController{0};
+  wpi::XboxController m_driverController{0};
 
  public:
   Robot() {
-    wpi::SendableRegistry::AddChild(&m_robotDrive, &m_leftMotor);
-    wpi::SendableRegistry::AddChild(&m_robotDrive, &m_rightMotor);
+    wpi::util::SendableRegistry::AddChild(&m_robotDrive, &m_leftMotor);
+    wpi::util::SendableRegistry::AddChild(&m_robotDrive, &m_rightMotor);
 
     // We need to invert one side of the drivetrain so that positive voltages
     // result in both sides moving forward. Depending on how your robot's
@@ -41,6 +41,6 @@ class Robot : public frc::TimedRobot {
 
 #ifndef RUNNING_FRC_TESTS
 int main() {
-  return frc::StartRobot();
+  return wpi::StartRobot();
 }
 #endif
diff --git a/wpilibcExamples/src/main/cpp/examples/ArmSimulation/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ArmSimulation/cpp/Robot.cpp
index 15cfb53301..ac3dfd9bff 100644
--- a/wpilibcExamples/src/main/cpp/examples/ArmSimulation/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/ArmSimulation/cpp/Robot.cpp
@@ -29,6 +29,6 @@ void Robot::DisabledInit() {
 
 #ifndef RUNNING_FRC_TESTS
 int main() {
-  return frc::StartRobot();
+  return wpi::StartRobot();
 }
 #endif
diff --git a/wpilibcExamples/src/main/cpp/examples/ArmSimulation/cpp/subsystems/Arm.cpp b/wpilibcExamples/src/main/cpp/examples/ArmSimulation/cpp/subsystems/Arm.cpp
index cead817b37..b443e5159b 100644
--- a/wpilibcExamples/src/main/cpp/examples/ArmSimulation/cpp/subsystems/Arm.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/ArmSimulation/cpp/subsystems/Arm.cpp
@@ -13,19 +13,19 @@ Arm::Arm() {
   m_encoder.SetDistancePerPulse(kArmEncoderDistPerPulse);
 
   // Put Mechanism 2d to SmartDashboard
-  frc::SmartDashboard::PutData("Arm Sim", &m_mech2d);
+  wpi::SmartDashboard::PutData("Arm Sim", &m_mech2d);
 
   // Set the Arm position setpoint and P constant to Preferences if the keys
   // don't already exist
-  frc::Preferences::InitDouble(kArmPositionKey, m_armSetpoint.value());
-  frc::Preferences::InitDouble(kArmPKey, m_armKp);
+  wpi::Preferences::InitDouble(kArmPositionKey, m_armSetpoint.value());
+  wpi::Preferences::InitDouble(kArmPKey, m_armKp);
 }
 
 void Arm::SimulationPeriodic() {
   // In this method, we update our simulation of what our arm is doing
   // First, we set our "inputs" (voltages)
   m_armSim.SetInput(
-      frc::Vectord<1>{m_motor.Get() * frc::RobotController::GetInputVoltage()});
+      wpi::math::Vectord<1>{m_motor.Get() * wpi::RobotController::GetInputVoltage()});
 
   // Next, we update it. The standard loop time is 20ms.
   m_armSim.Update(20_ms);
@@ -34,8 +34,8 @@ void Arm::SimulationPeriodic() {
   // voltage
   m_encoderSim.SetDistance(m_armSim.GetAngle().value());
   // SimBattery estimates loaded battery voltages
-  frc::sim::RoboRioSim::SetVInVoltage(
-      frc::sim::BatterySim::Calculate({m_armSim.GetCurrentDraw()}));
+  wpi::sim::RoboRioSim::SetVInVoltage(
+      wpi::sim::BatterySim::Calculate({m_armSim.GetCurrentDraw()}));
 
   // Update the Mechanism Arm angle based on the simulated arm angle
   m_arm->SetAngle(m_armSim.GetAngle());
@@ -43,10 +43,10 @@ void Arm::SimulationPeriodic() {
 
 void Arm::LoadPreferences() {
   // Read Preferences for Arm setpoint and kP on entering Teleop
-  m_armSetpoint = units::degree_t{
-      frc::Preferences::GetDouble(kArmPositionKey, m_armSetpoint.value())};
-  if (m_armKp != frc::Preferences::GetDouble(kArmPKey, m_armKp)) {
-    m_armKp = frc::Preferences::GetDouble(kArmPKey, m_armKp);
+  m_armSetpoint = wpi::units::degree_t{
+      wpi::Preferences::GetDouble(kArmPositionKey, m_armSetpoint.value())};
+  if (m_armKp != wpi::Preferences::GetDouble(kArmPKey, m_armKp)) {
+    m_armKp = wpi::Preferences::GetDouble(kArmPKey, m_armKp);
     m_controller.SetP(m_armKp);
   }
 }
@@ -55,8 +55,8 @@ void Arm::ReachSetpoint() {
   // Here, we run PID control like normal, with a setpoint read from
   // preferences in degrees.
   double pidOutput = m_controller.Calculate(
-      m_encoder.GetDistance(), (units::radian_t{m_armSetpoint}.value()));
-  m_motor.SetVoltage(units::volt_t{pidOutput});
+      m_encoder.GetDistance(), (wpi::units::radian_t{m_armSetpoint}.value()));
+  m_motor.SetVoltage(wpi::units::volt_t{pidOutput});
 }
 
 void Arm::Stop() {
diff --git a/wpilibcExamples/src/main/cpp/examples/ArmSimulation/include/Constants.hpp b/wpilibcExamples/src/main/cpp/examples/ArmSimulation/include/Constants.hpp
index 816a7d39db..cda5ee0317 100644
--- a/wpilibcExamples/src/main/cpp/examples/ArmSimulation/include/Constants.hpp
+++ b/wpilibcExamples/src/main/cpp/examples/ArmSimulation/include/Constants.hpp
@@ -31,14 +31,14 @@ inline constexpr std::string_view kArmPositionKey = "ArmPosition";
 inline constexpr std::string_view kArmPKey = "ArmP";
 
 inline constexpr double kDefaultArmKp = 50.0;
-inline constexpr units::degree_t kDefaultArmSetpoint = 75.0_deg;
+inline constexpr wpi::units::degree_t kDefaultArmSetpoint = 75.0_deg;
 
-inline constexpr units::radian_t kMinAngle = -75.0_deg;
-inline constexpr units::radian_t kMaxAngle = 255.0_deg;
+inline constexpr wpi::units::radian_t kMinAngle = -75.0_deg;
+inline constexpr wpi::units::radian_t kMaxAngle = 255.0_deg;
 
 inline constexpr double kArmReduction = 200.0;
-inline constexpr units::kilogram_t kArmMass = 8.0_kg;
-inline constexpr units::meter_t kArmLength = 30.0_in;
+inline constexpr wpi::units::kilogram_t kArmMass = 8.0_kg;
+inline constexpr wpi::units::meter_t kArmLength = 30.0_in;
 
 // distance per pulse = (angle per revolution) / (pulses per revolution)
 //  = (2 * PI rads) / (4096 pulses)
diff --git a/wpilibcExamples/src/main/cpp/examples/ArmSimulation/include/Robot.hpp b/wpilibcExamples/src/main/cpp/examples/ArmSimulation/include/Robot.hpp
index 53f13e7f0c..032fff4033 100644
--- a/wpilibcExamples/src/main/cpp/examples/ArmSimulation/include/Robot.hpp
+++ b/wpilibcExamples/src/main/cpp/examples/ArmSimulation/include/Robot.hpp
@@ -12,7 +12,7 @@
 /**
  * This is a sample program to demonstrate the use of arm simulation.
  */
-class Robot : public frc::TimedRobot {
+class Robot : public wpi::TimedRobot {
  public:
   Robot() {}
   void SimulationPeriodic() override;
@@ -21,6 +21,6 @@ class Robot : public frc::TimedRobot {
   void DisabledInit() override;
 
  private:
-  frc::Joystick m_joystick{kJoystickPort};
+  wpi::Joystick m_joystick{kJoystickPort};
   Arm m_arm;
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/ArmSimulation/include/subsystems/Arm.hpp b/wpilibcExamples/src/main/cpp/examples/ArmSimulation/include/subsystems/Arm.hpp
index 01abb0d076..ae87d939b5 100644
--- a/wpilibcExamples/src/main/cpp/examples/ArmSimulation/include/subsystems/Arm.hpp
+++ b/wpilibcExamples/src/main/cpp/examples/ArmSimulation/include/subsystems/Arm.hpp
@@ -31,38 +31,38 @@ class Arm {
  private:
   // The P gain for the PID controller that drives this arm.
   double m_armKp = kDefaultArmKp;
-  units::degree_t m_armSetpoint = kDefaultArmSetpoint;
+  wpi::units::degree_t m_armSetpoint = kDefaultArmSetpoint;
 
   // The arm gearbox represents a gearbox containing two Vex 775pro motors.
-  frc::DCMotor m_armGearbox = frc::DCMotor::Vex775Pro(2);
+  wpi::math::DCMotor m_armGearbox = wpi::math::DCMotor::Vex775Pro(2);
 
   // Standard classes for controlling our arm
-  frc::PIDController m_controller{m_armKp, 0, 0};
-  frc::Encoder m_encoder{kEncoderAChannel, kEncoderBChannel};
-  frc::PWMSparkMax m_motor{kMotorPort};
+  wpi::math::PIDController m_controller{m_armKp, 0, 0};
+  wpi::Encoder m_encoder{kEncoderAChannel, kEncoderBChannel};
+  wpi::PWMSparkMax m_motor{kMotorPort};
 
   // Simulation classes help us simulate what's going on, including gravity.
   // This sim represents an arm with 2 775s, a 600:1 reduction, a mass of 5kg,
   // 30in overall arm length, range of motion in [-75, 255] degrees, and noise
   // with a standard deviation of 1 encoder tick.
-  frc::sim::SingleJointedArmSim m_armSim{
+  wpi::sim::SingleJointedArmSim m_armSim{
       m_armGearbox,
       kArmReduction,
-      frc::sim::SingleJointedArmSim::EstimateMOI(kArmLength, kArmMass),
+      wpi::sim::SingleJointedArmSim::EstimateMOI(kArmLength, kArmMass),
       kArmLength,
       kMinAngle,
       kMaxAngle,
       true,
       0_deg,
       {kArmEncoderDistPerPulse}};
-  frc::sim::EncoderSim m_encoderSim{m_encoder};
+  wpi::sim::EncoderSim m_encoderSim{m_encoder};
 
   // Create a Mechanism2d display of an Arm
-  frc::Mechanism2d m_mech2d{60, 60};
-  frc::MechanismRoot2d* m_armBase = m_mech2d.GetRoot("ArmBase", 30, 30);
-  frc::MechanismLigament2d* m_armTower =
-      m_armBase->Append(
-          "Arm Tower", 30, -90_deg, 6, frc::Color8Bit{frc::Color::kBlue});
-  frc::MechanismLigament2d* m_arm = m_armBase->Append(
-      "Arm", 30, m_armSim.GetAngle(), 6, frc::Color8Bit{frc::Color::kYellow});
+  wpi::Mechanism2d m_mech2d{60, 60};
+  wpi::MechanismRoot2d* m_armBase = m_mech2d.GetRoot("ArmBase", 30, 30);
+  wpi::MechanismLigament2d* m_armTower =
+      m_armBase->Append(
+          "Arm Tower", 30, -90_deg, 6, wpi::Color8Bit{wpi::Color::kBlue});
+  wpi::MechanismLigament2d* m_arm = m_armBase->Append(
+      "Arm", 30, m_armSim.GetAngle(), 6, wpi::Color8Bit{wpi::Color::kYellow});
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/CANPDP/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/CANPDP/cpp/Robot.cpp
index 3a83020687..b68b7551c8 100644
--- a/wpilibcExamples/src/main/cpp/examples/CANPDP/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/CANPDP/cpp/Robot.cpp
@@ -11,11 +11,11 @@
  * Distribution Panel via CAN. The information will be displayed under variables
  * through the SmartDashboard.
  */
-class Robot : public frc::TimedRobot {
+class Robot : public wpi::TimedRobot {
  public:
   Robot() {
     // Put the PDP itself to the dashboard
-    frc::SmartDashboard::PutData("PDP", &m_pdp);
+    wpi::SmartDashboard::PutData("PDP", &m_pdp);
   }
 
   void RobotPeriodic() override {
@@ -23,39 +23,39 @@ class Robot : public frc::TimedRobot {
     // The PDP returns the current in increments of 0.125A.
     // At low currents the current readings tend to be less accurate.
     double current7 = m_pdp.GetCurrent(7);
-    frc::SmartDashboard::PutNumber("Current Channel 7", current7);
+    wpi::SmartDashboard::PutNumber("Current Channel 7", current7);
 
     // Get the voltage going into the PDP, in Volts.
     // The PDP returns the voltage in increments of 0.05 Volts.
     double voltage = m_pdp.GetVoltage();
-    frc::SmartDashboard::PutNumber("Voltage", voltage);
+    wpi::SmartDashboard::PutNumber("Voltage", voltage);
 
     // Retrieves the temperature of the PDP, in degrees Celsius.
     double temperatureCelsius = m_pdp.GetTemperature();
-    frc::SmartDashboard::PutNumber("Temperature", temperatureCelsius);
+    wpi::SmartDashboard::PutNumber("Temperature", temperatureCelsius);
 
     // Get the total current of all channels.
     double totalCurrent = m_pdp.GetTotalCurrent();
-    frc::SmartDashboard::PutNumber("Total Current", totalCurrent);
+    wpi::SmartDashboard::PutNumber("Total Current", totalCurrent);
 
     // Get the total power of all channels.
     // Power is the bus voltage multiplied by the current with the units Watts.
     double totalPower = m_pdp.GetTotalPower();
-    frc::SmartDashboard::PutNumber("Total Power", totalPower);
+    wpi::SmartDashboard::PutNumber("Total Power", totalPower);
 
     // Get the total energy of all channels.
     // Energy is the power summed over time with units Joules.
     double totalEnergy = m_pdp.GetTotalEnergy();
-    frc::SmartDashboard::PutNumber("Total Energy", totalEnergy);
+    wpi::SmartDashboard::PutNumber("Total Energy", totalEnergy);
   }
 
  private:
   // Object for dealing with the Power Distribution Panel (PDP).
-  frc::PowerDistribution m_pdp{0};
+  wpi::PowerDistribution m_pdp{0};
 };
 
 #ifndef RUNNING_FRC_TESTS
 int main() {
-  return frc::StartRobot();
+  return wpi::StartRobot();
 }
 #endif
diff --git a/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/cpp/Drivetrain.cpp b/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/cpp/Drivetrain.cpp
index 0ed23babec..86a9a96b20 100644
--- a/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/cpp/Drivetrain.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/cpp/Drivetrain.cpp
@@ -4,7 +4,7 @@
 
 #include "Drivetrain.hpp"
 
-void Drivetrain::SetSpeeds(const frc::DifferentialDriveWheelSpeeds& speeds) {
+void Drivetrain::SetSpeeds(const wpi::math::DifferentialDriveWheelSpeeds& speeds) {
   const auto leftFeedforward = m_feedforward.Calculate(speeds.left);
   const auto rightFeedforward = m_feedforward.Calculate(speeds.right);
   const double leftOutput = m_leftPIDController.Calculate(
@@ -12,17 +12,17 @@ void Drivetrain::SetSpeeds(const frc::DifferentialDriveWheelSpeeds& speeds) {
   const double rightOutput = m_rightPIDController.Calculate(
       m_rightEncoder.GetRate(), speeds.right.value());
 
-  m_leftLeader.SetVoltage(units::volt_t{leftOutput} + leftFeedforward);
-  m_rightLeader.SetVoltage(units::volt_t{rightOutput} + rightFeedforward);
+  m_leftLeader.SetVoltage(wpi::units::volt_t{leftOutput} + leftFeedforward);
+  m_rightLeader.SetVoltage(wpi::units::volt_t{rightOutput} + rightFeedforward);
 }
 
-void Drivetrain::Drive(units::meters_per_second_t xSpeed,
-                       units::radians_per_second_t rot) {
+void Drivetrain::Drive(wpi::units::meters_per_second_t xSpeed,
+                       wpi::units::radians_per_second_t rot) {
   SetSpeeds(m_kinematics.ToWheelSpeeds({xSpeed, 0_mps, rot}));
 }
 
 void Drivetrain::UpdateOdometry() {
   m_odometry.Update(m_imu.GetRotation2d(),
-                    units::meter_t{m_leftEncoder.GetDistance()},
-                    units::meter_t{m_rightEncoder.GetDistance()});
+                    wpi::units::meter_t{m_leftEncoder.GetDistance()},
+                    wpi::units::meter_t{m_rightEncoder.GetDistance()});
 }
diff --git a/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/cpp/Robot.cpp
index bbc136e116..3564349923 100644
--- a/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/cpp/Robot.cpp
@@ -8,7 +8,7 @@
 
 #include "Drivetrain.hpp"
 
-class Robot : public frc::TimedRobot {
+class Robot : public wpi::TimedRobot {
  public:
   void AutonomousPeriodic() override {
     TeleopPeriodic();
@@ -32,18 +32,18 @@ class Robot : public frc::TimedRobot {
   }
 
  private:
-  frc::XboxController m_controller{0};
+  wpi::XboxController m_controller{0};
 
   // Slew rate limiters to make joystick inputs more gentle; 1/3 sec from 0
   // to 1.
-  frc::SlewRateLimiter m_speedLimiter{3 / 1_s};
-  frc::SlewRateLimiter m_rotLimiter{3 / 1_s};
+  wpi::math::SlewRateLimiter m_speedLimiter{3 / 1_s};
+  wpi::math::SlewRateLimiter m_rotLimiter{3 / 1_s};
 
   Drivetrain m_drive;
 };
 
 #ifndef RUNNING_FRC_TESTS
 int main() {
-  return frc::StartRobot();
+  return wpi::StartRobot();
 }
 #endif
diff --git a/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/include/Drivetrain.hpp b/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/include/Drivetrain.hpp
index ca300d571f..6487ac102b 100644
--- a/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/include/Drivetrain.hpp
+++ b/wpilibcExamples/src/main/cpp/examples/DifferentialDriveBot/include/Drivetrain.hpp
@@ -45,40 +45,40 @@ class Drivetrain {
     m_rightEncoder.Reset();
   }
 
-  static constexpr units::meters_per_second_t kMaxSpeed =
+  static constexpr wpi::units::meters_per_second_t kMaxSpeed =
       3.0_mps;  // 3 meters per second
-  static constexpr units::radians_per_second_t kMaxAngularSpeed{
+  static constexpr wpi::units::radians_per_second_t kMaxAngularSpeed{
       std::numbers::pi};  // 1/2 rotation per second
 
-  void SetSpeeds(const frc::DifferentialDriveWheelSpeeds& speeds);
-  void Drive(units::meters_per_second_t xSpeed,
-             units::radians_per_second_t rot);
+  void SetSpeeds(const wpi::math::DifferentialDriveWheelSpeeds& speeds);
+  void Drive(wpi::units::meters_per_second_t xSpeed,
+             wpi::units::radians_per_second_t rot);
   void UpdateOdometry();
 
  private:
-  static constexpr units::meter_t kTrackwidth = 0.381_m * 2;
+  static constexpr wpi::units::meter_t kTrackwidth = 0.381_m * 2;
   static constexpr double kWheelRadius = 0.0508;  // meters
   static constexpr int kEncoderResolution = 4096;
 
-  frc::PWMSparkMax m_leftLeader{1};
-  frc::PWMSparkMax m_leftFollower{2};
-  frc::PWMSparkMax m_rightLeader{3};
-  frc::PWMSparkMax m_rightFollower{4};
+  wpi::PWMSparkMax m_leftLeader{1};
+  wpi::PWMSparkMax m_leftFollower{2};
+  wpi::PWMSparkMax m_rightLeader{3};
+  wpi::PWMSparkMax m_rightFollower{4};
 
-  frc::Encoder m_leftEncoder{0, 1};
-  frc::Encoder m_rightEncoder{2, 3};
+  wpi::Encoder m_leftEncoder{0, 1};
+  wpi::Encoder m_rightEncoder{2, 3};
 
-  frc::PIDController m_leftPIDController{1.0, 0.0, 0.0};
-  frc::PIDController m_rightPIDController{1.0, 0.0, 0.0};
+  wpi::math::PIDController m_leftPIDController{1.0, 0.0, 0.0};
+  wpi::math::PIDController m_rightPIDController{1.0, 0.0, 0.0};
 
-  frc::OnboardIMU m_imu{frc::OnboardIMU::kFlat};
+  wpi::OnboardIMU m_imu{wpi::OnboardIMU::kFlat};
 
-  frc::DifferentialDriveKinematics m_kinematics{kTrackwidth};
-  frc::DifferentialDriveOdometry m_odometry{
-      m_imu.GetRotation2d(), units::meter_t{m_leftEncoder.GetDistance()},
-      units::meter_t{m_rightEncoder.GetDistance()}};
+  wpi::math::DifferentialDriveKinematics m_kinematics{kTrackwidth};
+  wpi::math::DifferentialDriveOdometry m_odometry{
+      m_imu.GetRotation2d(), wpi::units::meter_t{m_leftEncoder.GetDistance()},
+      wpi::units::meter_t{m_rightEncoder.GetDistance()}};
 
   // Gains are for example purposes only - must be determined for your own
   // robot!
-  frc::SimpleMotorFeedforward m_feedforward{1_V, 3_V / 1_mps};
+  wpi::math::SimpleMotorFeedforward m_feedforward{1_V, 3_V / 1_mps};
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/cpp/Drivetrain.cpp b/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/cpp/Drivetrain.cpp
index e93771d4a8..a18e8dd08a 100644
--- a/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/cpp/Drivetrain.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/cpp/Drivetrain.cpp
@@ -28,11 +28,11 @@ Drivetrain::Drivetrain() {
   m_leftEncoder.Reset();
   m_rightEncoder.Reset();
 
-  frc::SmartDashboard::PutData("FieldSim", &m_fieldSim);
-  frc::SmartDashboard::PutData("Approximation", &m_fieldApproximation);
+  wpi::SmartDashboard::PutData("FieldSim", &m_fieldSim);
+  wpi::SmartDashboard::PutData("Approximation", &m_fieldApproximation);
 }
 
-void Drivetrain::SetSpeeds(const frc::DifferentialDriveWheelSpeeds& speeds) {
+void Drivetrain::SetSpeeds(const wpi::math::DifferentialDriveWheelSpeeds& speeds) {
   const auto leftFeedforward = m_feedforward.Calculate(speeds.left);
   const auto rightFeedforward = m_feedforward.Calculate(speeds.right);
   const double leftOutput = m_leftPIDController.Calculate(
@@ -40,22 +40,22 @@ void Drivetrain::SetSpeeds(const frc::DifferentialDriveWheelSpeeds& speeds) {
   const double rightOutput = m_rightPIDController.Calculate(
       m_rightEncoder.GetRate(), speeds.right.value());
 
-  m_leftLeader.SetVoltage(units::volt_t{leftOutput} + leftFeedforward);
-  m_rightLeader.SetVoltage(units::volt_t{rightOutput} + rightFeedforward);
+  m_leftLeader.SetVoltage(wpi::units::volt_t{leftOutput} + leftFeedforward);
+  m_rightLeader.SetVoltage(wpi::units::volt_t{rightOutput} + rightFeedforward);
 }
 
-void Drivetrain::Drive(units::meters_per_second_t xSpeed,
-                       units::radians_per_second_t rot) {
+void Drivetrain::Drive(wpi::units::meters_per_second_t xSpeed,
+                       wpi::units::radians_per_second_t rot) {
   SetSpeeds(m_kinematics.ToWheelSpeeds({xSpeed, 0_mps, rot}));
 }
 
 void Drivetrain::PublishCameraToObject(
-    frc::Pose3d objectInField, frc::Transform3d robotToCamera,
-    nt::DoubleArrayEntry& cameraToObjectEntry,
-    frc::sim::DifferentialDrivetrainSim drivetrainSimulator) {
-  frc::Pose3d robotInField{drivetrainSimulator.GetPose()};
-  frc::Pose3d cameraInField = robotInField + robotToCamera;
-  frc::Transform3d cameraToObject{cameraInField, objectInField};
+    wpi::math::Pose3d objectInField, wpi::math::Transform3d robotToCamera,
+    wpi::nt::DoubleArrayEntry& cameraToObjectEntry,
+    wpi::sim::DifferentialDrivetrainSim drivetrainSimulator) {
+  wpi::math::Pose3d robotInField{drivetrainSimulator.GetPose()};
+  wpi::math::Pose3d cameraInField = robotInField + robotToCamera;
+  wpi::math::Transform3d cameraToObject{cameraInField, objectInField};
 
   // Publishes double array with Translation3D elements {x, y, z} and Rotation3D
   // elements {w, x, y, z} which describe the cameraToObject transformation.
@@ -69,24 +69,24 @@ void Drivetrain::PublishCameraToObject(
   cameraToObjectEntry.Set(val);
 }
 
-frc::Pose3d Drivetrain::ObjectToRobotPose(
-    frc::Pose3d objectInField, frc::Transform3d robotToCamera,
-    nt::DoubleArrayEntry& cameraToObjectEntry) {
+wpi::math::Pose3d Drivetrain::ObjectToRobotPose(
+    wpi::math::Pose3d objectInField, wpi::math::Transform3d robotToCamera,
+    wpi::nt::DoubleArrayEntry& cameraToObjectEntry) {
   std::vector val{cameraToObjectEntry.Get()};
 
   // Reconstruct cameraToObject Transform3D from networktables.
-  frc::Translation3d translation{units::meter_t{val[0]}, units::meter_t{val[1]},
-                                 units::meter_t{val[2]}};
-  frc::Rotation3d rotation{frc::Quaternion{val[3], val[4], val[5], val[6]}};
-  frc::Transform3d cameraToObject{translation, rotation};
+  wpi::math::Translation3d translation{wpi::units::meter_t{val[0]}, wpi::units::meter_t{val[1]},
+                                 wpi::units::meter_t{val[2]}};
+  wpi::math::Rotation3d rotation{wpi::math::Quaternion{val[3], val[4], val[5], val[6]}};
+  wpi::math::Transform3d cameraToObject{translation, rotation};
 
-  return frc::ObjectToRobotPose(objectInField, cameraToObject, robotToCamera);
+  return wpi::math::ObjectToRobotPose(objectInField, cameraToObject, robotToCamera);
 }
 
 void Drivetrain::UpdateOdometry() {
   m_poseEstimator.Update(m_imu.GetRotation2d(),
-                         units::meter_t{m_leftEncoder.GetDistance()},
-                         units::meter_t{m_rightEncoder.GetDistance()});
+                         wpi::units::meter_t{m_leftEncoder.GetDistance()},
+                         wpi::units::meter_t{m_rightEncoder.GetDistance()});
 
   // Publish cameraToObject transformation to networktables --this would
   // normally be handled by the computer vision solution.
@@ -95,28 +95,28 @@ void Drivetrain::UpdateOdometry() {
 
   // Compute the robot's field-relative position exclusively from vision
   // measurements.
-  frc::Pose3d visionMeasurement3d = ObjectToRobotPose(
+  wpi::math::Pose3d visionMeasurement3d = ObjectToRobotPose(
       m_objectInField, m_robotToCamera, m_cameraToObjectEntryRef);
 
-  // Convert robot's pose from Pose3d to Pose2d needed to apply vision
+  // Convert robot's pose from wpi::math::Pose3d to wpi::math::Pose2d needed to apply vision
   // measurements.
-  frc::Pose2d visionMeasurement2d = visionMeasurement3d.ToPose2d();
+  wpi::math::Pose2d visionMeasurement2d = visionMeasurement3d.ToPose2d();
 
   // Apply vision measurements. For simulation purposes only, we don't input a
   // latency delay -- on a real robot, this must be calculated based either on
   // known latency or timestamps.
   m_poseEstimator.AddVisionMeasurement(visionMeasurement2d,
-                                       frc::Timer::GetTimestamp());
+                                       wpi::Timer::GetTimestamp());
 }
 
 void Drivetrain::SimulationPeriodic() {
   // To update our simulation, we set motor voltage inputs, update the
   // simulation, and write the simulated positions and velocities to our
   // simulated encoder and gyro.
-  m_drivetrainSimulator.SetInputs(units::volt_t{m_leftLeader.Get()} *
-                                      frc::RobotController::GetInputVoltage(),
-                                  units::volt_t{m_rightLeader.Get()} *
-                                      frc::RobotController::GetInputVoltage());
+  m_drivetrainSimulator.SetInputs(wpi::units::volt_t{m_leftLeader.Get()} *
+                                      wpi::RobotController::GetInputVoltage(),
+                                  wpi::units::volt_t{m_rightLeader.Get()} *
+                                      wpi::RobotController::GetInputVoltage());
   m_drivetrainSimulator.Update(20_ms);
 
   m_leftEncoderSim.SetDistance(m_drivetrainSimulator.GetLeftPosition().value());
diff --git a/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/cpp/Robot.cpp
index a012a7b0e1..18d3b31f4e 100644
--- a/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/cpp/Robot.cpp
@@ -8,7 +8,7 @@
 
 #include "Drivetrain.hpp"
 
-class Robot : public frc::TimedRobot {
+class Robot : public wpi::TimedRobot {
  public:
   void AutonomousPeriodic() override {
     TeleopPeriodic();
@@ -36,18 +36,18 @@ class Robot : public frc::TimedRobot {
   void SimulationPeriodic() override { m_drive.SimulationPeriodic(); }
 
  private:
-  frc::XboxController m_controller{0};
+  wpi::XboxController m_controller{0};
 
   // Slew rate limiters to make joystick inputs more gentle; 1/3 sec from 0
   // to 1.
-  frc::SlewRateLimiter m_speedLimiter{3 / 1_s};
-  frc::SlewRateLimiter m_rotLimiter{3 / 1_s};
+  wpi::math::SlewRateLimiter m_speedLimiter{3 / 1_s};
+  wpi::math::SlewRateLimiter m_rotLimiter{3 / 1_s};
 
   Drivetrain m_drive;
 };
 
 #ifndef RUNNING_FRC_TESTS
 int main() {
-  return frc::StartRobot();
+  return wpi::StartRobot();
 }
 #endif
diff --git a/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/include/Drivetrain.hpp b/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/include/Drivetrain.hpp
index 014a3581ec..5d1453f7db 100644
--- a/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/include/Drivetrain.hpp
+++ b/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/include/Drivetrain.hpp
@@ -41,9 +41,9 @@ class Drivetrain {
  public:
   Drivetrain();
 
-  static constexpr units::meters_per_second_t kMaxSpeed =
+  static constexpr wpi::units::meters_per_second_t kMaxSpeed =
       3.0_mps;  // 3 meters per second
-  static constexpr units::radians_per_second_t kMaxAngularSpeed{
+  static constexpr wpi::units::radians_per_second_t kMaxAngularSpeed{
       std::numbers::pi};  // 1/2 rotation per second
 
   /**
@@ -51,15 +51,15 @@ class Drivetrain {
    *
    * @param speeds The desired wheel speeds.
    */
-  void SetSpeeds(const frc::DifferentialDriveWheelSpeeds& speeds);
+  void SetSpeeds(const wpi::math::DifferentialDriveWheelSpeeds& speeds);
 
   /** Drives the robot with the given linear velocity and angular velocity.
    *
    * @param xSpeed Linear velocity.
    * @param rot Angular Velocity.
    */
-  void Drive(units::meters_per_second_t xSpeed,
-             units::radians_per_second_t rot);
+  void Drive(wpi::units::meters_per_second_t xSpeed,
+             wpi::units::radians_per_second_t rot);
 
   /**
    * Updates the field-relative position.
@@ -90,9 +90,9 @@ class Drivetrain {
    * robot's drivetrain.
    */
   void PublishCameraToObject(
-      frc::Pose3d objectInField, frc::Transform3d robotToCamera,
-      nt::DoubleArrayEntry& cameraToObjectEntry,
-      frc::sim::DifferentialDrivetrainSim drivetrainSimulator);
+      wpi::math::Pose3d objectInField, wpi::math::Transform3d robotToCamera,
+      wpi::nt::DoubleArrayEntry& cameraToObjectEntry,
+      wpi::sim::DifferentialDrivetrainSim drivetrainSimulator);
 
   /**
    * Queries the camera-to-object transformation from networktables to compute
@@ -106,71 +106,71 @@ class Drivetrain {
    * @param cameraToObjectEntry The networktables entry publishing and querying
    * example computer vision measurements.
    */
-  frc::Pose3d ObjectToRobotPose(frc::Pose3d objectInField,
-                                frc::Transform3d robotToCamera,
-                                nt::DoubleArrayEntry& cameraToObjectEntry);
+  wpi::math::Pose3d ObjectToRobotPose(wpi::math::Pose3d objectInField,
+                                wpi::math::Transform3d robotToCamera,
+                                wpi::nt::DoubleArrayEntry& cameraToObjectEntry);
 
  private:
-  static constexpr units::meter_t kTrackwidth = 0.381_m * 2;
-  static constexpr units::meter_t kWheelRadius = 0.0508_m;
+  static constexpr wpi::units::meter_t kTrackwidth = 0.381_m * 2;
+  static constexpr wpi::units::meter_t kWheelRadius = 0.0508_m;
   static constexpr int kEncoderResolution = 4096;
 
   static constexpr std::array kDefaultVal{0.0, 0.0, 0.0, 0.0,
                                                      0.0, 0.0, 0.0};
 
-  frc::Transform3d m_robotToCamera{
-      frc::Translation3d{1_m, 1_m, 1_m},
-      frc::Rotation3d{0_rad, 0_rad, units::radian_t{std::numbers::pi / 2}}};
+  wpi::math::Transform3d m_robotToCamera{
+      wpi::math::Translation3d{1_m, 1_m, 1_m},
+      wpi::math::Rotation3d{0_rad, 0_rad, wpi::units::radian_t{std::numbers::pi / 2}}};
 
-  nt::NetworkTableInstance m_inst{nt::NetworkTableInstance::GetDefault()};
-  nt::DoubleArrayTopic m_cameraToObjectTopic{
+  wpi::nt::NetworkTableInstance m_inst{wpi::nt::NetworkTableInstance::GetDefault()};
+  wpi::nt::DoubleArrayTopic m_cameraToObjectTopic{
       m_inst.GetDoubleArrayTopic("m_cameraToObjectTopic")};
-  nt::DoubleArrayEntry m_cameraToObjectEntry =
+  wpi::nt::DoubleArrayEntry m_cameraToObjectEntry =
       m_cameraToObjectTopic.GetEntry(kDefaultVal);
-  nt::DoubleArrayEntry& m_cameraToObjectEntryRef = m_cameraToObjectEntry;
+  wpi::nt::DoubleArrayEntry& m_cameraToObjectEntryRef = m_cameraToObjectEntry;
 
-  frc::AprilTagFieldLayout m_aprilTagFieldLayout{
-      frc::AprilTagFieldLayout::LoadField(frc::AprilTagField::k2024Crescendo)};
-  frc::Pose3d m_objectInField{m_aprilTagFieldLayout.GetTagPose(0).value()};
+  wpi::apriltag::AprilTagFieldLayout m_aprilTagFieldLayout{
+      wpi::apriltag::AprilTagFieldLayout::LoadField(wpi::apriltag::AprilTagField::k2024Crescendo)};
+  wpi::math::Pose3d m_objectInField{m_aprilTagFieldLayout.GetTagPose(0).value()};
 
-  frc::PWMSparkMax m_leftLeader{1};
-  frc::PWMSparkMax m_leftFollower{2};
-  frc::PWMSparkMax m_rightLeader{3};
-  frc::PWMSparkMax m_rightFollower{4};
+  wpi::PWMSparkMax m_leftLeader{1};
+  wpi::PWMSparkMax m_leftFollower{2};
+  wpi::PWMSparkMax m_rightLeader{3};
+  wpi::PWMSparkMax m_rightFollower{4};
 
-  frc::Encoder m_leftEncoder{0, 1};
-  frc::Encoder m_rightEncoder{2, 3};
+  wpi::Encoder m_leftEncoder{0, 1};
+  wpi::Encoder m_rightEncoder{2, 3};
 
-  frc::PIDController m_leftPIDController{1.0, 0.0, 0.0};
-  frc::PIDController m_rightPIDController{1.0, 0.0, 0.0};
+  wpi::math::PIDController m_leftPIDController{1.0, 0.0, 0.0};
+  wpi::math::PIDController m_rightPIDController{1.0, 0.0, 0.0};
 
-  frc::OnboardIMU m_imu{frc::OnboardIMU::kFlat};
+  wpi::OnboardIMU m_imu{wpi::OnboardIMU::kFlat};
 
-  frc::DifferentialDriveKinematics m_kinematics{kTrackwidth};
+  wpi::math::DifferentialDriveKinematics m_kinematics{kTrackwidth};
 
   // Gains are for example purposes only - must be determined for your own
   // robot!
-  frc::DifferentialDrivePoseEstimator m_poseEstimator{
+  wpi::math::DifferentialDrivePoseEstimator m_poseEstimator{
       m_kinematics,
       m_imu.GetRotation2d(),
-      units::meter_t{m_leftEncoder.GetDistance()},
-      units::meter_t{m_rightEncoder.GetDistance()},
-      frc::Pose2d{},
+      wpi::units::meter_t{m_leftEncoder.GetDistance()},
+      wpi::units::meter_t{m_rightEncoder.GetDistance()},
+      wpi::math::Pose2d{},
       {0.01, 0.01, 0.01},
       {0.1, 0.1, 0.1}};
 
   // Gains are for example purposes only - must be determined for your own
   // robot!
-  frc::SimpleMotorFeedforward m_feedforward{1_V, 3_V / 1_mps};
+  wpi::math::SimpleMotorFeedforward m_feedforward{1_V, 3_V / 1_mps};
 
   // Simulation classes
-  frc::sim::EncoderSim m_leftEncoderSim{m_leftEncoder};
-  frc::sim::EncoderSim m_rightEncoderSim{m_rightEncoder};
-  frc::Field2d m_fieldSim;
-  frc::Field2d m_fieldApproximation;
-  frc::LinearSystem<2, 2, 2> m_drivetrainSystem =
-      frc::LinearSystemId::IdentifyDrivetrainSystem(
+  wpi::sim::EncoderSim m_leftEncoderSim{m_leftEncoder};
+  wpi::sim::EncoderSim m_rightEncoderSim{m_rightEncoder};
+  wpi::Field2d m_fieldSim;
+  wpi::Field2d m_fieldApproximation;
+  wpi::math::LinearSystem<2, 2, 2> m_drivetrainSystem =
+      wpi::math::LinearSystemId::IdentifyDrivetrainSystem(
           1.98_V / 1_mps, 0.2_V / 1_mps_sq, 1.5_V / 1_mps, 0.3_V / 1_mps_sq);
-  frc::sim::DifferentialDrivetrainSim m_drivetrainSimulator{
-      m_drivetrainSystem, kTrackwidth, frc::DCMotor::CIM(2), 8, 2_in};
+  wpi::sim::DifferentialDrivetrainSim m_drivetrainSimulator{
+      m_drivetrainSystem, kTrackwidth, wpi::math::DCMotor::CIM(2), 8, 2_in};
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/include/ExampleGlobalMeasurementSensor.hpp b/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/include/ExampleGlobalMeasurementSensor.hpp
index d4f9b4e52f..16f4123f08 100644
--- a/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/include/ExampleGlobalMeasurementSensor.hpp
+++ b/wpilibcExamples/src/main/cpp/examples/DifferentialDrivePoseEstimator/include/ExampleGlobalMeasurementSensor.hpp
@@ -13,12 +13,12 @@
  */
 class ExampleGlobalMeasurementSensor {
  public:
-  static frc::Pose2d GetEstimatedGlobalPose(
-      const frc::Pose2d& estimatedRobotPose) {
-    auto randVec = frc::MakeWhiteNoiseVector(0.1, 0.1, 0.1);
-    return frc::Pose2d{estimatedRobotPose.X() + units::meter_t{randVec(0)},
-                       estimatedRobotPose.Y() + units::meter_t{randVec(1)},
+  static wpi::math::Pose2d GetEstimatedGlobalPose(
+      const wpi::math::Pose2d& estimatedRobotPose) {
+    auto randVec = wpi::math::MakeWhiteNoiseVector(0.1, 0.1, 0.1);
+    return wpi::math::Pose2d{estimatedRobotPose.X() + wpi::units::meter_t{randVec(0)},
+                       estimatedRobotPose.Y() + wpi::units::meter_t{randVec(1)},
                        estimatedRobotPose.Rotation() +
-                           frc::Rotation2d{units::radian_t{randVec(2)}}};
+                           wpi::math::Rotation2d{wpi::units::radian_t{randVec(2)}}};
   }
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/DigitalCommunication/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/DigitalCommunication/cpp/Robot.cpp
index 3cd22ea1b3..719104caa2 100644
--- a/wpilibcExamples/src/main/cpp/examples/DigitalCommunication/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/DigitalCommunication/cpp/Robot.cpp
@@ -8,22 +8,22 @@
 
 void Robot::RobotPeriodic() {
   // pull alliance port high if on red alliance, pull low if on blue alliance
-  m_allianceOutput.Set(frc::DriverStation::GetAlliance() ==
-                       frc::DriverStation::kRed);
+  m_allianceOutput.Set(wpi::DriverStation::GetAlliance() ==
+                       wpi::DriverStation::kRed);
 
   // pull enabled port high if enabled, low if disabled
-  m_enabledOutput.Set(frc::DriverStation::IsEnabled());
+  m_enabledOutput.Set(wpi::DriverStation::IsEnabled());
 
   // pull auto port high if in autonomous, low if in teleop (or disabled)
-  m_autonomousOutput.Set(frc::DriverStation::IsAutonomous());
+  m_autonomousOutput.Set(wpi::DriverStation::IsAutonomous());
 
   // pull alert port high if match time remaining is between 30 and 25 seconds
-  auto matchTime = frc::DriverStation::GetMatchTime();
+  auto matchTime = wpi::DriverStation::GetMatchTime();
   m_alertOutput.Set(matchTime <= 30_s && matchTime >= 25_s);
 }
 
 #ifndef RUNNING_FRC_TESTS
 int main() {
-  return frc::StartRobot();
+  return wpi::StartRobot();
 }
 #endif
diff --git a/wpilibcExamples/src/main/cpp/examples/DigitalCommunication/include/Robot.hpp b/wpilibcExamples/src/main/cpp/examples/DigitalCommunication/include/Robot.hpp
index ec24e1f048..70c95bffa2 100644
--- a/wpilibcExamples/src/main/cpp/examples/DigitalCommunication/include/Robot.hpp
+++ b/wpilibcExamples/src/main/cpp/examples/DigitalCommunication/include/Robot.hpp
@@ -13,7 +13,7 @@
  * This is a sample program demonstrating how to communicate to a light
  * controller from the robot code using the roboRIO's DIO ports.
  */
-class Robot : public frc::TimedRobot {
+class Robot : public wpi::TimedRobot {
  public:
   // define ports for communication with light controller
   static constexpr int kAlliancePort = 0;
@@ -24,8 +24,8 @@ class Robot : public frc::TimedRobot {
   void RobotPeriodic() override;
 
  private:
-  frc::DigitalOutput m_allianceOutput{kAlliancePort};
-  frc::DigitalOutput m_enabledOutput{kEnabledPort};
-  frc::DigitalOutput m_autonomousOutput{kAutonomousPort};
-  frc::DigitalOutput m_alertOutput{kAlertPort};
+  wpi::DigitalOutput m_allianceOutput{kAlliancePort};
+  wpi::DigitalOutput m_enabledOutput{kEnabledPort};
+  wpi::DigitalOutput m_autonomousOutput{kAutonomousPort};
+  wpi::DigitalOutput m_alertOutput{kAlertPort};
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/Robot.cpp
index de43981c60..1b76bdb73d 100644
--- a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/Robot.cpp
@@ -18,7 +18,7 @@ Robot::Robot() {}
  * LiveWindow and SmartDashboard integrated updating.
  */
 void Robot::RobotPeriodic() {
-  frc2::CommandScheduler::GetInstance().Run();
+  wpi::cmd::CommandScheduler::GetInstance().Run();
 }
 
 /**
@@ -38,7 +38,7 @@ void Robot::AutonomousInit() {
   m_autonomousCommand = m_container.GetAutonomousCommand();
 
   if (m_autonomousCommand) {
-    frc2::CommandScheduler::GetInstance().Schedule(m_autonomousCommand.value());
+    wpi::cmd::CommandScheduler::GetInstance().Schedule(m_autonomousCommand.value());
   }
 }
 
@@ -67,6 +67,6 @@ void Robot::TestPeriodic() {}
 
 #ifndef RUNNING_FRC_TESTS
 int main() {
-  return frc::StartRobot();
+  return wpi::StartRobot();
 }
 #endif
diff --git a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/RobotContainer.cpp b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/RobotContainer.cpp
index b3c825e314..87502b1437 100644
--- a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/RobotContainer.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/RobotContainer.cpp
@@ -13,7 +13,7 @@ RobotContainer::RobotContainer() {
   ConfigureButtonBindings();
 
   // Set up default drive command
-  m_drive.SetDefaultCommand(frc2::cmd::Run(
+  m_drive.SetDefaultCommand(wpi::cmd::cmd::Run(
       [this] {
         m_drive.ArcadeDrive(-m_driverController.GetLeftY(),
                             -m_driverController.GetRightX());
@@ -40,7 +40,7 @@ void RobotContainer::ConfigureButtonBindings() {
       m_drive.DynamicProfiledDriveDistance(3_m).WithTimeout(10_s));
 }
 
-frc2::CommandPtr RobotContainer::GetAutonomousCommand() {
+wpi::cmd::CommandPtr RobotContainer::GetAutonomousCommand() {
   // Runs the chosen command in autonomous
-  return frc2::cmd::None();
+  return wpi::cmd::cmd::None();
 }
diff --git a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/subsystems/DriveSubsystem.cpp b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/subsystems/DriveSubsystem.cpp
index e19392b09d..7d10603054 100644
--- a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/subsystems/DriveSubsystem.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/cpp/subsystems/DriveSubsystem.cpp
@@ -14,8 +14,8 @@ DriveSubsystem::DriveSubsystem()
       m_rightLeader{kRightMotor1Port},
       m_rightFollower{kRightMotor2Port},
       m_feedforward{ks, kv, ka} {
-  wpi::SendableRegistry::AddChild(&m_drive, &m_leftLeader);
-  wpi::SendableRegistry::AddChild(&m_drive, &m_rightLeader);
+  wpi::util::SendableRegistry::AddChild(&m_drive, &m_leftLeader);
+  wpi::util::SendableRegistry::AddChild(&m_drive, &m_rightLeader);
 
   // We need to invert one side of the drivetrain so that positive voltages
   // result in both sides moving forward. Depending on how your robot's
@@ -34,21 +34,21 @@ void DriveSubsystem::Periodic() {
 }
 
 void DriveSubsystem::SetDriveStates(
-    frc::TrapezoidProfile::State currentLeft,
-    frc::TrapezoidProfile::State currentRight,
-    frc::TrapezoidProfile::State nextLeft,
-    frc::TrapezoidProfile::State nextRight) {
+    wpi::math::TrapezoidProfile::State currentLeft,
+    wpi::math::TrapezoidProfile::State currentRight,
+    wpi::math::TrapezoidProfile::State nextLeft,
+    wpi::math::TrapezoidProfile::State nextRight) {
   // Feedforward is divided by battery voltage to normalize it to [-1, 1]
   m_leftLeader.SetSetpoint(
       ExampleSmartMotorController::PIDMode::kPosition,
       currentLeft.position.value(),
       m_feedforward.Calculate(currentLeft.velocity, nextLeft.velocity) /
-          frc::RobotController::GetBatteryVoltage());
+          wpi::RobotController::GetBatteryVoltage());
   m_rightLeader.SetSetpoint(
       ExampleSmartMotorController::PIDMode::kPosition,
       currentRight.position.value(),
       m_feedforward.Calculate(currentRight.velocity, nextRight.velocity) /
-          frc::RobotController::GetBatteryVoltage());
+          wpi::RobotController::GetBatteryVoltage());
 }
 
 void DriveSubsystem::ArcadeDrive(double fwd, double rot) {
@@ -60,20 +60,20 @@ void DriveSubsystem::ResetEncoders() {
   m_rightLeader.ResetEncoder();
 }
 
-units::meter_t DriveSubsystem::GetLeftEncoderDistance() {
-  return units::meter_t{m_leftLeader.GetEncoderDistance()};
+wpi::units::meter_t DriveSubsystem::GetLeftEncoderDistance() {
+  return wpi::units::meter_t{m_leftLeader.GetEncoderDistance()};
 }
 
-units::meter_t DriveSubsystem::GetRightEncoderDistance() {
-  return units::meter_t{m_rightLeader.GetEncoderDistance()};
+wpi::units::meter_t DriveSubsystem::GetRightEncoderDistance() {
+  return wpi::units::meter_t{m_rightLeader.GetEncoderDistance()};
 }
 
 void DriveSubsystem::SetMaxOutput(double maxOutput) {
   m_drive.SetMaxOutput(maxOutput);
 }
 
-frc2::CommandPtr DriveSubsystem::ProfiledDriveDistance(
-    units::meter_t distance) {
+wpi::cmd::CommandPtr DriveSubsystem::ProfiledDriveDistance(
+    wpi::units::meter_t distance) {
   return StartRun(
              [&] {
                // Restart timer so profile setpoints start at the beginning
@@ -94,8 +94,8 @@ frc2::CommandPtr DriveSubsystem::ProfiledDriveDistance(
       .Until([&] { return m_profile.IsFinished(0_s); });
 }
 
-frc2::CommandPtr DriveSubsystem::DynamicProfiledDriveDistance(
-    units::meter_t distance) {
+wpi::cmd::CommandPtr DriveSubsystem::DynamicProfiledDriveDistance(
+    wpi::units::meter_t distance) {
   return StartRun(
              [&] {
                // Restart timer so profile setpoints start at the beginning
diff --git a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/Constants.hpp b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/Constants.hpp
index 81e325f9ca..503a97b73a 100644
--- a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/Constants.hpp
+++ b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/Constants.hpp
@@ -22,7 +22,7 @@
  */
 
 namespace DriveConstants {
-inline constexpr units::second_t kDt{0.02};
+inline constexpr wpi::units::second_t kDt{0.02};
 inline constexpr int kLeftMotor1Port = 0;
 inline constexpr int kLeftMotor2Port = 1;
 inline constexpr int kRightMotor1Port = 2;
diff --git a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/Robot.hpp b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/Robot.hpp
index ef3760deda..b49f882eb4 100644
--- a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/Robot.hpp
+++ b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/Robot.hpp
@@ -11,7 +11,7 @@
 
 #include "RobotContainer.hpp"
 
-class Robot : public frc::TimedRobot {
+class Robot : public wpi::TimedRobot {
  public:
   Robot();
   void RobotPeriodic() override;
@@ -26,7 +26,7 @@ class Robot : public frc::TimedRobot {
  private:
   // Have it null by default so that if testing teleop it
   // doesn't have undefined behavior and potentially crash.
-  std::optional m_autonomousCommand;
+  std::optional m_autonomousCommand;
 
   RobotContainer m_container;
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/RobotContainer.hpp b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/RobotContainer.hpp
index 9aed0824ef..265366f67c 100644
--- a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/RobotContainer.hpp
+++ b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/RobotContainer.hpp
@@ -23,11 +23,11 @@ class RobotContainer {
  public:
   RobotContainer();
 
-  frc2::CommandPtr GetAutonomousCommand();
+  wpi::cmd::CommandPtr GetAutonomousCommand();
 
  private:
   // The driver's controller
-  frc2::CommandXboxController m_driverController{
+  wpi::cmd::CommandXboxController m_driverController{
       OIConstants::kDriverControllerPort};
 
   // The robot's subsystems and commands are defined here...
@@ -36,10 +36,10 @@ class RobotContainer {
   DriveSubsystem m_drive;
 
   // RobotContainer-owned commands
-  frc2::CommandPtr m_driveHalfSpeed =
-      frc2::cmd::RunOnce([this] { m_drive.SetMaxOutput(0.5); }, {});
-  frc2::CommandPtr m_driveFullSpeed =
-      frc2::cmd::RunOnce([this] { m_drive.SetMaxOutput(1); }, {});
+  wpi::cmd::CommandPtr m_driveHalfSpeed =
+      wpi::cmd::cmd::RunOnce([this] { m_drive.SetMaxOutput(0.5); }, {});
+  wpi::cmd::CommandPtr m_driveFullSpeed =
+      wpi::cmd::cmd::RunOnce([this] { m_drive.SetMaxOutput(1); }, {});
 
   void ConfigureButtonBindings();
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/subsystems/DriveSubsystem.hpp b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/subsystems/DriveSubsystem.hpp
index 612b16a1bd..cb0b2e31ca 100644
--- a/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/subsystems/DriveSubsystem.hpp
+++ b/wpilibcExamples/src/main/cpp/examples/DriveDistanceOffboard/include/subsystems/DriveSubsystem.hpp
@@ -16,7 +16,7 @@
 #include "Constants.hpp"
 #include "ExampleSmartMotorController.hpp"
 
-class DriveSubsystem : public frc2::SubsystemBase {
+class DriveSubsystem : public wpi::cmd::SubsystemBase {
  public:
   DriveSubsystem();
 
@@ -35,10 +35,10 @@ class DriveSubsystem : public frc2::SubsystemBase {
    * @param nextLeft The next left wheel state.
    * @param nextRight The next right wheel state.
    */
-  void SetDriveStates(frc::TrapezoidProfile::State currentLeft,
-                      frc::TrapezoidProfile::State currentRight,
-                      frc::TrapezoidProfile::State nextLeft,
-                      frc::TrapezoidProfile::State nextRight);
+  void SetDriveStates(wpi::math::TrapezoidProfile::State currentLeft,
+                      wpi::math::TrapezoidProfile::State currentRight,
+                      wpi::math::TrapezoidProfile::State nextLeft,
+                      wpi::math::TrapezoidProfile::State nextRight);
 
   /**
    * Drives the robot using arcade controls.
@@ -58,14 +58,14 @@ class DriveSubsystem : public frc2::SubsystemBase {
    *
    * @return the average of the TWO encoder readings
    */
-  units::meter_t GetLeftEncoderDistance();
+  wpi::units::meter_t GetLeftEncoderDistance();
 
   /**
    * Gets the distance of the right encoder.
    *
    * @return the average of the TWO encoder readings
    */
-  units::meter_t GetRightEncoderDistance();
+  wpi::units::meter_t GetRightEncoderDistance();
 
   /**
    * Sets the max output of the drive.  Useful for scaling the drive to drive
@@ -82,7 +82,7 @@ class DriveSubsystem : public frc2::SubsystemBase {
    * @param distance The distance to drive forward.
    * @return A command.
    */
-  frc2::CommandPtr ProfiledDriveDistance(units::meter_t distance);
+  wpi::cmd::CommandPtr ProfiledDriveDistance(wpi::units::meter_t distance);
 
   /**
    * Creates a command to drive forward a specified distance using a motion
@@ -91,14 +91,14 @@ class DriveSubsystem : public frc2::SubsystemBase {
    * @param distance The distance to drive forward.
    * @return A command.
    */
-  frc2::CommandPtr DynamicProfiledDriveDistance(units::meter_t distance);
+  wpi::cmd::CommandPtr DynamicProfiledDriveDistance(wpi::units::meter_t distance);
 
  private:
-  frc::TrapezoidProfile m_profile{
+  wpi::math::TrapezoidProfile m_profile{
       {DriveConstants::kMaxSpeed, DriveConstants::kMaxAcceleration}};
-  frc::Timer m_timer;
-  units::meter_t m_initialLeftDistance;
-  units::meter_t m_initialRightDistance;
+  wpi::Timer m_timer;
+  wpi::units::meter_t m_initialLeftDistance;
+  wpi::units::meter_t m_initialRightDistance;
   // Components (e.g. motor controllers and sensors) should generally be
   // declared private and exposed only through public methods.
 
@@ -109,10 +109,10 @@ class DriveSubsystem : public frc2::SubsystemBase {
   ExampleSmartMotorController m_rightFollower;
 
   // A feedforward component for the drive
-  frc::SimpleMotorFeedforward m_feedforward;
+  wpi::math::SimpleMotorFeedforward m_feedforward;
 
   // The robot's drive
-  frc::DifferentialDrive m_drive{
+  wpi::DifferentialDrive m_drive{
       [&](double output) { m_leftLeader.Set(output); },
       [&](double output) { m_rightLeader.Set(output); }};
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/DutyCycleEncoder/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/DutyCycleEncoder/cpp/Robot.cpp
index 49fbd3c3ab..eee460eb5f 100644
--- a/wpilibcExamples/src/main/cpp/examples/DutyCycleEncoder/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/DutyCycleEncoder/cpp/Robot.cpp
@@ -10,14 +10,14 @@
 constexpr double fullRange = 1.3;
 constexpr double expectedZero = 0.0;
 
-class Robot : public frc::TimedRobot {
+class Robot : public wpi::TimedRobot {
   // 2nd parameter is the range of values. This sensor will output between
   // 0 and the passed in value.
   // 3rd parameter is the the physical value where you want "0" to be. How
   // to measure this is fairly easy. Set the value to 0, place the mechanism
   // where you want "0" to be, and observe the value on the dashboard, That
   // is the value to enter for the 3rd parameter.
-  frc::DutyCycleEncoder m_dutyCycleEncoder{0, fullRange, expectedZero};
+  wpi::DutyCycleEncoder m_dutyCycleEncoder{0, fullRange, expectedZero};
 
  public:
   Robot() {
@@ -56,18 +56,18 @@ class Robot : public frc::TimedRobot {
     // This does not change where "0" is, so no calibration numbers need
     // to be changed.
     double percentOfRange = fullRange * 0.1;
-    double shiftedOutput = frc::InputModulus(output, 0 - percentOfRange,
+    double shiftedOutput = wpi::math::InputModulus(output, 0 - percentOfRange,
                                              fullRange - percentOfRange);
 
-    frc::SmartDashboard::PutBoolean("Connected", connected);
-    frc::SmartDashboard::PutNumber("Frequency", frequency.value());
-    frc::SmartDashboard::PutNumber("Output", output);
-    frc::SmartDashboard::PutNumber("ShiftedOutput", shiftedOutput);
+    wpi::SmartDashboard::PutBoolean("Connected", connected);
+    wpi::SmartDashboard::PutNumber("Frequency", frequency.value());
+    wpi::SmartDashboard::PutNumber("Output", output);
+    wpi::SmartDashboard::PutNumber("ShiftedOutput", shiftedOutput);
   }
 };
 
 #ifndef RUNNING_FRC_TESTS
 int main() {
-  return frc::StartRobot();
+  return wpi::StartRobot();
 }
 #endif
diff --git a/wpilibcExamples/src/main/cpp/examples/DutyCycleInput/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/DutyCycleInput/cpp/Robot.cpp
index 371e54a309..1faee99457 100644
--- a/wpilibcExamples/src/main/cpp/examples/DutyCycleInput/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/DutyCycleInput/cpp/Robot.cpp
@@ -7,8 +7,8 @@
 #include 
 #include 
 
-class Robot : public frc::TimedRobot {
-  frc::DutyCycle m_dutyCycle{0};  // Duty cycle input
+class Robot : public wpi::TimedRobot {
+  wpi::DutyCycle m_dutyCycle{0};  // Duty cycle input
 
  public:
   Robot() {}
@@ -21,13 +21,13 @@ class Robot : public frc::TimedRobot {
     // 1 is fully on, 0 is fully off
     auto output = m_dutyCycle.GetOutput();
 
-    frc::SmartDashboard::PutNumber("Frequency", frequency.value());
-    frc::SmartDashboard::PutNumber("Duty Cycle", output);
+    wpi::SmartDashboard::PutNumber("Frequency", frequency.value());
+    wpi::SmartDashboard::PutNumber("Duty Cycle", output);
   }
 };
 
 #ifndef RUNNING_FRC_TESTS
 int main() {
-  return frc::StartRobot();
+  return wpi::StartRobot();
 }
 #endif
diff --git a/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialProfile/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialProfile/cpp/Robot.cpp
index f7c9b35b53..6479442f82 100644
--- a/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialProfile/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialProfile/cpp/Robot.cpp
@@ -16,9 +16,9 @@
 
 #include "ExampleSmartMotorController.hpp"
 
-class Robot : public frc::TimedRobot {
+class Robot : public wpi::TimedRobot {
  public:
-  static constexpr units::second_t kDt = 20_ms;
+  static constexpr wpi::units::second_t kDt = 20_ms;
 
   Robot() {
     // Note: These gains are fake, and will have to be tuned for your robot.
@@ -46,22 +46,22 @@ class Robot : public frc::TimedRobot {
   }
 
  private:
-  frc::Joystick m_joystick{1};
+  wpi::Joystick m_joystick{1};
   ExampleSmartMotorController m_motor{1};
-  frc::SimpleMotorFeedforward m_feedforward{
+  wpi::math::SimpleMotorFeedforward m_feedforward{
       // Note: These gains are fake, and will have to be tuned for your robot.
       1_V, 1_V / 1_mps, 1_V / 1_mps_sq};
 
   // Create a motion profile with the given maximum velocity and maximum
   // acceleration constraints for the next setpoint.
-  frc::ExponentialProfile m_profile{
+  wpi::math::ExponentialProfile m_profile{
       {10_V, 1_V / 1_mps, 1_V / 1_mps_sq}};
-  frc::ExponentialProfile::State m_goal;
-  frc::ExponentialProfile::State m_setpoint;
+  wpi::math::ExponentialProfile::State m_goal;
+  wpi::math::ExponentialProfile::State m_setpoint;
 };
 
 #ifndef RUNNING_FRC_TESTS
 int main() {
-  return frc::StartRobot();
+  return wpi::StartRobot();
 }
 #endif
diff --git a/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialSimulation/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialSimulation/cpp/Robot.cpp
index eb74029829..82c64241d0 100644
--- a/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialSimulation/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialSimulation/cpp/Robot.cpp
@@ -39,6 +39,6 @@ void Robot::DisabledInit() {
 
 #ifndef RUNNING_FRC_TESTS
 int main() {
-  return frc::StartRobot();
+  return wpi::StartRobot();
 }
 #endif
diff --git a/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialSimulation/cpp/subsystems/Elevator.cpp b/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialSimulation/cpp/subsystems/Elevator.cpp
index f727f5591f..a9d785fb9c 100644
--- a/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialSimulation/cpp/subsystems/Elevator.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialSimulation/cpp/subsystems/Elevator.cpp
@@ -14,14 +14,14 @@ Elevator::Elevator() {
   // Put Mechanism 2d to SmartDashboard
   // To view the Elevator visualization, select Network Tables -> SmartDashboard
   // -> Elevator Sim
-  frc::SmartDashboard::PutData("Elevator Sim", &m_mech2d);
+  wpi::SmartDashboard::PutData("Elevator Sim", &m_mech2d);
 }
 
 void Elevator::SimulationPeriodic() {
   // In this method, we update our simulation of what our elevator is doing
   // First, we set our "inputs" (voltages)
-  m_elevatorSim.SetInput(frc::Vectord<1>{
-      m_motorSim.GetSpeed() * frc::RobotController::GetInputVoltage()});
+  m_elevatorSim.SetInput(wpi::math::Vectord<1>{
+      m_motorSim.GetSpeed() * wpi::RobotController::GetInputVoltage()});
 
   // Next, we update it. The standard loop time is 20ms.
   m_elevatorSim.Update(20_ms);
@@ -30,8 +30,8 @@ void Elevator::SimulationPeriodic() {
   // voltage
   m_encoderSim.SetDistance(m_elevatorSim.GetPosition().value());
   // SimBattery estimates loaded battery voltages
-  frc::sim::RoboRioSim::SetVInVoltage(
-      frc::sim::BatterySim::Calculate({m_elevatorSim.GetCurrentDraw()}));
+  wpi::sim::RoboRioSim::SetVInVoltage(
+      wpi::sim::BatterySim::Calculate({m_elevatorSim.GetCurrentDraw()}));
 }
 
 void Elevator::UpdateTelemetry() {
@@ -39,8 +39,8 @@ void Elevator::UpdateTelemetry() {
   m_elevatorMech2d->SetLength(m_encoder.GetDistance());
 }
 
-void Elevator::ReachGoal(units::meter_t goal) {
-  frc::ExponentialProfile::State goalState{goal,
+void Elevator::ReachGoal(wpi::units::meter_t goal) {
+  wpi::math::ExponentialProfile::State goalState{goal,
                                                                         0_mps};
 
   auto next = m_profile.Calculate(20_ms, m_setpoint, goalState);
@@ -50,7 +50,7 @@ void Elevator::ReachGoal(units::meter_t goal) {
   auto feedforwardOutput =
       m_feedforward.Calculate(m_setpoint.velocity, next.velocity);
 
-  m_motor.SetVoltage(units::volt_t{pidOutput} + feedforwardOutput);
+  m_motor.SetVoltage(wpi::units::volt_t{pidOutput} + feedforwardOutput);
 
   m_setpoint = next;
 }
diff --git a/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialSimulation/include/Constants.hpp b/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialSimulation/include/Constants.hpp
index a3c97c7866..9a5e38658d 100644
--- a/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialSimulation/include/Constants.hpp
+++ b/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialSimulation/include/Constants.hpp
@@ -34,20 +34,20 @@ inline constexpr double kElevatorKp = 0.75;
 inline constexpr double kElevatorKi = 0.0;
 inline constexpr double kElevatorKd = 0.0;
 
-inline constexpr units::volt_t kElevatorMaxV = 10_V;
-inline constexpr units::volt_t kElevatorkS = 0.0_V;
-inline constexpr units::volt_t kElevatorkG = 0.62_V;
+inline constexpr wpi::units::volt_t kElevatorMaxV = 10_V;
+inline constexpr wpi::units::volt_t kElevatorkS = 0.0_V;
+inline constexpr wpi::units::volt_t kElevatorkG = 0.62_V;
 inline constexpr auto kElevatorkV = 3.9_V / 1_mps;
 inline constexpr auto kElevatorkA = 0.06_V / 1_mps_sq;
 
 inline constexpr double kElevatorGearing = 5.0;
-inline constexpr units::meter_t kElevatorDrumRadius = 1_in;
-inline constexpr units::kilogram_t kCarriageMass = 12_lb;
+inline constexpr wpi::units::meter_t kElevatorDrumRadius = 1_in;
+inline constexpr wpi::units::kilogram_t kCarriageMass = 12_lb;
 
-inline constexpr units::meter_t kSetpoint = 42.875_in;
-inline constexpr units::meter_t kLowerSetpoint = 15_in;
-inline constexpr units::meter_t kMinElevatorHeight = 0_cm;
-inline constexpr units::meter_t kMaxElevatorHeight = 50_in;
+inline constexpr wpi::units::meter_t kSetpoint = 42.875_in;
+inline constexpr wpi::units::meter_t kLowerSetpoint = 15_in;
+inline constexpr wpi::units::meter_t kMinElevatorHeight = 0_cm;
+inline constexpr wpi::units::meter_t kMaxElevatorHeight = 50_in;
 
 // distance per pulse = (distance per revolution) / (pulses per revolution)
 //  = (Pi * D) / ppr
diff --git a/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialSimulation/include/Robot.hpp b/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialSimulation/include/Robot.hpp
index ec33857b69..34f0c6a84b 100644
--- a/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialSimulation/include/Robot.hpp
+++ b/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialSimulation/include/Robot.hpp
@@ -12,7 +12,7 @@
 /**
  * This is a sample program to demonstrate the use of elevator simulation.
  */
-class Robot : public frc::TimedRobot {
+class Robot : public wpi::TimedRobot {
  public:
   Robot() {}
   void RobotPeriodic() override;
@@ -22,6 +22,6 @@ class Robot : public frc::TimedRobot {
   void DisabledInit() override;
 
  private:
-  frc::Joystick m_joystick{Constants::kJoystickPort};
+  wpi::Joystick m_joystick{Constants::kJoystickPort};
   Elevator m_elevator;
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialSimulation/include/subsystems/Elevator.hpp b/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialSimulation/include/subsystems/Elevator.hpp
index 8b040e913b..db2869077e 100644
--- a/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialSimulation/include/subsystems/Elevator.hpp
+++ b/wpilibcExamples/src/main/cpp/examples/ElevatorExponentialSimulation/include/subsystems/Elevator.hpp
@@ -26,34 +26,34 @@ class Elevator {
   Elevator();
   void SimulationPeriodic();
   void UpdateTelemetry();
-  void ReachGoal(units::meter_t goal);
+  void ReachGoal(wpi::units::meter_t goal);
   void Reset();
   void Stop();
 
  private:
   // This gearbox represents a gearbox containing 4 Vex 775pro motors.
-  frc::DCMotor m_elevatorGearbox = frc::DCMotor::NEO(2);
+  wpi::math::DCMotor m_elevatorGearbox = wpi::math::DCMotor::NEO(2);
 
   // Standard classes for controlling our elevator
-  frc::ExponentialProfile::Constraints
+  wpi::math::ExponentialProfile::Constraints
       m_constraints{Constants::kElevatorMaxV, Constants::kElevatorkV,
                     Constants::kElevatorkA};
-  frc::ExponentialProfile m_profile{m_constraints};
-  frc::ExponentialProfile::State m_setpoint;
+  wpi::math::ExponentialProfile m_profile{m_constraints};
+  wpi::math::ExponentialProfile::State m_setpoint;
 
-  frc::PIDController m_controller{
+  wpi::math::PIDController m_controller{
       Constants::kElevatorKp, Constants::kElevatorKi, Constants::kElevatorKd};
 
-  frc::ElevatorFeedforward m_feedforward{
+  wpi::math::ElevatorFeedforward m_feedforward{
       Constants::kElevatorkS, Constants::kElevatorkG, Constants::kElevatorkV,
       Constants::kElevatorkA};
-  frc::Encoder m_encoder{Constants::kEncoderAChannel,
+  wpi::Encoder m_encoder{Constants::kEncoderAChannel,
                          Constants::kEncoderBChannel};
-  frc::PWMSparkMax m_motor{Constants::kMotorPort};
-  frc::sim::PWMMotorControllerSim m_motorSim{m_motor};
+  wpi::PWMSparkMax m_motor{Constants::kMotorPort};
+  wpi::sim::PWMMotorControllerSim m_motorSim{m_motor};
 
   // Simulation classes help us simulate what's going on, including gravity.
-  frc::sim::ElevatorSim m_elevatorSim{m_elevatorGearbox,
+  wpi::sim::ElevatorSim m_elevatorSim{m_elevatorGearbox,
                                       Constants::kElevatorGearing,
                                       Constants::kCarriageMass,
                                       Constants::kElevatorDrumRadius,
@@ -62,13 +62,13 @@ class Elevator {
                                       true,
                                       0_m,
                                       {0.005}};
-  frc::sim::EncoderSim m_encoderSim{m_encoder};
+  wpi::sim::EncoderSim m_encoderSim{m_encoder};
 
   // Create a Mechanism2d display of an elevator
-  frc::Mechanism2d m_mech2d{10_in / 1_m, 51_in / 1_m};
-  frc::MechanismRoot2d* m_elevatorRoot =
+  wpi::Mechanism2d m_mech2d{10_in / 1_m, 51_in / 1_m};
+  wpi::MechanismRoot2d* m_elevatorRoot =
       m_mech2d.GetRoot("Elevator Root", 5_in / 1_m, 0.5_in / 1_m);
-  frc::MechanismLigament2d* m_elevatorMech2d =
-      m_elevatorRoot->Append(
+  wpi::MechanismLigament2d* m_elevatorMech2d =
+      m_elevatorRoot->Append(
           "Elevator", m_elevatorSim.GetPosition().value(), 90_deg);
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/ElevatorProfiledPID/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ElevatorProfiledPID/cpp/Robot.cpp
index d4da52a748..58af891b13 100644
--- a/wpilibcExamples/src/main/cpp/examples/ElevatorProfiledPID/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/ElevatorProfiledPID/cpp/Robot.cpp
@@ -17,9 +17,9 @@
 #include 
 #include 
 
-class Robot : public frc::TimedRobot {
+class Robot : public wpi::TimedRobot {
  public:
-  static constexpr units::second_t kDt = 20_ms;
+  static constexpr wpi::units::second_t kDt = 20_ms;
 
   Robot() {
     m_encoder.SetDistancePerPulse(1.0 / 360.0 * 2.0 * std::numbers::pi * 1.5);
@@ -34,37 +34,37 @@ class Robot : public frc::TimedRobot {
 
     // Run controller and update motor output
     m_motor.SetVoltage(
-        units::volt_t{
-            m_controller.Calculate(units::meter_t{m_encoder.GetDistance()})} +
+        wpi::units::volt_t{
+            m_controller.Calculate(wpi::units::meter_t{m_encoder.GetDistance()})} +
         m_feedforward.Calculate(m_controller.GetSetpoint().velocity));
   }
 
  private:
-  static constexpr units::meters_per_second_t kMaxVelocity = 1.75_mps;
-  static constexpr units::meters_per_second_squared_t kMaxAcceleration =
+  static constexpr wpi::units::meters_per_second_t kMaxVelocity = 1.75_mps;
+  static constexpr wpi::units::meters_per_second_squared_t kMaxAcceleration =
       0.75_mps_sq;
   static constexpr double kP = 1.3;
   static constexpr double kI = 0.0;
   static constexpr double kD = 0.7;
-  static constexpr units::volt_t kS = 1.1_V;
-  static constexpr units::volt_t kG = 1.2_V;
+  static constexpr wpi::units::volt_t kS = 1.1_V;
+  static constexpr wpi::units::volt_t kG = 1.2_V;
   static constexpr auto kV = 1.3_V / 1_mps;
 
-  frc::Joystick m_joystick{1};
-  frc::Encoder m_encoder{1, 2};
-  frc::PWMSparkMax m_motor{1};
+  wpi::Joystick m_joystick{1};
+  wpi::Encoder m_encoder{1, 2};
+  wpi::PWMSparkMax m_motor{1};
 
   // Create a PID controller whose setpoint's change is subject to maximum
   // velocity and acceleration constraints.
-  frc::TrapezoidProfile::Constraints m_constraints{
+  wpi::math::TrapezoidProfile::Constraints m_constraints{
       kMaxVelocity, kMaxAcceleration};
-  frc::ProfiledPIDController m_controller{kP, kI, kD,
+  wpi::math::ProfiledPIDController m_controller{kP, kI, kD,
                                                          m_constraints, kDt};
-  frc::ElevatorFeedforward m_feedforward{kS, kG, kV};
+  wpi::math::ElevatorFeedforward m_feedforward{kS, kG, kV};
 };
 
 #ifndef RUNNING_FRC_TESTS
 int main() {
-  return frc::StartRobot();
+  return wpi::StartRobot();
 }
 #endif
diff --git a/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/cpp/Robot.cpp
index 8b41513dd4..a015d903e9 100644
--- a/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/cpp/Robot.cpp
@@ -34,6 +34,6 @@ void Robot::DisabledInit() {
 
 #ifndef RUNNING_FRC_TESTS
 int main() {
-  return frc::StartRobot();
+  return wpi::StartRobot();
 }
 #endif
diff --git a/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/cpp/subsystems/Elevator.cpp b/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/cpp/subsystems/Elevator.cpp
index 3206082c9e..d5140a7636 100644
--- a/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/cpp/subsystems/Elevator.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/cpp/subsystems/Elevator.cpp
@@ -14,14 +14,14 @@ Elevator::Elevator() {
   // Put Mechanism 2d to SmartDashboard
   // To view the Elevator visualization, select Network Tables -> SmartDashboard
   // -> Elevator Sim
-  frc::SmartDashboard::PutData("Elevator Sim", &m_mech2d);
+  wpi::SmartDashboard::PutData("Elevator Sim", &m_mech2d);
 }
 
 void Elevator::SimulationPeriodic() {
   // In this method, we update our simulation of what our elevator is doing
   // First, we set our "inputs" (voltages)
-  m_elevatorSim.SetInput(frc::Vectord<1>{
-      m_motorSim.GetSpeed() * frc::RobotController::GetInputVoltage()});
+  m_elevatorSim.SetInput(wpi::math::Vectord<1>{
+      m_motorSim.GetSpeed() * wpi::RobotController::GetInputVoltage()});
 
   // Next, we update it. The standard loop time is 20ms.
   m_elevatorSim.Update(20_ms);
@@ -30,8 +30,8 @@ void Elevator::SimulationPeriodic() {
   // voltage
   m_encoderSim.SetDistance(m_elevatorSim.GetPosition().value());
   // SimBattery estimates loaded battery voltages
-  frc::sim::RoboRioSim::SetVInVoltage(
-      frc::sim::BatterySim::Calculate({m_elevatorSim.GetCurrentDraw()}));
+  wpi::sim::RoboRioSim::SetVInVoltage(
+      wpi::sim::BatterySim::Calculate({m_elevatorSim.GetCurrentDraw()}));
 }
 
 void Elevator::UpdateTelemetry() {
@@ -39,14 +39,14 @@ void Elevator::UpdateTelemetry() {
   m_elevatorMech2d->SetLength(m_encoder.GetDistance());
 }
 
-void Elevator::ReachGoal(units::meter_t goal) {
+void Elevator::ReachGoal(wpi::units::meter_t goal) {
   m_controller.SetGoal(goal);
   // With the setpoint value we run PID control like normal
   double pidOutput =
-      m_controller.Calculate(units::meter_t{m_encoder.GetDistance()});
-  units::volt_t feedforwardOutput =
+      m_controller.Calculate(wpi::units::meter_t{m_encoder.GetDistance()});
+  wpi::units::volt_t feedforwardOutput =
       m_feedforward.Calculate(m_controller.GetSetpoint().velocity);
-  m_motor.SetVoltage(units::volt_t{pidOutput} + feedforwardOutput);
+  m_motor.SetVoltage(wpi::units::volt_t{pidOutput} + feedforwardOutput);
 }
 
 void Elevator::Stop() {
diff --git a/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/include/Constants.hpp b/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/include/Constants.hpp
index 928bfa061d..e5afd4a072 100644
--- a/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/include/Constants.hpp
+++ b/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/include/Constants.hpp
@@ -34,18 +34,18 @@ inline constexpr double kElevatorKp = 5.0;
 inline constexpr double kElevatorKi = 0.0;
 inline constexpr double kElevatorKd = 0.0;
 
-inline constexpr units::volt_t kElevatorkS = 0.0_V;
-inline constexpr units::volt_t kElevatorkG = 0.762_V;
+inline constexpr wpi::units::volt_t kElevatorkS = 0.0_V;
+inline constexpr wpi::units::volt_t kElevatorkG = 0.762_V;
 inline constexpr auto kElevatorkV = 0.762_V / 1_mps;
 inline constexpr auto kElevatorkA = 0.0_V / 1_mps_sq;
 
 inline constexpr double kElevatorGearing = 10.0;
-inline constexpr units::meter_t kElevatorDrumRadius = 2_in;
-inline constexpr units::kilogram_t kCarriageMass = 4.0_kg;
+inline constexpr wpi::units::meter_t kElevatorDrumRadius = 2_in;
+inline constexpr wpi::units::kilogram_t kCarriageMass = 4.0_kg;
 
-inline constexpr units::meter_t kSetpoint = 75_cm;
-inline constexpr units::meter_t kMinElevatorHeight = 0_cm;
-inline constexpr units::meter_t kMaxElevatorHeight = 1.25_m;
+inline constexpr wpi::units::meter_t kSetpoint = 75_cm;
+inline constexpr wpi::units::meter_t kMinElevatorHeight = 0_cm;
+inline constexpr wpi::units::meter_t kMaxElevatorHeight = 1.25_m;
 
 // distance per pulse = (distance per revolution) / (pulses per revolution)
 //  = (Pi * D) / ppr
diff --git a/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/include/Robot.hpp b/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/include/Robot.hpp
index ea1bf8775f..1c0ac7a33a 100644
--- a/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/include/Robot.hpp
+++ b/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/include/Robot.hpp
@@ -12,7 +12,7 @@
 /**
  * This is a sample program to demonstrate the use of elevator simulation.
  */
-class Robot : public frc::TimedRobot {
+class Robot : public wpi::TimedRobot {
  public:
   Robot() {}
   void RobotPeriodic() override;
@@ -21,6 +21,6 @@ class Robot : public frc::TimedRobot {
   void DisabledInit() override;
 
  private:
-  frc::Joystick m_joystick{Constants::kJoystickPort};
+  wpi::Joystick m_joystick{Constants::kJoystickPort};
   Elevator m_elevator;
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/include/subsystems/Elevator.hpp b/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/include/subsystems/Elevator.hpp
index 8ed8bd3a2e..64f1591c4b 100644
--- a/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/include/subsystems/Elevator.hpp
+++ b/wpilibcExamples/src/main/cpp/examples/ElevatorSimulation/include/subsystems/Elevator.hpp
@@ -26,30 +26,30 @@ class Elevator {
   Elevator();
   void SimulationPeriodic();
   void UpdateTelemetry();
-  void ReachGoal(units::meter_t goal);
+  void ReachGoal(wpi::units::meter_t goal);
   void Stop();
 
  private:
   // This gearbox represents a gearbox containing 4 Vex 775pro motors.
-  frc::DCMotor m_elevatorGearbox = frc::DCMotor::Vex775Pro(4);
+  wpi::math::DCMotor m_elevatorGearbox = wpi::math::DCMotor::Vex775Pro(4);
 
   // Standard classes for controlling our elevator
-  frc::TrapezoidProfile::Constraints m_constraints{2.45_mps,
+  wpi::math::TrapezoidProfile::Constraints m_constraints{2.45_mps,
                                                                   2.45_mps_sq};
-  frc::ProfiledPIDController m_controller{
+  wpi::math::ProfiledPIDController m_controller{
       Constants::kElevatorKp, Constants::kElevatorKi, Constants::kElevatorKd,
       m_constraints};
 
-  frc::ElevatorFeedforward m_feedforward{
+  wpi::math::ElevatorFeedforward m_feedforward{
       Constants::kElevatorkS, Constants::kElevatorkG, Constants::kElevatorkV,
       Constants::kElevatorkA};
-  frc::Encoder m_encoder{Constants::kEncoderAChannel,
+  wpi::Encoder m_encoder{Constants::kEncoderAChannel,
                          Constants::kEncoderBChannel};
-  frc::PWMSparkMax m_motor{Constants::kMotorPort};
-  frc::sim::PWMMotorControllerSim m_motorSim{m_motor};
+  wpi::PWMSparkMax m_motor{Constants::kMotorPort};
+  wpi::sim::PWMMotorControllerSim m_motorSim{m_motor};
 
   // Simulation classes help us simulate what's going on, including gravity.
-  frc::sim::ElevatorSim m_elevatorSim{m_elevatorGearbox,
+  wpi::sim::ElevatorSim m_elevatorSim{m_elevatorGearbox,
                                       Constants::kElevatorGearing,
                                       Constants::kCarriageMass,
                                       Constants::kElevatorDrumRadius,
@@ -58,13 +58,13 @@ class Elevator {
                                       true,
                                       0_m,
                                       {0.01}};
-  frc::sim::EncoderSim m_encoderSim{m_encoder};
+  wpi::sim::EncoderSim m_encoderSim{m_encoder};
 
   // Create a Mechanism2d display of an elevator
-  frc::Mechanism2d m_mech2d{20, 50};
-  frc::MechanismRoot2d* m_elevatorRoot =
+  wpi::Mechanism2d m_mech2d{20, 50};
+  wpi::MechanismRoot2d* m_elevatorRoot =
       m_mech2d.GetRoot("Elevator Root", 10, 0);
-  frc::MechanismLigament2d* m_elevatorMech2d =
-      m_elevatorRoot->Append(
+  wpi::MechanismLigament2d* m_elevatorMech2d =
+      m_elevatorRoot->Append(
           "Elevator", m_elevatorSim.GetPosition().value(), 90_deg);
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/ElevatorTrapezoidProfile/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/ElevatorTrapezoidProfile/cpp/Robot.cpp
index 9ffb16b58c..736df29e7e 100644
--- a/wpilibcExamples/src/main/cpp/examples/ElevatorTrapezoidProfile/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/ElevatorTrapezoidProfile/cpp/Robot.cpp
@@ -16,9 +16,9 @@
 
 #include "ExampleSmartMotorController.hpp"
 
-class Robot : public frc::TimedRobot {
+class Robot : public wpi::TimedRobot {
  public:
-  static constexpr units::second_t kDt = 20_ms;
+  static constexpr wpi::units::second_t kDt = 20_ms;
 
   Robot() {
     // Note: These gains are fake, and will have to be tuned for your robot.
@@ -43,21 +43,21 @@ class Robot : public frc::TimedRobot {
   }
 
  private:
-  frc::Joystick m_joystick{1};
+  wpi::Joystick m_joystick{1};
   ExampleSmartMotorController m_motor{1};
-  frc::SimpleMotorFeedforward m_feedforward{
+  wpi::math::SimpleMotorFeedforward m_feedforward{
       // Note: These gains are fake, and will have to be tuned for your robot.
       1_V, 1.5_V * 1_s / 1_m};
 
   // Create a motion profile with the given maximum velocity and maximum
   // acceleration constraints for the next setpoint.
-  frc::TrapezoidProfile m_profile{{1.75_mps, 0.75_mps_sq}};
-  frc::TrapezoidProfile::State m_goal;
-  frc::TrapezoidProfile::State m_setpoint;
+  wpi::math::TrapezoidProfile m_profile{{1.75_mps, 0.75_mps_sq}};
+  wpi::math::TrapezoidProfile::State m_goal;
+  wpi::math::TrapezoidProfile::State m_setpoint;
 };
 
 #ifndef RUNNING_FRC_TESTS
 int main() {
-  return frc::StartRobot();
+  return wpi::StartRobot();
 }
 #endif
diff --git a/wpilibcExamples/src/main/cpp/examples/Encoder/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/Encoder/cpp/Robot.cpp
index 8d92d4441d..4ceaa2348d 100644
--- a/wpilibcExamples/src/main/cpp/examples/Encoder/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/Encoder/cpp/Robot.cpp
@@ -27,7 +27,7 @@
  * distance that the robot drives can be precisely controlled during the
  * autonomous mode.
  */
-class Robot : public frc::TimedRobot {
+class Robot : public wpi::TimedRobot {
  public:
   Robot() {
     /* Defines the number of samples to average when determining the rate.
@@ -53,10 +53,10 @@ class Robot : public frc::TimedRobot {
 
   void TeleopPeriodic() override {
     // Retrieve the net displacement of the Encoder since the last Reset.
-    frc::SmartDashboard::PutNumber("Encoder Distance", m_encoder.GetDistance());
+    wpi::SmartDashboard::PutNumber("Encoder Distance", m_encoder.GetDistance());
 
     // Retrieve the current rate of the encoder.
-    frc::SmartDashboard::PutNumber("Encoder Rate", m_encoder.GetRate());
+    wpi::SmartDashboard::PutNumber("Encoder Rate", m_encoder.GetRate());
   }
 
  private:
@@ -76,11 +76,11 @@ class Robot : public frc::TimedRobot {
    * and defaults to k4X. Faster (k4X) encoding gives greater positional
    * precision but more noise in the rate.
    */
-  frc::Encoder m_encoder{1, 2, false, frc::Encoder::k4X};
+  wpi::Encoder m_encoder{1, 2, false, wpi::Encoder::k4X};
 };
 
 #ifndef RUNNING_FRC_TESTS
 int main() {
-  return frc::StartRobot();
+  return wpi::StartRobot();
 }
 #endif
diff --git a/wpilibcExamples/src/main/cpp/examples/EventLoop/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/EventLoop/cpp/Robot.cpp
index fd47f6880d..0aa6895dc6 100644
--- a/wpilibcExamples/src/main/cpp/examples/EventLoop/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/EventLoop/cpp/Robot.cpp
@@ -18,17 +18,17 @@
 static const auto SHOT_VELOCITY = 200_rpm;
 static const auto TOLERANCE = 8_rpm;
 
-class Robot : public frc::TimedRobot {
+class Robot : public wpi::TimedRobot {
  public:
   Robot() {
     m_controller.SetTolerance(TOLERANCE.value());
 
-    frc::BooleanEvent isBallAtKicker{&m_loop, [] {
+    wpi::BooleanEvent isBallAtKicker{&m_loop, [] {
                                        return false;
                                        //    return kickerSensor.GetRange() <
                                        //           KICKER_THRESHOLD;
                                      }};
-    frc::BooleanEvent intakeButton{
+    wpi::BooleanEvent intakeButton{
         &m_loop, [&joystick = m_joystick] { return joystick.GetRawButton(2); }};
 
     // if the thumb button is held
@@ -45,7 +45,7 @@ class Robot : public frc::TimedRobot {
         // stop the intake
         .IfHigh([&intake = m_intake] { intake.Set(0.0); });
 
-    frc::BooleanEvent shootTrigger{
+    wpi::BooleanEvent shootTrigger{
         &m_loop, [&joystick = m_joystick] { return joystick.GetTrigger(); }};
 
     // if the trigger is held
@@ -54,15 +54,15 @@ class Robot : public frc::TimedRobot {
         .IfHigh([&shooter = m_shooter, &controller = m_controller, &ff = m_ff,
                  &encoder = m_shooterEncoder] {
           shooter.SetVoltage(
-              units::volt_t{controller.Calculate(encoder.GetRate(),
+              wpi::units::volt_t{controller.Calculate(encoder.GetRate(),
                                                  SHOT_VELOCITY.value())} +
-              ff.Calculate(units::radians_per_second_t{SHOT_VELOCITY}));
+              ff.Calculate(wpi::units::radians_per_second_t{SHOT_VELOCITY}));
         });
     // if not, stop
     (!shootTrigger).IfHigh([&shooter = m_shooter] { shooter.Set(0.0); });
 
-    frc::BooleanEvent atTargetVelocity =
-        frc::BooleanEvent(
+    wpi::BooleanEvent atTargetVelocity =
+        wpi::BooleanEvent(
             &m_loop,
             [&controller = m_controller] { return controller.AtSetpoint(); })
             // debounce for more stability
@@ -81,21 +81,21 @@ class Robot : public frc::TimedRobot {
   void RobotPeriodic() override { m_loop.Poll(); }
 
  private:
-  frc::PWMSparkMax m_shooter{0};
-  frc::Encoder m_shooterEncoder{0, 1};
-  frc::PIDController m_controller{0.3, 0, 0};
-  frc::SimpleMotorFeedforward m_ff{0.1_V, 0.065_V / 1_rpm};
+  wpi::PWMSparkMax m_shooter{0};
+  wpi::Encoder m_shooterEncoder{0, 1};
+  wpi::math::PIDController m_controller{0.3, 0, 0};
+  wpi::math::SimpleMotorFeedforward m_ff{0.1_V, 0.065_V / 1_rpm};
 
-  frc::PWMSparkMax m_kicker{1};
+  wpi::PWMSparkMax m_kicker{1};
 
-  frc::PWMSparkMax m_intake{3};
+  wpi::PWMSparkMax m_intake{3};
 
-  frc::EventLoop m_loop{};
-  frc::Joystick m_joystick{0};
+  wpi::EventLoop m_loop{};
+  wpi::Joystick m_joystick{0};
 };
 
 #ifndef RUNNING_FRC_TESTS
 int main() {
-  return frc::StartRobot();
+  return wpi::StartRobot();
 }
 #endif
diff --git a/wpilibcExamples/src/main/cpp/examples/FlywheelBangBangController/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/FlywheelBangBangController/cpp/Robot.cpp
index b115ff94c3..281db535f7 100644
--- a/wpilibcExamples/src/main/cpp/examples/FlywheelBangBangController/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/FlywheelBangBangController/cpp/Robot.cpp
@@ -15,21 +15,21 @@
 #include 
 
 /**
- * This is a sample program to demonstrate the use of a BangBangController with
+ * This is a sample program to demonstrate the use of a wpi::math::BangBangController with
  * a flywheel to control speed.
  */
-class Robot : public frc::TimedRobot {
+class Robot : public wpi::TimedRobot {
  public:
   /**
    * Controls flywheel to a set speed (RPM) controlled by a joystick.
    */
   void TeleopPeriodic() override {
     // Scale setpoint value between 0 and maxSetpointValue
-    units::radians_per_second_t setpoint =
-        units::math::max(0_rpm, m_joystick.GetRawAxis(0) * kMaxSetpointValue);
+    wpi::units::radians_per_second_t setpoint =
+        wpi::units::math::max(0_rpm, m_joystick.GetRawAxis(0) * kMaxSetpointValue);
 
     // Set setpoint and measurement of the bang-bang controller
-    units::volt_t bangOutput =
+    wpi::units::volt_t bangOutput =
         m_bangBangController.Calculate(m_encoder.GetRate(), setpoint.value()) *
         12_V;
 
@@ -42,7 +42,7 @@ class Robot : public frc::TimedRobot {
 
   Robot() {
     // Add bang-bang controller to SmartDashboard and networktables.
-    frc::SmartDashboard::PutData("BangBangController", &m_bangBangController);
+    wpi::SmartDashboard::PutData("BangBangController", &m_bangBangController);
   }
 
   /**
@@ -53,7 +53,7 @@ class Robot : public frc::TimedRobot {
     // simulation, and write the simulated velocities to our simulated encoder
     m_flywheelSim.SetInputVoltage(
         m_flywheelMotor.Get() *
-        units::volt_t{frc::RobotController::GetInputVoltage()});
+        wpi::units::volt_t{wpi::RobotController::GetInputVoltage()});
     m_flywheelSim.Update(20_ms);
     m_encoderSim.SetRate(m_flywheelSim.GetAngularVelocity().value());
   }
@@ -64,23 +64,23 @@ class Robot : public frc::TimedRobot {
   static constexpr int kEncoderBChannel = 1;
 
   // Max setpoint for joystick control
-  static constexpr units::radians_per_second_t kMaxSetpointValue = 6000_rpm;
+  static constexpr wpi::units::radians_per_second_t kMaxSetpointValue = 6000_rpm;
 
   // Joystick to control setpoint
-  frc::Joystick m_joystick{0};
+  wpi::Joystick m_joystick{0};
 
-  frc::PWMSparkMax m_flywheelMotor{kMotorPort};
-  frc::Encoder m_encoder{kEncoderAChannel, kEncoderBChannel};
+  wpi::PWMSparkMax m_flywheelMotor{kMotorPort};
+  wpi::Encoder m_encoder{kEncoderAChannel, kEncoderBChannel};
 
-  frc::BangBangController m_bangBangController;
+  wpi::math::BangBangController m_bangBangController;
 
   // Gains are for example purposes only - must be determined for your own
   // robot!
-  static constexpr units::volt_t kFlywheelKs = 0.0001_V;
+  static constexpr wpi::units::volt_t kFlywheelKs = 0.0001_V;
   static constexpr decltype(1_V / 1_rad_per_s) kFlywheelKv = 0.000195_V / 1_rpm;
   static constexpr decltype(1_V / 1_rad_per_s_sq) kFlywheelKa =
       0.0003_V / 1_rev_per_m_per_s;
-  frc::SimpleMotorFeedforward m_feedforward{
+  wpi::math::SimpleMotorFeedforward m_feedforward{
       kFlywheelKs, kFlywheelKv, kFlywheelKa};
 
   // Simulation classes help us simulate our robot
@@ -90,19 +90,19 @@ class Robot : public frc::TimedRobot {
   static constexpr double kFlywheelGearing = 1.0;
 
   // 1/2 MR²
-  static constexpr units::kilogram_square_meter_t kFlywheelMomentOfInertia =
+  static constexpr wpi::units::kilogram_square_meter_t kFlywheelMomentOfInertia =
       0.5 * 1.5_lb * 4_in * 4_in;
 
-  frc::DCMotor m_gearbox = frc::DCMotor::NEO(1);
-  frc::LinearSystem<1, 1, 1> m_plant{frc::LinearSystemId::FlywheelSystem(
+  wpi::math::DCMotor m_gearbox = wpi::math::DCMotor::NEO(1);
+  wpi::math::LinearSystem<1, 1, 1> m_plant{wpi::math::LinearSystemId::FlywheelSystem(
       m_gearbox, kFlywheelMomentOfInertia, kFlywheelGearing)};
 
-  frc::sim::FlywheelSim m_flywheelSim{m_plant, m_gearbox};
-  frc::sim::EncoderSim m_encoderSim{m_encoder};
+  wpi::sim::FlywheelSim m_flywheelSim{m_plant, m_gearbox};
+  wpi::sim::EncoderSim m_encoderSim{m_encoder};
 };
 
 #ifndef RUNNING_FRC_TESTS
 int main() {
-  return frc::StartRobot();
+  return wpi::StartRobot();
 }
 #endif
diff --git a/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp
index f721bee724..b6ff8b6b7c 100644
--- a/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/GettingStarted/cpp/Robot.cpp
@@ -8,11 +8,11 @@
 #include 
 #include 
 
-class Robot : public frc::TimedRobot {
+class Robot : public wpi::TimedRobot {
  public:
   Robot() {
-    wpi::SendableRegistry::AddChild(&m_robotDrive, &m_left);
-    wpi::SendableRegistry::AddChild(&m_robotDrive, &m_right);
+    wpi::util::SendableRegistry::AddChild(&m_robotDrive, &m_left);
+    wpi::util::SendableRegistry::AddChild(&m_robotDrive, &m_right);
 
     // We need to invert one side of the drivetrain so that positive voltages
     // result in both sides moving forward. Depending on how your robot's
@@ -49,18 +49,18 @@ class Robot : public frc::TimedRobot {
 
  private:
   // Robot drive system
-  frc::PWMSparkMax m_left{0};
-  frc::PWMSparkMax m_right{1};
-  frc::DifferentialDrive m_robotDrive{
+  wpi::PWMSparkMax m_left{0};
+  wpi::PWMSparkMax m_right{1};
+  wpi::DifferentialDrive m_robotDrive{
       [&](double output) { m_left.Set(output); },
       [&](double output) { m_right.Set(output); }};
 
-  frc::XboxController m_controller{0};
-  frc::Timer m_timer;
+  wpi::XboxController m_controller{0};
+  wpi::Timer m_timer;
 };
 
 #ifndef RUNNING_FRC_TESTS
 int main() {
-  return frc::StartRobot();
+  return wpi::StartRobot();
 }
 #endif
diff --git a/wpilibcExamples/src/main/cpp/examples/Gyro/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/Gyro/cpp/Robot.cpp
index 3b8dc7329b..7dd6f510ae 100644
--- a/wpilibcExamples/src/main/cpp/examples/Gyro/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/Gyro/cpp/Robot.cpp
@@ -15,7 +15,7 @@
  * robot drive straight. This program uses a joystick to drive forwards and
  * backwards while the gyro is used for direction keeping.
  */
-class Robot : public frc::TimedRobot {
+class Robot : public wpi::TimedRobot {
  public:
   Robot() {
     // We need to invert one side of the drivetrain so that positive voltages
@@ -23,8 +23,8 @@ class Robot : public frc::TimedRobot {
     // gearbox is constructed, you might have to invert the left side instead.
     m_right.SetInverted(true);
 
-    wpi::SendableRegistry::AddChild(&m_drive, &m_left);
-    wpi::SendableRegistry::AddChild(&m_drive, &m_right);
+    wpi::util::SendableRegistry::AddChild(&m_drive, &m_left);
+    wpi::util::SendableRegistry::AddChild(&m_drive, &m_right);
   }
 
   /**
@@ -44,21 +44,21 @@ class Robot : public frc::TimedRobot {
 
   static constexpr int kLeftMotorPort = 0;
   static constexpr int kRightMotorPort = 1;
-  static constexpr frc::OnboardIMU::MountOrientation kIMUMountOrientation =
-      frc::OnboardIMU::kFlat;
+  static constexpr wpi::OnboardIMU::MountOrientation kIMUMountOrientation =
+      wpi::OnboardIMU::kFlat;
   static constexpr int kJoystickPort = 0;
 
-  frc::PWMSparkMax m_left{kLeftMotorPort};
-  frc::PWMSparkMax m_right{kRightMotorPort};
-  frc::DifferentialDrive m_drive{[&](double output) { m_left.Set(output); },
+  wpi::PWMSparkMax m_left{kLeftMotorPort};
+  wpi::PWMSparkMax m_right{kRightMotorPort};
+  wpi::DifferentialDrive m_drive{[&](double output) { m_left.Set(output); },
                                  [&](double output) { m_right.Set(output); }};
 
-  frc::OnboardIMU m_imu{kIMUMountOrientation};
-  frc::Joystick m_joystick{kJoystickPort};
+  wpi::OnboardIMU m_imu{kIMUMountOrientation};
+  wpi::Joystick m_joystick{kJoystickPort};
 };
 
 #ifndef RUNNING_FRC_TESTS
 int main() {
-  return frc::StartRobot();
+  return wpi::StartRobot();
 }
 #endif
diff --git a/wpilibcExamples/src/main/cpp/examples/GyroMecanum/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/GyroMecanum/cpp/Robot.cpp
index 876af1b314..059b224af4 100644
--- a/wpilibcExamples/src/main/cpp/examples/GyroMecanum/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/GyroMecanum/cpp/Robot.cpp
@@ -13,13 +13,13 @@
  * maintain rotation vectors in relation to the starting orientation of the
  * robot (field-oriented controls).
  */
-class Robot : public frc::TimedRobot {
+class Robot : public wpi::TimedRobot {
  public:
   Robot() {
-    wpi::SendableRegistry::AddChild(&m_robotDrive, &m_frontLeft);
-    wpi::SendableRegistry::AddChild(&m_robotDrive, &m_rearLeft);
-    wpi::SendableRegistry::AddChild(&m_robotDrive, &m_frontRight);
-    wpi::SendableRegistry::AddChild(&m_robotDrive, &m_rearRight);
+    wpi::util::SendableRegistry::AddChild(&m_robotDrive, &m_frontLeft);
+    wpi::util::SendableRegistry::AddChild(&m_robotDrive, &m_rearLeft);
+    wpi::util::SendableRegistry::AddChild(&m_robotDrive, &m_frontRight);
+    wpi::util::SendableRegistry::AddChild(&m_robotDrive, &m_rearRight);
 
     // Invert the right side motors. You may need to change or remove this to
     // match your robot.
@@ -40,26 +40,26 @@ class Robot : public frc::TimedRobot {
   static constexpr int kRearLeftMotorPort = 1;
   static constexpr int kFrontRightMotorPort = 2;
   static constexpr int kRearRightMotorPort = 3;
-  static constexpr frc::OnboardIMU::MountOrientation kIMUMountOrientation =
-      frc::OnboardIMU::kFlat;
+  static constexpr wpi::OnboardIMU::MountOrientation kIMUMountOrientation =
+      wpi::OnboardIMU::kFlat;
   static constexpr int kJoystickPort = 0;
 
-  frc::PWMSparkMax m_frontLeft{kFrontLeftMotorPort};
-  frc::PWMSparkMax m_rearLeft{kRearLeftMotorPort};
-  frc::PWMSparkMax m_frontRight{kFrontRightMotorPort};
-  frc::PWMSparkMax m_rearRight{kRearRightMotorPort};
-  frc::MecanumDrive m_robotDrive{
+  wpi::PWMSparkMax m_frontLeft{kFrontLeftMotorPort};
+  wpi::PWMSparkMax m_rearLeft{kRearLeftMotorPort};
+  wpi::PWMSparkMax m_frontRight{kFrontRightMotorPort};
+  wpi::PWMSparkMax m_rearRight{kRearRightMotorPort};
+  wpi::MecanumDrive m_robotDrive{
       [&](double output) { m_frontLeft.Set(output); },
       [&](double output) { m_rearLeft.Set(output); },
       [&](double output) { m_frontRight.Set(output); },
       [&](double output) { m_rearRight.Set(output); }};
 
-  frc::OnboardIMU m_imu{kIMUMountOrientation};
-  frc::Joystick m_joystick{kJoystickPort};
+  wpi::OnboardIMU m_imu{kIMUMountOrientation};
+  wpi::Joystick m_joystick{kJoystickPort};
 };
 
 #ifndef RUNNING_FRC_TESTS
 int main() {
-  return frc::StartRobot();
+  return wpi::StartRobot();
 }
 #endif
diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/Robot.cpp
index a65f524314..f3a5693620 100644
--- a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/Robot.cpp
@@ -11,11 +11,11 @@
 
 Robot::Robot() {
   // Start recording to data log
-  frc::DataLogManager::Start();
+  wpi::DataLogManager::Start();
 
   // Record DS control and joystick data.
   // Change to `false` to not record joystick data.
-  frc::DriverStation::StartDataLog(frc::DataLogManager::GetLog(), true);
+  wpi::DriverStation::StartDataLog(wpi::DataLogManager::GetLog(), true);
 }
 
 /**
@@ -27,7 +27,7 @@ Robot::Robot() {
  * LiveWindow and SmartDashboard integrated updating.
  */
 void Robot::RobotPeriodic() {
-  frc2::CommandScheduler::GetInstance().Run();
+  wpi::cmd::CommandScheduler::GetInstance().Run();
 }
 
 /**
@@ -47,7 +47,7 @@ void Robot::AutonomousInit() {
   m_autonomousCommand = m_container.GetAutonomousCommand();
 
   if (m_autonomousCommand != nullptr) {
-    frc2::CommandScheduler::GetInstance().Schedule(m_autonomousCommand);
+    wpi::cmd::CommandScheduler::GetInstance().Schedule(m_autonomousCommand);
   }
 }
 
@@ -76,6 +76,6 @@ void Robot::TestPeriodic() {}
 
 #ifndef RUNNING_FRC_TESTS
 int main() {
-  return frc::StartRobot();
+  return wpi::StartRobot();
 }
 #endif
diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/RobotContainer.cpp b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/RobotContainer.cpp
index caf50ec9d6..bd1a8ec805 100644
--- a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/RobotContainer.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/RobotContainer.cpp
@@ -15,16 +15,16 @@ RobotContainer::RobotContainer() {
   m_chooser.AddOption("Complex Auto", m_complexAuto.get());
 
   // Put the chooser on the dashboard
-  frc::SmartDashboard::PutData("Autonomous", &m_chooser);
+  wpi::SmartDashboard::PutData("Autonomous", &m_chooser);
   // Put subsystems to dashboard.
-  frc::SmartDashboard::PutData("Drivetrain", &m_drive);
-  frc::SmartDashboard::PutData("HatchSubsystem", &m_hatch);
+  wpi::SmartDashboard::PutData("Drivetrain", &m_drive);
+  wpi::SmartDashboard::PutData("HatchSubsystem", &m_hatch);
 
   // Configure the button bindings
   ConfigureButtonBindings();
 
   // Set up default drive command
-  m_drive.SetDefaultCommand(frc2::cmd::Run(
+  m_drive.SetDefaultCommand(wpi::cmd::cmd::Run(
       [this] {
         m_drive.ArcadeDrive(-m_driverController.GetLeftY(),
                             -m_driverController.GetRightX());
@@ -41,11 +41,11 @@ void RobotContainer::ConfigureButtonBindings() {
   m_driverController.Square().OnTrue(m_hatch.ReleaseHatchCommand());
   // While holding R1, drive at half speed
   m_driverController.R1()
-      .OnTrue(frc2::cmd::RunOnce([this] { m_drive.SetMaxOutput(0.5); }, {}))
-      .OnFalse(frc2::cmd::RunOnce([this] { m_drive.SetMaxOutput(1.0); }, {}));
+      .OnTrue(wpi::cmd::cmd::RunOnce([this] { m_drive.SetMaxOutput(0.5); }, {}))
+      .OnFalse(wpi::cmd::cmd::RunOnce([this] { m_drive.SetMaxOutput(1.0); }, {}));
 }
 
-frc2::Command* RobotContainer::GetAutonomousCommand() {
+wpi::cmd::Command* RobotContainer::GetAutonomousCommand() {
   // Runs the chosen command in autonomous
   return m_chooser.GetSelected();
 }
diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/commands/Autos.cpp b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/commands/Autos.cpp
index 473fdbfbfa..d6515a4156 100644
--- a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/commands/Autos.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/commands/Autos.cpp
@@ -11,8 +11,8 @@
 
 using namespace AutoConstants;
 
-frc2::CommandPtr autos::SimpleAuto(DriveSubsystem* drive) {
-  return frc2::FunctionalCommand(
+wpi::cmd::CommandPtr autos::SimpleAuto(DriveSubsystem* drive) {
+  return wpi::cmd::FunctionalCommand(
              // Reset encoders on command start
              [drive] { drive->ResetEncoders(); },
              // Drive forward while the command is executing
@@ -30,11 +30,11 @@ frc2::CommandPtr autos::SimpleAuto(DriveSubsystem* drive) {
       .ToPtr();
 }
 
-frc2::CommandPtr autos::ComplexAuto(DriveSubsystem* drive,
+wpi::cmd::CommandPtr autos::ComplexAuto(DriveSubsystem* drive,
                                     HatchSubsystem* hatch) {
-  return frc2::cmd::Sequence(
+  return wpi::cmd::cmd::Sequence(
       // Drive forward the specified distance
-      frc2::FunctionalCommand(
+      wpi::cmd::FunctionalCommand(
           // Reset encoders on command start
           [drive] { drive->ResetEncoders(); },
           // Drive forward while the command is executing
@@ -54,7 +54,7 @@ frc2::CommandPtr autos::ComplexAuto(DriveSubsystem* drive,
       hatch->ReleaseHatchCommand(),
       // Drive backward the specified distance
       // Drive forward the specified distance
-      frc2::FunctionalCommand(
+      wpi::cmd::FunctionalCommand(
           // Reset encoders on command start
           [drive] { drive->ResetEncoders(); },
           // Drive backward while the command is executing
diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/subsystems/DriveSubsystem.cpp b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/subsystems/DriveSubsystem.cpp
index 0d1c8a6f4e..3421e69341 100644
--- a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/subsystems/DriveSubsystem.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/subsystems/DriveSubsystem.cpp
@@ -15,8 +15,8 @@ DriveSubsystem::DriveSubsystem()
       m_right2{kRightMotor2Port},
       m_leftEncoder{kLeftEncoderPorts[0], kLeftEncoderPorts[1]},
       m_rightEncoder{kRightEncoderPorts[0], kRightEncoderPorts[1]} {
-  wpi::SendableRegistry::AddChild(&m_drive, &m_left1);
-  wpi::SendableRegistry::AddChild(&m_drive, &m_right1);
+  wpi::util::SendableRegistry::AddChild(&m_drive, &m_left1);
+  wpi::util::SendableRegistry::AddChild(&m_drive, &m_right1);
 
   m_left1.AddFollower(m_left2);
   m_right1.AddFollower(m_right2);
@@ -52,7 +52,7 @@ void DriveSubsystem::SetMaxOutput(double maxOutput) {
   m_drive.SetMaxOutput(maxOutput);
 }
 
-void DriveSubsystem::InitSendable(wpi::SendableBuilder& builder) {
+void DriveSubsystem::InitSendable(wpi::util::SendableBuilder& builder) {
   SubsystemBase::InitSendable(builder);
 
   // Publish encoder distances to telemetry.
diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/subsystems/HatchSubsystem.cpp b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/subsystems/HatchSubsystem.cpp
index cf47294bd5..6ebc783f4a 100644
--- a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/subsystems/HatchSubsystem.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/cpp/subsystems/HatchSubsystem.cpp
@@ -9,27 +9,27 @@
 using namespace HatchConstants;
 
 HatchSubsystem::HatchSubsystem()
-    : m_hatchSolenoid{0, frc::PneumaticsModuleType::CTREPCM,
+    : m_hatchSolenoid{0, wpi::PneumaticsModuleType::CTREPCM,
                       kHatchSolenoidPorts[0], kHatchSolenoidPorts[1]} {}
 
-frc2::CommandPtr HatchSubsystem::GrabHatchCommand() {
+wpi::cmd::CommandPtr HatchSubsystem::GrabHatchCommand() {
   // implicitly require `this`
   return this->RunOnce(
-      [this] { m_hatchSolenoid.Set(frc::DoubleSolenoid::kForward); });
+      [this] { m_hatchSolenoid.Set(wpi::DoubleSolenoid::kForward); });
 }
 
-frc2::CommandPtr HatchSubsystem::ReleaseHatchCommand() {
+wpi::cmd::CommandPtr HatchSubsystem::ReleaseHatchCommand() {
   // implicitly require `this`
   return this->RunOnce(
-      [this] { m_hatchSolenoid.Set(frc::DoubleSolenoid::kReverse); });
+      [this] { m_hatchSolenoid.Set(wpi::DoubleSolenoid::kReverse); });
 }
 
-void HatchSubsystem::InitSendable(wpi::SendableBuilder& builder) {
+void HatchSubsystem::InitSendable(wpi::util::SendableBuilder& builder) {
   SubsystemBase::InitSendable(builder);
 
   // Publish the solenoid state to telemetry.
   builder.AddBooleanProperty(
       "extended",
-      [this] { return m_hatchSolenoid.Get() == frc::DoubleSolenoid::kForward; },
+      [this] { return m_hatchSolenoid.Get() == wpi::DoubleSolenoid::kForward; },
       nullptr);
 }
diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/Robot.hpp b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/Robot.hpp
index 7a9d5e7e42..219b7b9799 100644
--- a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/Robot.hpp
+++ b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/Robot.hpp
@@ -9,7 +9,7 @@
 
 #include "RobotContainer.hpp"
 
-class Robot : public frc::TimedRobot {
+class Robot : public wpi::TimedRobot {
  public:
   Robot();
   void RobotPeriodic() override;
@@ -24,7 +24,7 @@ class Robot : public frc::TimedRobot {
  private:
   // Have it null by default so that if testing teleop it
   // doesn't have undefined behavior and potentially crash.
-  frc2::Command* m_autonomousCommand = nullptr;
+  wpi::cmd::Command* m_autonomousCommand = nullptr;
 
   RobotContainer m_container;
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/RobotContainer.hpp b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/RobotContainer.hpp
index 0358d8c556..bf90d22f37 100644
--- a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/RobotContainer.hpp
+++ b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/RobotContainer.hpp
@@ -27,11 +27,11 @@ class RobotContainer {
  public:
   RobotContainer();
 
-  frc2::Command* GetAutonomousCommand();
+  wpi::cmd::Command* GetAutonomousCommand();
 
  private:
   // The driver's controller
-  frc2::CommandPS4Controller m_driverController{
+  wpi::cmd::CommandPS4Controller m_driverController{
       OIConstants::kDriverControllerPort};
 
   // The robot's subsystems and commands are defined here...
@@ -43,11 +43,11 @@ class RobotContainer {
   // Commands owned by RobotContainer
 
   // The autonomous routines
-  frc2::CommandPtr m_simpleAuto = autos::SimpleAuto(&m_drive);
-  frc2::CommandPtr m_complexAuto = autos::ComplexAuto(&m_drive, &m_hatch);
+  wpi::cmd::CommandPtr m_simpleAuto = autos::SimpleAuto(&m_drive);
+  wpi::cmd::CommandPtr m_complexAuto = autos::ComplexAuto(&m_drive, &m_hatch);
 
   // The chooser for the autonomous routines
-  frc::SendableChooser m_chooser;
+  wpi::SendableChooser m_chooser;
 
   void ConfigureButtonBindings();
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/commands/Autos.hpp b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/commands/Autos.hpp
index 979689161d..59afdd21d9 100644
--- a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/commands/Autos.hpp
+++ b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/commands/Autos.hpp
@@ -15,12 +15,12 @@ namespace autos {
 /**
  * A simple auto that drives forward, then stops.
  */
-frc2::CommandPtr SimpleAuto(DriveSubsystem* drive);
+wpi::cmd::CommandPtr SimpleAuto(DriveSubsystem* drive);
 
 /**
  * A complex auto command that drives forward, releases a hatch, and then drives
  * backward.
  */
-frc2::CommandPtr ComplexAuto(DriveSubsystem* drive, HatchSubsystem* hatch);
+wpi::cmd::CommandPtr ComplexAuto(DriveSubsystem* drive, HatchSubsystem* hatch);
 
 }  // namespace autos
diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/subsystems/DriveSubsystem.hpp b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/subsystems/DriveSubsystem.hpp
index 88339eb767..f8896a27af 100644
--- a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/subsystems/DriveSubsystem.hpp
+++ b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/subsystems/DriveSubsystem.hpp
@@ -11,7 +11,7 @@
 
 #include "Constants.hpp"
 
-class DriveSubsystem : public frc2::SubsystemBase {
+class DriveSubsystem : public wpi::cmd::SubsystemBase {
  public:
   DriveSubsystem();
 
@@ -50,25 +50,25 @@ class DriveSubsystem : public frc2::SubsystemBase {
    */
   void SetMaxOutput(double maxOutput);
 
-  void InitSendable(wpi::SendableBuilder& builder) override;
+  void InitSendable(wpi::util::SendableBuilder& builder) override;
 
  private:
   // Components (e.g. motor controllers and sensors) should generally be
   // declared private and exposed only through public methods.
 
   // The motor controllers
-  frc::PWMSparkMax m_left1;
-  frc::PWMSparkMax m_left2;
-  frc::PWMSparkMax m_right1;
-  frc::PWMSparkMax m_right2;
+  wpi::PWMSparkMax m_left1;
+  wpi::PWMSparkMax m_left2;
+  wpi::PWMSparkMax m_right1;
+  wpi::PWMSparkMax m_right2;
 
   // The robot's drive
-  frc::DifferentialDrive m_drive{[&](double output) { m_left1.Set(output); },
+  wpi::DifferentialDrive m_drive{[&](double output) { m_left1.Set(output); },
                                  [&](double output) { m_right1.Set(output); }};
 
   // The left-side drive encoder
-  frc::Encoder m_leftEncoder;
+  wpi::Encoder m_leftEncoder;
 
   // The right-side drive encoder
-  frc::Encoder m_rightEncoder;
+  wpi::Encoder m_rightEncoder;
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/subsystems/HatchSubsystem.hpp b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/subsystems/HatchSubsystem.hpp
index 5e8970ac5e..ba81b034f3 100644
--- a/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/subsystems/HatchSubsystem.hpp
+++ b/wpilibcExamples/src/main/cpp/examples/HatchbotInlined/include/subsystems/HatchSubsystem.hpp
@@ -11,7 +11,7 @@
 
 #include "Constants.hpp"
 
-class HatchSubsystem : public frc2::SubsystemBase {
+class HatchSubsystem : public wpi::cmd::SubsystemBase {
  public:
   HatchSubsystem();
 
@@ -20,17 +20,17 @@ class HatchSubsystem : public frc2::SubsystemBase {
   /**
    * Grabs the hatch.
    */
-  frc2::CommandPtr GrabHatchCommand();
+  wpi::cmd::CommandPtr GrabHatchCommand();
 
   /**
    * Releases the hatch.
    */
-  frc2::CommandPtr ReleaseHatchCommand();
+  wpi::cmd::CommandPtr ReleaseHatchCommand();
 
-  void InitSendable(wpi::SendableBuilder& builder) override;
+  void InitSendable(wpi::util::SendableBuilder& builder) override;
 
  private:
   // Components (e.g. motor controllers and sensors) should generally be
   // declared private and exposed only through public methods.
-  frc::DoubleSolenoid m_hatchSolenoid;
+  wpi::DoubleSolenoid m_hatchSolenoid;
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/Robot.cpp
index a65f524314..f3a5693620 100644
--- a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/Robot.cpp
@@ -11,11 +11,11 @@
 
 Robot::Robot() {
   // Start recording to data log
-  frc::DataLogManager::Start();
+  wpi::DataLogManager::Start();
 
   // Record DS control and joystick data.
   // Change to `false` to not record joystick data.
-  frc::DriverStation::StartDataLog(frc::DataLogManager::GetLog(), true);
+  wpi::DriverStation::StartDataLog(wpi::DataLogManager::GetLog(), true);
 }
 
 /**
@@ -27,7 +27,7 @@ Robot::Robot() {
  * LiveWindow and SmartDashboard integrated updating.
  */
 void Robot::RobotPeriodic() {
-  frc2::CommandScheduler::GetInstance().Run();
+  wpi::cmd::CommandScheduler::GetInstance().Run();
 }
 
 /**
@@ -47,7 +47,7 @@ void Robot::AutonomousInit() {
   m_autonomousCommand = m_container.GetAutonomousCommand();
 
   if (m_autonomousCommand != nullptr) {
-    frc2::CommandScheduler::GetInstance().Schedule(m_autonomousCommand);
+    wpi::cmd::CommandScheduler::GetInstance().Schedule(m_autonomousCommand);
   }
 }
 
@@ -76,6 +76,6 @@ void Robot::TestPeriodic() {}
 
 #ifndef RUNNING_FRC_TESTS
 int main() {
-  return frc::StartRobot();
+  return wpi::StartRobot();
 }
 #endif
diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/RobotContainer.cpp b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/RobotContainer.cpp
index 928a670e4f..7ce8aea9e2 100644
--- a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/RobotContainer.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/RobotContainer.cpp
@@ -20,10 +20,10 @@ RobotContainer::RobotContainer() {
   m_chooser.AddOption("Complex Auto", &m_complexAuto);
 
   // Put the chooser on the dashboard
-  frc::SmartDashboard::PutData("Autonomous", &m_chooser);
+  wpi::SmartDashboard::PutData("Autonomous", &m_chooser);
   // Put subsystems to dashboard.
-  frc::SmartDashboard::PutData("Drivetrain", &m_drive);
-  frc::SmartDashboard::PutData("HatchSubsystem", &m_hatch);
+  wpi::SmartDashboard::PutData("Drivetrain", &m_drive);
+  wpi::SmartDashboard::PutData("HatchSubsystem", &m_hatch);
 
   // Configure the button bindings
   ConfigureButtonBindings();
@@ -41,18 +41,18 @@ void RobotContainer::ConfigureButtonBindings() {
   // the scheduler thus, no memory leaks!
 
   // Grab the hatch when the 'A' button is pressed.
-  frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kA)
+  wpi::cmd::JoystickButton(&m_driverController, wpi::XboxController::Button::kA)
       .OnTrue(GrabHatch(&m_hatch).ToPtr());
   // Release the hatch when the 'B' button is pressed.
-  frc2::JoystickButton(&m_driverController, frc::XboxController::Button::kB)
+  wpi::cmd::JoystickButton(&m_driverController, wpi::XboxController::Button::kB)
       .OnTrue(ReleaseHatch(&m_hatch).ToPtr());
   // While holding the shoulder button, drive at half speed
-  frc2::JoystickButton(&m_driverController,
-                       frc::XboxController::Button::kRightBumper)
+  wpi::cmd::JoystickButton(&m_driverController,
+                       wpi::XboxController::Button::kRightBumper)
       .WhileTrue(HalveDriveSpeed(&m_drive).ToPtr());
 }
 
-frc2::Command* RobotContainer::GetAutonomousCommand() {
+wpi::cmd::Command* RobotContainer::GetAutonomousCommand() {
   // Runs the chosen command in autonomous
   return m_chooser.GetSelected();
 }
diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/subsystems/DriveSubsystem.cpp b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/subsystems/DriveSubsystem.cpp
index 0d1c8a6f4e..3421e69341 100644
--- a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/subsystems/DriveSubsystem.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/subsystems/DriveSubsystem.cpp
@@ -15,8 +15,8 @@ DriveSubsystem::DriveSubsystem()
       m_right2{kRightMotor2Port},
       m_leftEncoder{kLeftEncoderPorts[0], kLeftEncoderPorts[1]},
       m_rightEncoder{kRightEncoderPorts[0], kRightEncoderPorts[1]} {
-  wpi::SendableRegistry::AddChild(&m_drive, &m_left1);
-  wpi::SendableRegistry::AddChild(&m_drive, &m_right1);
+  wpi::util::SendableRegistry::AddChild(&m_drive, &m_left1);
+  wpi::util::SendableRegistry::AddChild(&m_drive, &m_right1);
 
   m_left1.AddFollower(m_left2);
   m_right1.AddFollower(m_right2);
@@ -52,7 +52,7 @@ void DriveSubsystem::SetMaxOutput(double maxOutput) {
   m_drive.SetMaxOutput(maxOutput);
 }
 
-void DriveSubsystem::InitSendable(wpi::SendableBuilder& builder) {
+void DriveSubsystem::InitSendable(wpi::util::SendableBuilder& builder) {
   SubsystemBase::InitSendable(builder);
 
   // Publish encoder distances to telemetry.
diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/subsystems/HatchSubsystem.cpp b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/subsystems/HatchSubsystem.cpp
index 5aa2b96317..517392617a 100644
--- a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/subsystems/HatchSubsystem.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/cpp/subsystems/HatchSubsystem.cpp
@@ -9,23 +9,23 @@
 using namespace HatchConstants;
 
 HatchSubsystem::HatchSubsystem()
-    : m_hatchSolenoid{0, frc::PneumaticsModuleType::CTREPCM,
+    : m_hatchSolenoid{0, wpi::PneumaticsModuleType::CTREPCM,
                       kHatchSolenoidPorts[0], kHatchSolenoidPorts[1]} {}
 
 void HatchSubsystem::GrabHatch() {
-  m_hatchSolenoid.Set(frc::DoubleSolenoid::kForward);
+  m_hatchSolenoid.Set(wpi::DoubleSolenoid::kForward);
 }
 
 void HatchSubsystem::ReleaseHatch() {
-  m_hatchSolenoid.Set(frc::DoubleSolenoid::kReverse);
+  m_hatchSolenoid.Set(wpi::DoubleSolenoid::kReverse);
 }
 
-void HatchSubsystem::InitSendable(wpi::SendableBuilder& builder) {
+void HatchSubsystem::InitSendable(wpi::util::SendableBuilder& builder) {
   SubsystemBase::InitSendable(builder);
 
   // Publish the solenoid state to telemetry.
   builder.AddBooleanProperty(
       "extended",
-      [this] { return m_hatchSolenoid.Get() == frc::DoubleSolenoid::kForward; },
+      [this] { return m_hatchSolenoid.Get() == wpi::DoubleSolenoid::kForward; },
       nullptr);
 }
diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/Robot.hpp b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/Robot.hpp
index 7a9d5e7e42..219b7b9799 100644
--- a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/Robot.hpp
+++ b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/Robot.hpp
@@ -9,7 +9,7 @@
 
 #include "RobotContainer.hpp"
 
-class Robot : public frc::TimedRobot {
+class Robot : public wpi::TimedRobot {
  public:
   Robot();
   void RobotPeriodic() override;
@@ -24,7 +24,7 @@ class Robot : public frc::TimedRobot {
  private:
   // Have it null by default so that if testing teleop it
   // doesn't have undefined behavior and potentially crash.
-  frc2::Command* m_autonomousCommand = nullptr;
+  wpi::cmd::Command* m_autonomousCommand = nullptr;
 
   RobotContainer m_container;
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/RobotContainer.hpp b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/RobotContainer.hpp
index c32adf6bf4..b080241199 100644
--- a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/RobotContainer.hpp
+++ b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/RobotContainer.hpp
@@ -26,7 +26,7 @@ class RobotContainer {
  public:
   RobotContainer();
 
-  frc2::Command* GetAutonomousCommand();
+  wpi::cmd::Command* GetAutonomousCommand();
 
  private:
   // The robot's subsystems and commands are defined here...
@@ -41,10 +41,10 @@ class RobotContainer {
   ComplexAuto m_complexAuto{&m_drive, &m_hatch};
 
   // The chooser for the autonomous routines
-  frc::SendableChooser m_chooser;
+  wpi::SendableChooser m_chooser;
 
   // The driver's controller
-  frc::XboxController m_driverController{OIConstants::kDriverControllerPort};
+  wpi::XboxController m_driverController{OIConstants::kDriverControllerPort};
 
   void ConfigureButtonBindings();
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/ComplexAuto.hpp b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/ComplexAuto.hpp
index 25e8d6c3e9..715eebb9d0 100644
--- a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/ComplexAuto.hpp
+++ b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/ComplexAuto.hpp
@@ -16,7 +16,7 @@
  * backward.
  */
 class ComplexAuto
-    : public frc2::CommandHelper {
+    : public wpi::cmd::CommandHelper {
  public:
   /**
    * Creates a new ComplexAuto.
diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/DefaultDrive.hpp b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/DefaultDrive.hpp
index d069c5086b..abf2dad6f5 100644
--- a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/DefaultDrive.hpp
+++ b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/DefaultDrive.hpp
@@ -18,7 +18,7 @@
  *
  * @see RunCommand
  */
-class DefaultDrive : public frc2::CommandHelper {
+class DefaultDrive : public wpi::cmd::CommandHelper {
  public:
   /**
    * Creates a new DefaultDrive.
diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/DriveDistance.hpp b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/DriveDistance.hpp
index 79fdde41f6..c3eb068155 100644
--- a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/DriveDistance.hpp
+++ b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/DriveDistance.hpp
@@ -9,7 +9,7 @@
 
 #include "subsystems/DriveSubsystem.hpp"
 
-class DriveDistance : public frc2::CommandHelper {
+class DriveDistance : public wpi::cmd::CommandHelper {
  public:
   /**
    * Creates a new DriveDistance.
diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/GrabHatch.hpp b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/GrabHatch.hpp
index cfd3971ebb..11f8f9e366 100644
--- a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/GrabHatch.hpp
+++ b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/GrabHatch.hpp
@@ -16,7 +16,7 @@
  *
  * @see InstantCommand
  */
-class GrabHatch : public frc2::CommandHelper {
+class GrabHatch : public wpi::cmd::CommandHelper {
  public:
   explicit GrabHatch(HatchSubsystem* subsystem);
 
diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/HalveDriveSpeed.hpp b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/HalveDriveSpeed.hpp
index 85e0c79ec9..b64c9209c3 100644
--- a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/HalveDriveSpeed.hpp
+++ b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/HalveDriveSpeed.hpp
@@ -10,7 +10,7 @@
 #include "subsystems/DriveSubsystem.hpp"
 
 class HalveDriveSpeed
-    : public frc2::CommandHelper {
+    : public wpi::cmd::CommandHelper {
  public:
   explicit HalveDriveSpeed(DriveSubsystem* subsystem);
 
diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/ReleaseHatch.hpp b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/ReleaseHatch.hpp
index 868bb88bb4..7a54ac5853 100644
--- a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/ReleaseHatch.hpp
+++ b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/commands/ReleaseHatch.hpp
@@ -16,7 +16,7 @@
  *
  * @see InstantCommand
  */
-class ReleaseHatch : public frc2::CommandHelper {
+class ReleaseHatch : public wpi::cmd::CommandHelper {
  public:
   explicit ReleaseHatch(HatchSubsystem* subsystem);
 
diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/subsystems/DriveSubsystem.hpp b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/subsystems/DriveSubsystem.hpp
index 88339eb767..f8896a27af 100644
--- a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/subsystems/DriveSubsystem.hpp
+++ b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/subsystems/DriveSubsystem.hpp
@@ -11,7 +11,7 @@
 
 #include "Constants.hpp"
 
-class DriveSubsystem : public frc2::SubsystemBase {
+class DriveSubsystem : public wpi::cmd::SubsystemBase {
  public:
   DriveSubsystem();
 
@@ -50,25 +50,25 @@ class DriveSubsystem : public frc2::SubsystemBase {
    */
   void SetMaxOutput(double maxOutput);
 
-  void InitSendable(wpi::SendableBuilder& builder) override;
+  void InitSendable(wpi::util::SendableBuilder& builder) override;
 
  private:
   // Components (e.g. motor controllers and sensors) should generally be
   // declared private and exposed only through public methods.
 
   // The motor controllers
-  frc::PWMSparkMax m_left1;
-  frc::PWMSparkMax m_left2;
-  frc::PWMSparkMax m_right1;
-  frc::PWMSparkMax m_right2;
+  wpi::PWMSparkMax m_left1;
+  wpi::PWMSparkMax m_left2;
+  wpi::PWMSparkMax m_right1;
+  wpi::PWMSparkMax m_right2;
 
   // The robot's drive
-  frc::DifferentialDrive m_drive{[&](double output) { m_left1.Set(output); },
+  wpi::DifferentialDrive m_drive{[&](double output) { m_left1.Set(output); },
                                  [&](double output) { m_right1.Set(output); }};
 
   // The left-side drive encoder
-  frc::Encoder m_leftEncoder;
+  wpi::Encoder m_leftEncoder;
 
   // The right-side drive encoder
-  frc::Encoder m_rightEncoder;
+  wpi::Encoder m_rightEncoder;
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/subsystems/HatchSubsystem.hpp b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/subsystems/HatchSubsystem.hpp
index 6f0ecaeaa9..4a8218e74f 100644
--- a/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/subsystems/HatchSubsystem.hpp
+++ b/wpilibcExamples/src/main/cpp/examples/HatchbotTraditional/include/subsystems/HatchSubsystem.hpp
@@ -10,7 +10,7 @@
 
 #include "Constants.hpp"
 
-class HatchSubsystem : public frc2::SubsystemBase {
+class HatchSubsystem : public wpi::cmd::SubsystemBase {
  public:
   HatchSubsystem();
 
@@ -26,10 +26,10 @@ class HatchSubsystem : public frc2::SubsystemBase {
    */
   void ReleaseHatch();
 
-  void InitSendable(wpi::SendableBuilder& builder) override;
+  void InitSendable(wpi::util::SendableBuilder& builder) override;
 
  private:
   // Components (e.g. motor controllers and sensors) should generally be
   // declared private and exposed only through public methods.
-  frc::DoubleSolenoid m_hatchSolenoid;
+  wpi::DoubleSolenoid m_hatchSolenoid;
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/HidRumble/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/HidRumble/cpp/Robot.cpp
index 092ea96fb4..974f48b322 100644
--- a/wpilibcExamples/src/main/cpp/examples/HidRumble/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/HidRumble/cpp/Robot.cpp
@@ -8,26 +8,26 @@
 /**
  * This is a demo program showing the use of GenericHID's rumble feature.
  */
-class Robot : public frc::TimedRobot {
+class Robot : public wpi::TimedRobot {
  public:
   void AutonomousInit() override {
     // Turn on rumble at the start of auto
-    m_hid.SetRumble(frc::GenericHID::RumbleType::kLeftRumble, 1.0);
-    m_hid.SetRumble(frc::GenericHID::RumbleType::kRightRumble, 1.0);
+    m_hid.SetRumble(wpi::GenericHID::RumbleType::kLeftRumble, 1.0);
+    m_hid.SetRumble(wpi::GenericHID::RumbleType::kRightRumble, 1.0);
   }
 
   void DisabledInit() override {
     // Stop the rumble when entering disabled
-    m_hid.SetRumble(frc::GenericHID::RumbleType::kLeftRumble, 0.0);
-    m_hid.SetRumble(frc::GenericHID::RumbleType::kRightRumble, 0.0);
+    m_hid.SetRumble(wpi::GenericHID::RumbleType::kLeftRumble, 0.0);
+    m_hid.SetRumble(wpi::GenericHID::RumbleType::kRightRumble, 0.0);
   }
 
  private:
-  frc::GenericHID m_hid{0};
+  wpi::GenericHID m_hid{0};
 };
 
 #ifndef RUNNING_FRC_TESTS
 int main() {
-  return frc::StartRobot();
+  return wpi::StartRobot();
 }
 #endif
diff --git a/wpilibcExamples/src/main/cpp/examples/HttpCamera/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/HttpCamera/cpp/Robot.cpp
index 46db9dc877..29f92f85a0 100644
--- a/wpilibcExamples/src/main/cpp/examples/HttpCamera/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/HttpCamera/cpp/Robot.cpp
@@ -14,7 +14,7 @@
  * and sent to the dashboard. OpenCV has many methods for different types of
  * processing.
  */
-class Robot : public frc::TimedRobot {
+class Robot : public wpi::TimedRobot {
  public:
   Robot() {
     // We need to run our vision program in a separate thread. If not, our robot
@@ -27,17 +27,17 @@ class Robot : public frc::TimedRobot {
   static void VisionThread() {
     // Create an HTTP camera. The address will need to be modified to have the
     // correct team number. The exact path will depend on the source.
-    cs::HttpCamera camera{"My Camera", "http://10.x.y.11/video/stream.mjpg"};
+    wpi::cs::HttpCamera camera{"My Camera", "http://10.x.y.11/video/stream.mjpg"};
     // Start capturing images
-    frc::CameraServer::StartAutomaticCapture(camera);
+    wpi::CameraServer::StartAutomaticCapture(camera);
     // Set the resolution
     camera.SetResolution(640, 480);
 
     // Get a CvSink. This will capture Mats from the Camera
-    cs::CvSink cvSink = frc::CameraServer::GetVideo();
+    wpi::cs::CvSink cvSink = wpi::CameraServer::GetVideo();
     // Setup a CvSource. This will send images back to the Dashboard
-    cs::CvSource outputStream =
-        frc::CameraServer::PutVideo("Rectangle", 640, 480);
+    wpi::cs::CvSource outputStream =
+        wpi::CameraServer::PutVideo("Rectangle", 640, 480);
 
     // Mats are very memory expensive. Lets reuse this Mat.
     cv::Mat mat;
@@ -62,6 +62,6 @@ class Robot : public frc::TimedRobot {
 
 #ifndef RUNNING_FRC_TESTS
 int main() {
-  return frc::StartRobot();
+  return wpi::StartRobot();
 }
 #endif
diff --git a/wpilibcExamples/src/main/cpp/examples/I2CCommunication/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/I2CCommunication/cpp/Robot.cpp
index 9b61fd5158..ff4c2a2e62 100644
--- a/wpilibcExamples/src/main/cpp/examples/I2CCommunication/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/I2CCommunication/cpp/Robot.cpp
@@ -22,9 +22,9 @@ void Robot::RobotPeriodic() {
   // alliance, enabled in teleop mode, with 43 seconds left in the match.
 
   std::string allianceString = "U";
-  auto alliance = frc::DriverStation::GetAlliance();
+  auto alliance = wpi::DriverStation::GetAlliance();
   if (alliance.has_value()) {
-    if (alliance == frc::DriverStation::Alliance::kRed) {
+    if (alliance == wpi::DriverStation::Alliance::kRed) {
       allianceString = "R";
     } else {
       allianceString = "B";
@@ -33,15 +33,15 @@ void Robot::RobotPeriodic() {
 
   auto string =
       fmt::format("{}{}{}{:03}", allianceString,
-                  frc::DriverStation::IsEnabled() ? "E" : "D",
-                  frc::DriverStation::IsAutonomous() ? "A" : "T",
-                  static_cast(frc::Timer::GetMatchTime().value()));
+                  wpi::DriverStation::IsEnabled() ? "E" : "D",
+                  wpi::DriverStation::IsAutonomous() ? "A" : "T",
+                  static_cast(wpi::Timer::GetMatchTime().value()));
 
   arduino.WriteBulk(reinterpret_cast(string.data()), string.size());
 }
 
 #ifndef RUNNING_FRC_TESTS
 int main() {
-  return frc::StartRobot();
+  return wpi::StartRobot();
 }
 #endif
diff --git a/wpilibcExamples/src/main/cpp/examples/I2CCommunication/include/Robot.hpp b/wpilibcExamples/src/main/cpp/examples/I2CCommunication/include/Robot.hpp
index 0e2bc795a4..4172a92b82 100644
--- a/wpilibcExamples/src/main/cpp/examples/I2CCommunication/include/Robot.hpp
+++ b/wpilibcExamples/src/main/cpp/examples/I2CCommunication/include/Robot.hpp
@@ -13,13 +13,13 @@
  * This is a sample program demonstrating how to communicate to a light
  * controller from the robot code using the roboRIO's I2C port.
  */
-class Robot : public frc::TimedRobot {
+class Robot : public wpi::TimedRobot {
  public:
   void RobotPeriodic() override;
 
-  static constexpr frc::I2C::Port kPort = frc::I2C::Port::kPort0;
+  static constexpr wpi::I2C::Port kPort = wpi::I2C::Port::kPort0;
 
  private:
   static constexpr int deviceAddress = 4;
-  frc::I2C arduino{kPort, deviceAddress};
+  wpi::I2C arduino{kPort, deviceAddress};
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/IntermediateVision/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/IntermediateVision/cpp/Robot.cpp
index db5c5e732b..458dff7203 100644
--- a/wpilibcExamples/src/main/cpp/examples/IntermediateVision/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/IntermediateVision/cpp/Robot.cpp
@@ -17,7 +17,7 @@
  * and sent to the dashboard. OpenCV has many methods for different types of
  * processing.
  */
-class Robot : public frc::TimedRobot {
+class Robot : public wpi::TimedRobot {
  public:
   Robot() {
     // We need to run our vision program in a separate thread. If not, our robot
@@ -36,15 +36,15 @@ class Robot : public frc::TimedRobot {
  private:
   static void VisionThread() {
     // Get the USB camera from CameraServer
-    cs::UsbCamera camera = frc::CameraServer::StartAutomaticCapture();
+    wpi::cs::UsbCamera camera = wpi::CameraServer::StartAutomaticCapture();
     // Set the resolution
     camera.SetResolution(640, 480);
 
     // Get a CvSink. This will capture Mats from the Camera
-    cs::CvSink cvSink = frc::CameraServer::GetVideo();
+    wpi::cs::CvSink cvSink = wpi::CameraServer::GetVideo();
     // Setup a CvSource. This will send images back to the Dashboard
-    cs::CvSource outputStream =
-        frc::CameraServer::PutVideo("Rectangle", 640, 480);
+    wpi::cs::CvSource outputStream =
+        wpi::CameraServer::PutVideo("Rectangle", 640, 480);
 
     // Mats are very memory expensive. Lets reuse this Mat.
     cv::Mat mat;
@@ -72,6 +72,6 @@ class Robot : public frc::TimedRobot {
 
 #ifndef RUNNING_FRC_TESTS
 int main() {
-  return frc::StartRobot();
+  return wpi::StartRobot();
 }
 #endif
diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumBot/cpp/Drivetrain.cpp b/wpilibcExamples/src/main/cpp/examples/MecanumBot/cpp/Drivetrain.cpp
index 6d5d7ffd88..1edeb28c9f 100644
--- a/wpilibcExamples/src/main/cpp/examples/MecanumBot/cpp/Drivetrain.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/MecanumBot/cpp/Drivetrain.cpp
@@ -6,21 +6,21 @@
 
 #include 
 
-frc::MecanumDriveWheelSpeeds Drivetrain::GetCurrentState() const {
-  return {units::meters_per_second_t{m_frontLeftEncoder.GetRate()},
-          units::meters_per_second_t{m_frontRightEncoder.GetRate()},
-          units::meters_per_second_t{m_backLeftEncoder.GetRate()},
-          units::meters_per_second_t{m_backRightEncoder.GetRate()}};
+wpi::math::MecanumDriveWheelSpeeds Drivetrain::GetCurrentState() const {
+  return {wpi::units::meters_per_second_t{m_frontLeftEncoder.GetRate()},
+          wpi::units::meters_per_second_t{m_frontRightEncoder.GetRate()},
+          wpi::units::meters_per_second_t{m_backLeftEncoder.GetRate()},
+          wpi::units::meters_per_second_t{m_backRightEncoder.GetRate()}};
 }
 
-frc::MecanumDriveWheelPositions Drivetrain::GetCurrentWheelDistances() const {
-  return {units::meter_t{m_frontLeftEncoder.GetDistance()},
-          units::meter_t{m_frontRightEncoder.GetDistance()},
-          units::meter_t{m_backLeftEncoder.GetDistance()},
-          units::meter_t{m_backRightEncoder.GetDistance()}};
+wpi::math::MecanumDriveWheelPositions Drivetrain::GetCurrentWheelDistances() const {
+  return {wpi::units::meter_t{m_frontLeftEncoder.GetDistance()},
+          wpi::units::meter_t{m_frontRightEncoder.GetDistance()},
+          wpi::units::meter_t{m_backLeftEncoder.GetDistance()},
+          wpi::units::meter_t{m_backRightEncoder.GetDistance()}};
 }
 
-void Drivetrain::SetSpeeds(const frc::MecanumDriveWheelSpeeds& wheelSpeeds) {
+void Drivetrain::SetSpeeds(const wpi::math::MecanumDriveWheelSpeeds& wheelSpeeds) {
   const auto frontLeftFeedforward =
       m_feedforward.Calculate(wheelSpeeds.frontLeft);
   const auto frontRightFeedforward =
@@ -39,21 +39,21 @@ void Drivetrain::SetSpeeds(const frc::MecanumDriveWheelSpeeds& wheelSpeeds) {
   const double backRightOutput = m_backRightPIDController.Calculate(
       m_backRightEncoder.GetRate(), wheelSpeeds.rearRight.value());
 
-  m_frontLeftMotor.SetVoltage(units::volt_t{frontLeftOutput} +
+  m_frontLeftMotor.SetVoltage(wpi::units::volt_t{frontLeftOutput} +
                               frontLeftFeedforward);
-  m_frontRightMotor.SetVoltage(units::volt_t{frontRightOutput} +
+  m_frontRightMotor.SetVoltage(wpi::units::volt_t{frontRightOutput} +
                                frontRightFeedforward);
-  m_backLeftMotor.SetVoltage(units::volt_t{backLeftOutput} +
+  m_backLeftMotor.SetVoltage(wpi::units::volt_t{backLeftOutput} +
                              backLeftFeedforward);
-  m_backRightMotor.SetVoltage(units::volt_t{backRightOutput} +
+  m_backRightMotor.SetVoltage(wpi::units::volt_t{backRightOutput} +
                               backRightFeedforward);
 }
 
-void Drivetrain::Drive(units::meters_per_second_t xSpeed,
-                       units::meters_per_second_t ySpeed,
-                       units::radians_per_second_t rot, bool fieldRelative,
-                       units::second_t period) {
-  frc::ChassisSpeeds chassisSpeeds{xSpeed, ySpeed, rot};
+void Drivetrain::Drive(wpi::units::meters_per_second_t xSpeed,
+                       wpi::units::meters_per_second_t ySpeed,
+                       wpi::units::radians_per_second_t rot, bool fieldRelative,
+                       wpi::units::second_t period) {
+  wpi::math::ChassisSpeeds chassisSpeeds{xSpeed, ySpeed, rot};
   if (fieldRelative) {
     chassisSpeeds = chassisSpeeds.ToRobotRelative(m_imu.GetRotation2d());
   }
diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumBot/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/MecanumBot/cpp/Robot.cpp
index dd29ae5889..eb5a574ed2 100644
--- a/wpilibcExamples/src/main/cpp/examples/MecanumBot/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/MecanumBot/cpp/Robot.cpp
@@ -8,7 +8,7 @@
 
 #include "Drivetrain.hpp"
 
-class Robot : public frc::TimedRobot {
+class Robot : public wpi::TimedRobot {
  public:
   void AutonomousPeriodic() override {
     DriveWithJoystick(false);
@@ -18,14 +18,14 @@ class Robot : public frc::TimedRobot {
   void TeleopPeriodic() override { DriveWithJoystick(true); }
 
  private:
-  frc::XboxController m_controller{0};
+  wpi::XboxController m_controller{0};
   Drivetrain m_mecanum;
 
   // Slew rate limiters to make joystick inputs more gentle; 1/3 sec from 0
   // to 1.
-  frc::SlewRateLimiter m_xspeedLimiter{3 / 1_s};
-  frc::SlewRateLimiter m_yspeedLimiter{3 / 1_s};
-  frc::SlewRateLimiter m_rotLimiter{3 / 1_s};
+  wpi::math::SlewRateLimiter m_xspeedLimiter{3 / 1_s};
+  wpi::math::SlewRateLimiter m_yspeedLimiter{3 / 1_s};
+  wpi::math::SlewRateLimiter m_rotLimiter{3 / 1_s};
 
   void DriveWithJoystick(bool fieldRelative) {
     // Get the x speed. We are inverting this because Xbox controllers return
@@ -52,6 +52,6 @@ class Robot : public frc::TimedRobot {
 
 #ifndef RUNNING_FRC_TESTS
 int main() {
-  return frc::StartRobot();
+  return wpi::StartRobot();
 }
 #endif
diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumBot/include/Drivetrain.hpp b/wpilibcExamples/src/main/cpp/examples/MecanumBot/include/Drivetrain.hpp
index c6c2f7aa89..360ec9fb66 100644
--- a/wpilibcExamples/src/main/cpp/examples/MecanumBot/include/Drivetrain.hpp
+++ b/wpilibcExamples/src/main/cpp/examples/MecanumBot/include/Drivetrain.hpp
@@ -30,50 +30,50 @@ class Drivetrain {
     m_backRightMotor.SetInverted(true);
   }
 
-  frc::MecanumDriveWheelSpeeds GetCurrentState() const;
-  frc::MecanumDriveWheelPositions GetCurrentWheelDistances() const;
-  void SetSpeeds(const frc::MecanumDriveWheelSpeeds& wheelSpeeds);
-  void Drive(units::meters_per_second_t xSpeed,
-             units::meters_per_second_t ySpeed, units::radians_per_second_t rot,
-             bool fieldRelative, units::second_t period);
+  wpi::math::MecanumDriveWheelSpeeds GetCurrentState() const;
+  wpi::math::MecanumDriveWheelPositions GetCurrentWheelDistances() const;
+  void SetSpeeds(const wpi::math::MecanumDriveWheelSpeeds& wheelSpeeds);
+  void Drive(wpi::units::meters_per_second_t xSpeed,
+             wpi::units::meters_per_second_t ySpeed, wpi::units::radians_per_second_t rot,
+             bool fieldRelative, wpi::units::second_t period);
   void UpdateOdometry();
 
-  static constexpr units::meters_per_second_t kMaxSpeed =
+  static constexpr wpi::units::meters_per_second_t kMaxSpeed =
       3.0_mps;  // 3 meters per second
-  static constexpr units::radians_per_second_t kMaxAngularSpeed{
+  static constexpr wpi::units::radians_per_second_t kMaxAngularSpeed{
       std::numbers::pi};  // 1/2 rotation per second
 
  private:
-  frc::PWMSparkMax m_frontLeftMotor{1};
-  frc::PWMSparkMax m_frontRightMotor{2};
-  frc::PWMSparkMax m_backLeftMotor{3};
-  frc::PWMSparkMax m_backRightMotor{4};
+  wpi::PWMSparkMax m_frontLeftMotor{1};
+  wpi::PWMSparkMax m_frontRightMotor{2};
+  wpi::PWMSparkMax m_backLeftMotor{3};
+  wpi::PWMSparkMax m_backRightMotor{4};
 
-  frc::Encoder m_frontLeftEncoder{0, 1};
-  frc::Encoder m_frontRightEncoder{2, 3};
-  frc::Encoder m_backLeftEncoder{4, 5};
-  frc::Encoder m_backRightEncoder{6, 7};
+  wpi::Encoder m_frontLeftEncoder{0, 1};
+  wpi::Encoder m_frontRightEncoder{2, 3};
+  wpi::Encoder m_backLeftEncoder{4, 5};
+  wpi::Encoder m_backRightEncoder{6, 7};
 
-  frc::Translation2d m_frontLeftLocation{0.381_m, 0.381_m};
-  frc::Translation2d m_frontRightLocation{0.381_m, -0.381_m};
-  frc::Translation2d m_backLeftLocation{-0.381_m, 0.381_m};
-  frc::Translation2d m_backRightLocation{-0.381_m, -0.381_m};
+  wpi::math::Translation2d m_frontLeftLocation{0.381_m, 0.381_m};
+  wpi::math::Translation2d m_frontRightLocation{0.381_m, -0.381_m};
+  wpi::math::Translation2d m_backLeftLocation{-0.381_m, 0.381_m};
+  wpi::math::Translation2d m_backRightLocation{-0.381_m, -0.381_m};
 
-  frc::PIDController m_frontLeftPIDController{1.0, 0.0, 0.0};
-  frc::PIDController m_frontRightPIDController{1.0, 0.0, 0.0};
-  frc::PIDController m_backLeftPIDController{1.0, 0.0, 0.0};
-  frc::PIDController m_backRightPIDController{1.0, 0.0, 0.0};
+  wpi::math::PIDController m_frontLeftPIDController{1.0, 0.0, 0.0};
+  wpi::math::PIDController m_frontRightPIDController{1.0, 0.0, 0.0};
+  wpi::math::PIDController m_backLeftPIDController{1.0, 0.0, 0.0};
+  wpi::math::PIDController m_backRightPIDController{1.0, 0.0, 0.0};
 
-  frc::OnboardIMU m_imu{frc::OnboardIMU::kFlat};
+  wpi::OnboardIMU m_imu{wpi::OnboardIMU::kFlat};
 
-  frc::MecanumDriveKinematics m_kinematics{
+  wpi::math::MecanumDriveKinematics m_kinematics{
       m_frontLeftLocation, m_frontRightLocation, m_backLeftLocation,
       m_backRightLocation};
 
-  frc::MecanumDriveOdometry m_odometry{m_kinematics, m_imu.GetRotation2d(),
+  wpi::math::MecanumDriveOdometry m_odometry{m_kinematics, m_imu.GetRotation2d(),
                                        GetCurrentWheelDistances()};
 
   // Gains are for example purposes only - must be determined for your own
   // robot!
-  frc::SimpleMotorFeedforward m_feedforward{1_V, 3_V / 1_mps};
+  wpi::math::SimpleMotorFeedforward m_feedforward{1_V, 3_V / 1_mps};
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumDrive/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/MecanumDrive/cpp/Robot.cpp
index 7d802193e4..ccab39f64f 100644
--- a/wpilibcExamples/src/main/cpp/examples/MecanumDrive/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/MecanumDrive/cpp/Robot.cpp
@@ -11,13 +11,13 @@
  * This is a demo program showing how to use Mecanum control with the
  * MecanumDrive class.
  */
-class Robot : public frc::TimedRobot {
+class Robot : public wpi::TimedRobot {
  public:
   Robot() {
-    wpi::SendableRegistry::AddChild(&m_robotDrive, &m_frontLeft);
-    wpi::SendableRegistry::AddChild(&m_robotDrive, &m_rearLeft);
-    wpi::SendableRegistry::AddChild(&m_robotDrive, &m_frontRight);
-    wpi::SendableRegistry::AddChild(&m_robotDrive, &m_rearRight);
+    wpi::util::SendableRegistry::AddChild(&m_robotDrive, &m_frontLeft);
+    wpi::util::SendableRegistry::AddChild(&m_robotDrive, &m_rearLeft);
+    wpi::util::SendableRegistry::AddChild(&m_robotDrive, &m_frontRight);
+    wpi::util::SendableRegistry::AddChild(&m_robotDrive, &m_rearRight);
 
     // Invert the right side motors. You may need to change or remove this to
     // match your robot.
@@ -41,21 +41,21 @@ class Robot : public frc::TimedRobot {
 
   static constexpr int kJoystickChannel = 0;
 
-  frc::PWMSparkMax m_frontLeft{kFrontLeftChannel};
-  frc::PWMSparkMax m_rearLeft{kRearLeftChannel};
-  frc::PWMSparkMax m_frontRight{kFrontRightChannel};
-  frc::PWMSparkMax m_rearRight{kRearRightChannel};
-  frc::MecanumDrive m_robotDrive{
+  wpi::PWMSparkMax m_frontLeft{kFrontLeftChannel};
+  wpi::PWMSparkMax m_rearLeft{kRearLeftChannel};
+  wpi::PWMSparkMax m_frontRight{kFrontRightChannel};
+  wpi::PWMSparkMax m_rearRight{kRearRightChannel};
+  wpi::MecanumDrive m_robotDrive{
       [&](double output) { m_frontLeft.Set(output); },
       [&](double output) { m_rearLeft.Set(output); },
       [&](double output) { m_frontRight.Set(output); },
       [&](double output) { m_rearRight.Set(output); }};
 
-  frc::Joystick m_stick{kJoystickChannel};
+  wpi::Joystick m_stick{kJoystickChannel};
 };
 
 #ifndef RUNNING_FRC_TESTS
 int main() {
-  return frc::StartRobot();
+  return wpi::StartRobot();
 }
 #endif
diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/cpp/Drivetrain.cpp b/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/cpp/Drivetrain.cpp
index 75d69618e5..6d99b22f1d 100644
--- a/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/cpp/Drivetrain.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/cpp/Drivetrain.cpp
@@ -8,30 +8,30 @@
 
 #include "ExampleGlobalMeasurementSensor.hpp"
 
-frc::MecanumDriveWheelSpeeds Drivetrain::GetCurrentState() const {
-  return {units::meters_per_second_t{m_frontLeftEncoder.GetRate()},
-          units::meters_per_second_t{m_frontRightEncoder.GetRate()},
-          units::meters_per_second_t{m_backLeftEncoder.GetRate()},
-          units::meters_per_second_t{m_backRightEncoder.GetRate()}};
+wpi::math::MecanumDriveWheelSpeeds Drivetrain::GetCurrentState() const {
+  return {wpi::units::meters_per_second_t{m_frontLeftEncoder.GetRate()},
+          wpi::units::meters_per_second_t{m_frontRightEncoder.GetRate()},
+          wpi::units::meters_per_second_t{m_backLeftEncoder.GetRate()},
+          wpi::units::meters_per_second_t{m_backRightEncoder.GetRate()}};
 }
 
-frc::MecanumDriveWheelPositions Drivetrain::GetCurrentDistances() const {
-  return {units::meter_t{m_frontLeftEncoder.GetDistance()},
-          units::meter_t{m_frontRightEncoder.GetDistance()},
-          units::meter_t{m_backLeftEncoder.GetDistance()},
-          units::meter_t{m_backRightEncoder.GetDistance()}};
+wpi::math::MecanumDriveWheelPositions Drivetrain::GetCurrentDistances() const {
+  return {wpi::units::meter_t{m_frontLeftEncoder.GetDistance()},
+          wpi::units::meter_t{m_frontRightEncoder.GetDistance()},
+          wpi::units::meter_t{m_backLeftEncoder.GetDistance()},
+          wpi::units::meter_t{m_backRightEncoder.GetDistance()}};
 }
 
-void Drivetrain::SetSpeeds(const frc::MecanumDriveWheelSpeeds& wheelSpeeds) {
-  std::function
+void Drivetrain::SetSpeeds(const wpi::math::MecanumDriveWheelSpeeds& wheelSpeeds) {
+  std::function
       calcAndSetSpeeds = [&m_feedforward = m_feedforward](
-                             units::meters_per_second_t speed,
+                             wpi::units::meters_per_second_t speed,
                              const auto& encoder, auto& controller,
                              auto& motor) {
         auto feedforward = m_feedforward.Calculate(speed);
         double output = controller.Calculate(encoder.GetRate(), speed.value());
-        motor.SetVoltage(units::volt_t{output} + feedforward);
+        motor.SetVoltage(wpi::units::volt_t{output} + feedforward);
       };
 
   calcAndSetSpeeds(wheelSpeeds.frontLeft, m_frontLeftEncoder,
@@ -44,11 +44,11 @@ void Drivetrain::SetSpeeds(const frc::MecanumDriveWheelSpeeds& wheelSpeeds) {
                    m_backRightPIDController, m_backRightMotor);
 }
 
-void Drivetrain::Drive(units::meters_per_second_t xSpeed,
-                       units::meters_per_second_t ySpeed,
-                       units::radians_per_second_t rot, bool fieldRelative,
-                       units::second_t period) {
-  frc::ChassisSpeeds chassisSpeeds{xSpeed, ySpeed, rot};
+void Drivetrain::Drive(wpi::units::meters_per_second_t xSpeed,
+                       wpi::units::meters_per_second_t ySpeed,
+                       wpi::units::radians_per_second_t rot, bool fieldRelative,
+                       wpi::units::second_t period) {
+  wpi::math::ChassisSpeeds chassisSpeeds{xSpeed, ySpeed, rot};
   if (fieldRelative) {
     chassisSpeeds = chassisSpeeds.ToRobotRelative(
         m_poseEstimator.GetEstimatedPosition().Rotation());
@@ -68,5 +68,5 @@ void Drivetrain::UpdateOdometry() {
   m_poseEstimator.AddVisionMeasurement(
       ExampleGlobalMeasurementSensor::GetEstimatedGlobalPose(
           m_poseEstimator.GetEstimatedPosition()),
-      frc::Timer::GetTimestamp() - 0.3_s);
+      wpi::Timer::GetTimestamp() - 0.3_s);
 }
diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/cpp/Robot.cpp
index dd29ae5889..eb5a574ed2 100644
--- a/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/cpp/Robot.cpp
@@ -8,7 +8,7 @@
 
 #include "Drivetrain.hpp"
 
-class Robot : public frc::TimedRobot {
+class Robot : public wpi::TimedRobot {
  public:
   void AutonomousPeriodic() override {
     DriveWithJoystick(false);
@@ -18,14 +18,14 @@ class Robot : public frc::TimedRobot {
   void TeleopPeriodic() override { DriveWithJoystick(true); }
 
  private:
-  frc::XboxController m_controller{0};
+  wpi::XboxController m_controller{0};
   Drivetrain m_mecanum;
 
   // Slew rate limiters to make joystick inputs more gentle; 1/3 sec from 0
   // to 1.
-  frc::SlewRateLimiter m_xspeedLimiter{3 / 1_s};
-  frc::SlewRateLimiter m_yspeedLimiter{3 / 1_s};
-  frc::SlewRateLimiter m_rotLimiter{3 / 1_s};
+  wpi::math::SlewRateLimiter m_xspeedLimiter{3 / 1_s};
+  wpi::math::SlewRateLimiter m_yspeedLimiter{3 / 1_s};
+  wpi::math::SlewRateLimiter m_rotLimiter{3 / 1_s};
 
   void DriveWithJoystick(bool fieldRelative) {
     // Get the x speed. We are inverting this because Xbox controllers return
@@ -52,6 +52,6 @@ class Robot : public frc::TimedRobot {
 
 #ifndef RUNNING_FRC_TESTS
 int main() {
-  return frc::StartRobot();
+  return wpi::StartRobot();
 }
 #endif
diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/include/Drivetrain.hpp b/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/include/Drivetrain.hpp
index c94027326d..da042ca8b7 100644
--- a/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/include/Drivetrain.hpp
+++ b/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/include/Drivetrain.hpp
@@ -31,52 +31,52 @@ class Drivetrain {
     m_backRightMotor.SetInverted(true);
   }
 
-  frc::MecanumDriveWheelSpeeds GetCurrentState() const;
-  frc::MecanumDriveWheelPositions GetCurrentDistances() const;
-  void SetSpeeds(const frc::MecanumDriveWheelSpeeds& wheelSpeeds);
-  void Drive(units::meters_per_second_t xSpeed,
-             units::meters_per_second_t ySpeed, units::radians_per_second_t rot,
-             bool fieldRelative, units::second_t period);
+  wpi::math::MecanumDriveWheelSpeeds GetCurrentState() const;
+  wpi::math::MecanumDriveWheelPositions GetCurrentDistances() const;
+  void SetSpeeds(const wpi::math::MecanumDriveWheelSpeeds& wheelSpeeds);
+  void Drive(wpi::units::meters_per_second_t xSpeed,
+             wpi::units::meters_per_second_t ySpeed, wpi::units::radians_per_second_t rot,
+             bool fieldRelative, wpi::units::second_t period);
   void UpdateOdometry();
 
   static constexpr auto kMaxSpeed = 3.0_mps;  // 3 meters per second
-  static constexpr units::radians_per_second_t kMaxAngularSpeed{
+  static constexpr wpi::units::radians_per_second_t kMaxAngularSpeed{
       std::numbers::pi};  // 1/2 rotation per second
 
  private:
-  frc::PWMSparkMax m_frontLeftMotor{1};
-  frc::PWMSparkMax m_frontRightMotor{2};
-  frc::PWMSparkMax m_backLeftMotor{3};
-  frc::PWMSparkMax m_backRightMotor{4};
+  wpi::PWMSparkMax m_frontLeftMotor{1};
+  wpi::PWMSparkMax m_frontRightMotor{2};
+  wpi::PWMSparkMax m_backLeftMotor{3};
+  wpi::PWMSparkMax m_backRightMotor{4};
 
-  frc::Encoder m_frontLeftEncoder{0, 1};
-  frc::Encoder m_frontRightEncoder{2, 3};
-  frc::Encoder m_backLeftEncoder{4, 5};
-  frc::Encoder m_backRightEncoder{6, 7};
+  wpi::Encoder m_frontLeftEncoder{0, 1};
+  wpi::Encoder m_frontRightEncoder{2, 3};
+  wpi::Encoder m_backLeftEncoder{4, 5};
+  wpi::Encoder m_backRightEncoder{6, 7};
 
-  frc::Translation2d m_frontLeftLocation{0.381_m, 0.381_m};
-  frc::Translation2d m_frontRightLocation{0.381_m, -0.381_m};
-  frc::Translation2d m_backLeftLocation{-0.381_m, 0.381_m};
-  frc::Translation2d m_backRightLocation{-0.381_m, -0.381_m};
+  wpi::math::Translation2d m_frontLeftLocation{0.381_m, 0.381_m};
+  wpi::math::Translation2d m_frontRightLocation{0.381_m, -0.381_m};
+  wpi::math::Translation2d m_backLeftLocation{-0.381_m, 0.381_m};
+  wpi::math::Translation2d m_backRightLocation{-0.381_m, -0.381_m};
 
-  frc::PIDController m_frontLeftPIDController{1.0, 0.0, 0.0};
-  frc::PIDController m_frontRightPIDController{1.0, 0.0, 0.0};
-  frc::PIDController m_backLeftPIDController{1.0, 0.0, 0.0};
-  frc::PIDController m_backRightPIDController{1.0, 0.0, 0.0};
+  wpi::math::PIDController m_frontLeftPIDController{1.0, 0.0, 0.0};
+  wpi::math::PIDController m_frontRightPIDController{1.0, 0.0, 0.0};
+  wpi::math::PIDController m_backLeftPIDController{1.0, 0.0, 0.0};
+  wpi::math::PIDController m_backRightPIDController{1.0, 0.0, 0.0};
 
-  frc::OnboardIMU m_imu{frc::OnboardIMU::kFlat};
+  wpi::OnboardIMU m_imu{wpi::OnboardIMU::kFlat};
 
-  frc::MecanumDriveKinematics m_kinematics{
+  wpi::math::MecanumDriveKinematics m_kinematics{
       m_frontLeftLocation, m_frontRightLocation, m_backLeftLocation,
       m_backRightLocation};
 
   // Gains are for example purposes only - must be determined for your own
   // robot!
-  frc::SimpleMotorFeedforward m_feedforward{1_V, 3_V / 1_mps};
+  wpi::math::SimpleMotorFeedforward m_feedforward{1_V, 3_V / 1_mps};
 
   // Gains are for example purposes only - must be determined for your own
   // robot!
-  frc::MecanumDrivePoseEstimator m_poseEstimator{
+  wpi::math::MecanumDrivePoseEstimator m_poseEstimator{
       m_kinematics,  m_imu.GetRotation2d(), GetCurrentDistances(),
-      frc::Pose2d{}, {0.1, 0.1, 0.1},       {0.1, 0.1, 0.1}};
+      wpi::math::Pose2d{}, {0.1, 0.1, 0.1},       {0.1, 0.1, 0.1}};
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/include/ExampleGlobalMeasurementSensor.hpp b/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/include/ExampleGlobalMeasurementSensor.hpp
index d4f9b4e52f..16f4123f08 100644
--- a/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/include/ExampleGlobalMeasurementSensor.hpp
+++ b/wpilibcExamples/src/main/cpp/examples/MecanumDrivePoseEstimator/include/ExampleGlobalMeasurementSensor.hpp
@@ -13,12 +13,12 @@
  */
 class ExampleGlobalMeasurementSensor {
  public:
-  static frc::Pose2d GetEstimatedGlobalPose(
-      const frc::Pose2d& estimatedRobotPose) {
-    auto randVec = frc::MakeWhiteNoiseVector(0.1, 0.1, 0.1);
-    return frc::Pose2d{estimatedRobotPose.X() + units::meter_t{randVec(0)},
-                       estimatedRobotPose.Y() + units::meter_t{randVec(1)},
+  static wpi::math::Pose2d GetEstimatedGlobalPose(
+      const wpi::math::Pose2d& estimatedRobotPose) {
+    auto randVec = wpi::math::MakeWhiteNoiseVector(0.1, 0.1, 0.1);
+    return wpi::math::Pose2d{estimatedRobotPose.X() + wpi::units::meter_t{randVec(0)},
+                       estimatedRobotPose.Y() + wpi::units::meter_t{randVec(1)},
                        estimatedRobotPose.Rotation() +
-                           frc::Rotation2d{units::radian_t{randVec(2)}}};
+                           wpi::math::Rotation2d{wpi::units::radian_t{randVec(2)}}};
   }
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/Mechanism2d/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/Mechanism2d/cpp/Robot.cpp
index 7d06b68678..25e5d7749a 100644
--- a/wpilibcExamples/src/main/cpp/examples/Mechanism2d/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/Mechanism2d/cpp/Robot.cpp
@@ -25,7 +25,7 @@
  * the container out of scope - the appended nodes will be recursively
  * destructed!
  */
-class Robot : public frc::TimedRobot {
+class Robot : public wpi::TimedRobot {
   static constexpr double kMetersPerPulse = 0.01;
   static constexpr double kElevatorMinimumLength = 0.5;
 
@@ -34,14 +34,14 @@ class Robot : public frc::TimedRobot {
     m_elevatorEncoder.SetDistancePerPulse(kMetersPerPulse);
 
     // publish to dashboard
-    frc::SmartDashboard::PutData("Mech2d", &m_mech);
+    wpi::SmartDashboard::PutData("Mech2d", &m_mech);
   }
 
   void RobotPeriodic() override {
     // update the dashboard mechanism's state
     m_elevator->SetLength(kElevatorMinimumLength +
                           m_elevatorEncoder.GetDistance());
-    m_wrist->SetAngle(units::degree_t{m_wristPotentiometer.Get()});
+    m_wrist->SetAngle(wpi::units::degree_t{m_wristPotentiometer.Get()});
   }
 
   void TeleopPeriodic() override {
@@ -50,27 +50,27 @@ class Robot : public frc::TimedRobot {
   }
 
  private:
-  frc::PWMSparkMax m_elevatorMotor{0};
-  frc::PWMSparkMax m_wristMotor{1};
-  frc::Encoder m_elevatorEncoder{0, 1};
-  frc::AnalogPotentiometer m_wristPotentiometer{1, 90};
-  frc::Joystick m_joystick{0};
+  wpi::PWMSparkMax m_elevatorMotor{0};
+  wpi::PWMSparkMax m_wristMotor{1};
+  wpi::Encoder m_elevatorEncoder{0, 1};
+  wpi::AnalogPotentiometer m_wristPotentiometer{1, 90};
+  wpi::Joystick m_joystick{0};
 
   // the main mechanism object
-  frc::Mechanism2d m_mech{3, 3};
+  wpi::Mechanism2d m_mech{3, 3};
   // the mechanism root node
-  frc::MechanismRoot2d* m_root = m_mech.GetRoot("climber", 2, 0);
+  wpi::MechanismRoot2d* m_root = m_mech.GetRoot("climber", 2, 0);
   // MechanismLigament2d objects represent each "section"/"stage" of the
   // mechanism, and are based off the root node or another ligament object
-  frc::MechanismLigament2d* m_elevator =
-      m_root->Append("elevator", 1, 90_deg);
-  frc::MechanismLigament2d* m_wrist =
-      m_elevator->Append(
-          "wrist", 0.5, 90_deg, 6, frc::Color8Bit{frc::Color::kPurple});
+  wpi::MechanismLigament2d* m_elevator =
+      m_root->Append("elevator", 1, 90_deg);
+  wpi::MechanismLigament2d* m_wrist =
+      m_elevator->Append(
+          "wrist", 0.5, 90_deg, 6, wpi::Color8Bit{wpi::Color::kPurple});
 };
 
 #ifndef RUNNING_FRC_TESTS
 int main() {
-  return frc::StartRobot();
+  return wpi::StartRobot();
 }
 #endif
diff --git a/wpilibcExamples/src/main/cpp/examples/MotorControl/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/MotorControl/cpp/Robot.cpp
index 149681af48..77806a97ce 100644
--- a/wpilibcExamples/src/main/cpp/examples/MotorControl/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/MotorControl/cpp/Robot.cpp
@@ -21,7 +21,7 @@
  * In addition, the encoder value of an encoder connected to ports 0 and 1 is
  * consistently sent to the Dashboard.
  */
-class Robot : public frc::TimedRobot {
+class Robot : public wpi::TimedRobot {
  public:
   void TeleopPeriodic() override { m_motor.Set(m_stick.GetY()); }
 
@@ -30,7 +30,7 @@ class Robot : public frc::TimedRobot {
    * robot mode.
    */
   void RobotPeriodic() override {
-    frc::SmartDashboard::PutNumber("Encoder", m_encoder.GetDistance());
+    wpi::SmartDashboard::PutNumber("Encoder", m_encoder.GetDistance());
   }
 
   Robot() {
@@ -40,13 +40,13 @@ class Robot : public frc::TimedRobot {
   }
 
  private:
-  frc::Joystick m_stick{0};
-  frc::PWMSparkMax m_motor{0};
-  frc::Encoder m_encoder{0, 1};
+  wpi::Joystick m_stick{0};
+  wpi::PWMSparkMax m_motor{0};
+  wpi::Encoder m_encoder{0, 1};
 };
 
 #ifndef RUNNING_FRC_TESTS
 int main() {
-  return frc::StartRobot();
+  return wpi::StartRobot();
 }
 #endif
diff --git a/wpilibcExamples/src/main/cpp/examples/PotentiometerPID/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/PotentiometerPID/cpp/Robot.cpp
index 902b4a53a0..d1ad54c4c9 100644
--- a/wpilibcExamples/src/main/cpp/examples/PotentiometerPID/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/PotentiometerPID/cpp/Robot.cpp
@@ -12,7 +12,7 @@ void Robot::TeleopInit() {
 
 void Robot::TeleopPeriodic() {
   // Read from the sensor
-  units::meter_t position = units::meter_t{m_potentiometer.Get()};
+  wpi::units::meter_t position = wpi::units::meter_t{m_potentiometer.Get()};
 
   // Run the PID Controller
   double pidOut = m_pidController.Calculate(position.value());
@@ -31,6 +31,6 @@ void Robot::TeleopPeriodic() {
 
 #ifndef RUNNING_FRC_TESTS
 int main() {
-  return frc::StartRobot();
+  return wpi::StartRobot();
 }
 #endif
diff --git a/wpilibcExamples/src/main/cpp/examples/PotentiometerPID/include/Robot.hpp b/wpilibcExamples/src/main/cpp/examples/PotentiometerPID/include/Robot.hpp
index 6d1bab4d76..e812187800 100644
--- a/wpilibcExamples/src/main/cpp/examples/PotentiometerPID/include/Robot.hpp
+++ b/wpilibcExamples/src/main/cpp/examples/PotentiometerPID/include/Robot.hpp
@@ -18,7 +18,7 @@
  * PID controller to reach and maintain position setpoints on an elevator
  * mechanism.
  */
-class Robot : public frc::TimedRobot {
+class Robot : public wpi::TimedRobot {
  public:
   void TeleopInit() override;
   void TeleopPeriodic() override;
@@ -28,10 +28,10 @@ class Robot : public frc::TimedRobot {
   static constexpr int kJoystickChannel = 3;
 
   // The elevator can move 1.5 meters from top to bottom
-  static constexpr units::meter_t kFullHeight = 1.5_m;
+  static constexpr wpi::units::meter_t kFullHeight = 1.5_m;
 
   // Bottom, middle, and top elevator setpoints
-  static constexpr std::array kSetpoints = {
+  static constexpr std::array kSetpoints = {
       {0.2_m, 0.8_m, 1.4_m}};
 
  private:
@@ -45,11 +45,11 @@ class Robot : public frc::TimedRobot {
   static constexpr double kD = 0.25;
 
   // Scaling is handled internally
-  frc::AnalogPotentiometer m_potentiometer{kPotChannel, kFullHeight.value()};
+  wpi::AnalogPotentiometer m_potentiometer{kPotChannel, kFullHeight.value()};
 
-  frc::PWMSparkMax m_elevatorMotor{kMotorChannel};
-  frc::PIDController m_pidController{kP, kI, kD};
-  frc::Joystick m_joystick{kJoystickChannel};
+  wpi::PWMSparkMax m_elevatorMotor{kMotorChannel};
+  wpi::math::PIDController m_pidController{kP, kI, kD};
+  wpi::Joystick m_joystick{kJoystickChannel};
 
   size_t m_index;
 };
diff --git a/wpilibcExamples/src/main/cpp/examples/QuickVision/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/QuickVision/cpp/Robot.cpp
index 34447b0838..b19c972486 100644
--- a/wpilibcExamples/src/main/cpp/examples/QuickVision/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/QuickVision/cpp/Robot.cpp
@@ -13,11 +13,11 @@
  * the easiest way to get camera images to the dashboard. Just add this to the
  * robot class constructor.
  */
-class Robot : public frc::TimedRobot {
+class Robot : public wpi::TimedRobot {
  public:
   Robot() {
 #if defined(__linux__) || defined(_WIN32)
-    frc::CameraServer::StartAutomaticCapture();
+    wpi::CameraServer::StartAutomaticCapture();
 #else
     std::fputs("Vision only available on Linux or Windows.\n", stderr);
     std::fflush(stderr);
@@ -27,6 +27,6 @@ class Robot : public frc::TimedRobot {
 
 #ifndef RUNNING_FRC_TESTS
 int main() {
-  return frc::StartRobot();
+  return wpi::StartRobot();
 }
 #endif
diff --git a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/RapidReactCommandBot.cpp b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/RapidReactCommandBot.cpp
index baf2a58586..dcc4d4f575 100644
--- a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/RapidReactCommandBot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/RapidReactCommandBot.cpp
@@ -32,7 +32,7 @@ void RapidReactCommandBot::ConfigureBindings() {
 
   // Fire the shooter with the A button
   m_driverController.A().OnTrue(
-      frc2::cmd::Parallel(
+      wpi::cmd::cmd::Parallel(
           m_shooter.ShootCommand(ShooterConstants::kShooterTarget),
           m_storage.RunCommand())
           // Since we composed this inline we should give it a name
@@ -43,7 +43,7 @@ void RapidReactCommandBot::ConfigureBindings() {
       m_pneumatics.DisableCompressorCommand());
 }
 
-frc2::CommandPtr RapidReactCommandBot::GetAutonomousCommand() {
+wpi::cmd::CommandPtr RapidReactCommandBot::GetAutonomousCommand() {
   return m_drive
       .DriveDistanceCommand(AutoConstants::kDriveDistance,
                             AutoConstants::kDriveSpeed)
diff --git a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/Robot.cpp
index b70b1c37f3..8bccf119a5 100644
--- a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/Robot.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/Robot.cpp
@@ -15,7 +15,7 @@ void Robot::RobotPeriodic() {
   // finished or interrupted commands, and running subsystem Periodic() methods.
   // This must be called from the robot's periodic block in order for anything
   // in the Command-based framework to work.
-  frc2::CommandScheduler::GetInstance().Run();
+  wpi::cmd::CommandScheduler::GetInstance().Run();
 }
 
 void Robot::DisabledInit() {}
@@ -26,7 +26,7 @@ void Robot::AutonomousInit() {
   m_autonomousCommand = m_robot.GetAutonomousCommand();
 
   if (m_autonomousCommand) {
-    frc2::CommandScheduler::GetInstance().Schedule(m_autonomousCommand.value());
+    wpi::cmd::CommandScheduler::GetInstance().Schedule(m_autonomousCommand.value());
   }
 }
 
@@ -46,13 +46,13 @@ void Robot::TeleopPeriodic() {}
 
 void Robot::TestInit() {
   // Cancels all running commands at the start of test mode.
-  frc2::CommandScheduler::GetInstance().CancelAll();
+  wpi::cmd::CommandScheduler::GetInstance().CancelAll();
 }
 
 void Robot::TestPeriodic() {}
 
 #ifndef RUNNING_FRC_TESTS
 int main() {
-  return frc::StartRobot();
+  return wpi::StartRobot();
 }
 #endif
diff --git a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Drive.cpp b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Drive.cpp
index 1c4beb469b..663f5b6772 100644
--- a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Drive.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Drive.cpp
@@ -10,8 +10,8 @@
 #include 
 
 Drive::Drive() {
-  wpi::SendableRegistry::AddChild(&m_drive, &m_leftLeader);
-  wpi::SendableRegistry::AddChild(&m_drive, &m_rightLeader);
+  wpi::util::SendableRegistry::AddChild(&m_drive, &m_leftLeader);
+  wpi::util::SendableRegistry::AddChild(&m_drive, &m_rightLeader);
 
   m_leftLeader.AddFollower(m_leftFollower);
   m_rightLeader.AddFollower(m_rightFollower);
@@ -34,7 +34,7 @@ Drive::Drive() {
                             DriveConstants::kTurnRateTolerance);
 }
 
-frc2::CommandPtr Drive::ArcadeDriveCommand(std::function fwd,
+wpi::cmd::CommandPtr Drive::ArcadeDriveCommand(std::function fwd,
                                            std::function rot) {
   return Run([this, fwd = std::move(fwd), rot = std::move(rot)] {
            m_drive.ArcadeDrive(fwd(), rot());
@@ -42,7 +42,7 @@ frc2::CommandPtr Drive::ArcadeDriveCommand(std::function fwd,
       .WithName("ArcadeDrive");
 }
 
-frc2::CommandPtr Drive::DriveDistanceCommand(units::meter_t distance,
+wpi::cmd::CommandPtr Drive::DriveDistanceCommand(wpi::units::meter_t distance,
                                              double speed) {
   return RunOnce([this] {
            // Reset encoders at the start of the command
@@ -52,15 +52,15 @@ frc2::CommandPtr Drive::DriveDistanceCommand(units::meter_t distance,
       // Drive forward at specified speed
       .AndThen(Run([this, speed] { m_drive.ArcadeDrive(speed, 0.0); }))
       .Until([this, distance] {
-        return units::math::max(units::meter_t(m_leftEncoder.GetDistance()),
-                                units::meter_t(m_rightEncoder.GetDistance())) >=
+        return wpi::units::math::max(wpi::units::meter_t(m_leftEncoder.GetDistance()),
+                                wpi::units::meter_t(m_rightEncoder.GetDistance())) >=
                distance;
       })
       // Stop the drive when the command ends
       .FinallyDo([this](bool interrupted) { m_drive.StopMotor(); });
 }
 
-frc2::CommandPtr Drive::TurnToAngleCommand(units::degree_t angle) {
+wpi::cmd::CommandPtr Drive::TurnToAngleCommand(wpi::units::degree_t angle) {
   return StartRun(
              [this] { m_controller.Reset(m_imu.GetRotation2d().Degrees()); },
              [this, angle] {
@@ -71,7 +71,7 @@ frc2::CommandPtr Drive::TurnToAngleCommand(units::degree_t angle) {
                           // normalize it to [-1, 1]
                           m_feedforward.Calculate(
                               m_controller.GetSetpoint().velocity) /
-                              frc::RobotController::GetBatteryVoltage());
+                              wpi::RobotController::GetBatteryVoltage());
              })
       .Until([this] { return m_controller.AtGoal(); })
       .FinallyDo([this] { m_drive.ArcadeDrive(0, 0); });
diff --git a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Intake.cpp b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Intake.cpp
index 31feb4d848..b696c8f0f4 100644
--- a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Intake.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Intake.cpp
@@ -4,16 +4,16 @@
 
 #include "subsystems/Intake.hpp"
 
-frc2::CommandPtr Intake::IntakeCommand() {
-  return RunOnce([this] { m_piston.Set(frc::DoubleSolenoid::kForward); })
+wpi::cmd::CommandPtr Intake::IntakeCommand() {
+  return RunOnce([this] { m_piston.Set(wpi::DoubleSolenoid::kForward); })
       .AndThen(Run([this] { m_motor.Set(1.0); }))
       .WithName("Intake");
 }
 
-frc2::CommandPtr Intake::RetractCommand() {
+wpi::cmd::CommandPtr Intake::RetractCommand() {
   return RunOnce([this] {
            m_motor.Disable();
-           m_piston.Set(frc::DoubleSolenoid::kReverse);
+           m_piston.Set(wpi::DoubleSolenoid::kReverse);
          })
       .WithName("Retract");
 }
diff --git a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Pneumatics.cpp b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Pneumatics.cpp
index 3f5fac46a8..ddd3ac76be 100644
--- a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Pneumatics.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Pneumatics.cpp
@@ -6,7 +6,7 @@
 
 Pneumatics::Pneumatics() {}
 
-frc2::CommandPtr Pneumatics::DisableCompressorCommand() {
+wpi::cmd::CommandPtr Pneumatics::DisableCompressorCommand() {
   return StartEnd(
       [&] {
         // Disable closed-loop mode on the compressor.
@@ -20,8 +20,8 @@ frc2::CommandPtr Pneumatics::DisableCompressorCommand() {
       });
 }
 
-units::pounds_per_square_inch_t Pneumatics::GetPressure() {
+wpi::units::pounds_per_square_inch_t Pneumatics::GetPressure() {
   // Get the pressure (in PSI) from an analog pressure sensor connected to
   // the RIO.
-  return units::pounds_per_square_inch_t{m_pressureTransducer.Get()};
+  return wpi::units::pounds_per_square_inch_t{m_pressureTransducer.Get()};
 }
diff --git a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Shooter.cpp b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Shooter.cpp
index 8f5d0ac648..60ba31b7f2 100644
--- a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Shooter.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Shooter.cpp
@@ -19,19 +19,19 @@ Shooter::Shooter() {
                         .WithName("Idle"));
 }
 
-frc2::CommandPtr Shooter::ShootCommand(units::turns_per_second_t setpoint) {
-  return frc2::cmd::Parallel(
+wpi::cmd::CommandPtr Shooter::ShootCommand(wpi::units::turns_per_second_t setpoint) {
+  return wpi::cmd::cmd::Parallel(
              // Run the shooter flywheel at the desired setpoint using
              // feedforward and feedback
              Run([this, setpoint] {
                m_shooterMotor.SetVoltage(
                    m_shooterFeedforward.Calculate(setpoint) +
-                   units::volt_t(m_shooterFeedback.Calculate(
+                   wpi::units::volt_t(m_shooterFeedback.Calculate(
                        m_shooterEncoder.GetRate(), setpoint.value())));
              }),
              // Wait until the shooter has reached the setpoint, and then
              // run the feeder
-             frc2::cmd::WaitUntil([this] {
+             wpi::cmd::cmd::WaitUntil([this] {
                return m_shooterFeedback.AtSetpoint();
              }).AndThen([this] { m_feederMotor.Set(1.0); }))
       .WithName("Shoot");
diff --git a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Storage.cpp b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Storage.cpp
index ce2105275f..b6adc60e91 100644
--- a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Storage.cpp
+++ b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/cpp/subsystems/Storage.cpp
@@ -9,6 +9,6 @@ Storage::Storage() {
       RunOnce([this] { m_motor.Disable(); }).AndThen([] {}).WithName("Idle"));
 }
 
-frc2::CommandPtr Storage::RunCommand() {
+wpi::cmd::CommandPtr Storage::RunCommand() {
   return Run([this] { m_motor.Set(1.0); }).WithName("Run");
 }
diff --git a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/Constants.hpp b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/Constants.hpp
index 1639e36aba..caa3d0fd54 100644
--- a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/Constants.hpp
+++ b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/Constants.hpp
@@ -24,7 +24,7 @@ inline constexpr bool kLeftEncoderReversed = false;
 inline constexpr bool kRightEncoderReversed = true;
 
 inline constexpr double kEncoderCPR = 1024;
-inline constexpr units::meter_t kWheelDiameter = 6_in;
+inline constexpr wpi::units::meter_t kWheelDiameter = 6_in;
 inline constexpr double kEncoderDistancePerPulse =
     // Assumes the encoders are directly mounted on the wheel shafts
     ((kWheelDiameter * std::numbers::pi) / kEncoderCPR).value();
@@ -76,7 +76,7 @@ inline constexpr auto kShooterTolerance = 50_tps;
 // robot.
 inline constexpr double kP = 1;
 
-inline constexpr units::volt_t kS = 0.05_V;
+inline constexpr wpi::units::volt_t kS = 0.05_V;
 // Should have value 12V at free speed
 inline constexpr auto kV = 12_V / kShooterFree;
 
@@ -88,7 +88,7 @@ inline constexpr int kDriverControllerPort = 0;
 }  // namespace OIConstants
 
 namespace AutoConstants {
-constexpr units::second_t kTimeout = 3_s;
-constexpr units::meter_t kDriveDistance = 2_m;
+constexpr wpi::units::second_t kTimeout = 3_s;
+constexpr wpi::units::meter_t kDriveDistance = 2_m;
 constexpr double kDriveSpeed = 0.5;
 }  // namespace AutoConstants
diff --git a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/RapidReactCommandBot.hpp b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/RapidReactCommandBot.hpp
index ee40f47131..bec4bf5c59 100644
--- a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/RapidReactCommandBot.hpp
+++ b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/RapidReactCommandBot.hpp
@@ -29,7 +29,7 @@ class RapidReactCommandBot {
    *
    * 

Should be called in the robot class constructor. * - *

Event binding methods are available on the frc2::Trigger class. + *

Event binding methods are available on the wpi::cmd::Trigger class. */ void ConfigureBindings(); @@ -38,7 +38,7 @@ class RapidReactCommandBot { * *

Scheduled during Robot::AutonomousInit(). */ - frc2::CommandPtr GetAutonomousCommand(); + wpi::cmd::CommandPtr GetAutonomousCommand(); private: // The robot's subsystems @@ -49,6 +49,6 @@ class RapidReactCommandBot { Pneumatics m_pneumatics; // The driver's controller - frc2::CommandXboxController m_driverController{ + wpi::cmd::CommandXboxController m_driverController{ OIConstants::kDriverControllerPort}; }; diff --git a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/Robot.hpp b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/Robot.hpp index 00b67e52e1..eff1a55b71 100644 --- a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/Robot.hpp +++ b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/Robot.hpp @@ -11,7 +11,7 @@ #include "RapidReactCommandBot.hpp" -class Robot : public frc::TimedRobot { +class Robot : public wpi::TimedRobot { public: Robot(); void RobotPeriodic() override; @@ -26,5 +26,5 @@ class Robot : public frc::TimedRobot { private: RapidReactCommandBot m_robot; - std::optional m_autonomousCommand; + std::optional m_autonomousCommand; }; diff --git a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Drive.hpp b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Drive.hpp index 332d084c76..9e46055379 100644 --- a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Drive.hpp +++ b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Drive.hpp @@ -19,7 +19,7 @@ #include "Constants.hpp" -class Drive : public frc2::SubsystemBase { +class Drive : public wpi::cmd::SubsystemBase { public: Drive(); /** @@ -28,7 +28,7 @@ class Drive : public frc2::SubsystemBase { * @param fwd the commanded forward movement * @param rot the commanded rotation */ - frc2::CommandPtr ArcadeDriveCommand(std::function fwd, + wpi::cmd::CommandPtr ArcadeDriveCommand(std::function fwd, std::function rot); /** @@ -38,7 +38,7 @@ class Drive : public frc2::SubsystemBase { * @param distance The distance to drive forward in meters * @param speed The fraction of max speed at which to drive */ - frc2::CommandPtr DriveDistanceCommand(units::meter_t distance, double speed); + wpi::cmd::CommandPtr DriveDistanceCommand(wpi::units::meter_t distance, double speed); /** * Returns a command that turns to robot to the specified angle using a motion @@ -46,32 +46,32 @@ class Drive : public frc2::SubsystemBase { * * @param angle The angle to turn to */ - frc2::CommandPtr TurnToAngleCommand(units::degree_t angle); + wpi::cmd::CommandPtr TurnToAngleCommand(wpi::units::degree_t angle); private: - frc::PWMSparkMax m_leftLeader{DriveConstants::kLeftMotor1Port}; - frc::PWMSparkMax m_leftFollower{DriveConstants::kLeftMotor2Port}; - frc::PWMSparkMax m_rightLeader{DriveConstants::kRightMotor1Port}; - frc::PWMSparkMax m_rightFollower{DriveConstants::kRightMotor2Port}; + wpi::PWMSparkMax m_leftLeader{DriveConstants::kLeftMotor1Port}; + wpi::PWMSparkMax m_leftFollower{DriveConstants::kLeftMotor2Port}; + wpi::PWMSparkMax m_rightLeader{DriveConstants::kRightMotor1Port}; + wpi::PWMSparkMax m_rightFollower{DriveConstants::kRightMotor2Port}; - frc::DifferentialDrive m_drive{ + wpi::DifferentialDrive m_drive{ [&](double output) { m_leftLeader.Set(output); }, [&](double output) { m_rightLeader.Set(output); }}; - frc::Encoder m_leftEncoder{DriveConstants::kLeftEncoderPorts[0], + wpi::Encoder m_leftEncoder{DriveConstants::kLeftEncoderPorts[0], DriveConstants::kLeftEncoderPorts[1], DriveConstants::kLeftEncoderReversed}; - frc::Encoder m_rightEncoder{DriveConstants::kRightEncoderPorts[0], + wpi::Encoder m_rightEncoder{DriveConstants::kRightEncoderPorts[0], DriveConstants::kRightEncoderPorts[1], DriveConstants::kRightEncoderReversed}; - frc::OnboardIMU m_imu{frc::OnboardIMU::kFlat}; + wpi::OnboardIMU m_imu{wpi::OnboardIMU::kFlat}; - frc::ProfiledPIDController m_controller{ + wpi::math::ProfiledPIDController m_controller{ DriveConstants::kTurnP, DriveConstants::kTurnI, DriveConstants::kTurnD, {DriveConstants::kMaxTurnRate, DriveConstants::kMaxTurnAcceleration}}; - frc::SimpleMotorFeedforward m_feedforward{ + wpi::math::SimpleMotorFeedforward m_feedforward{ DriveConstants::ks, DriveConstants::kv, DriveConstants::ka}; }; diff --git a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Intake.hpp b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Intake.hpp index 0b460db465..71addb4f6a 100644 --- a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Intake.hpp +++ b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Intake.hpp @@ -13,22 +13,22 @@ #include "Constants.hpp" -class Intake : public frc2::SubsystemBase { +class Intake : public wpi::cmd::SubsystemBase { public: Intake() = default; /** Returns a command that deploys the intake, and then runs the intake motor * indefinitely. */ - frc2::CommandPtr IntakeCommand(); + wpi::cmd::CommandPtr IntakeCommand(); /** Returns a command that turns off and retracts the intake. */ - frc2::CommandPtr RetractCommand(); + wpi::cmd::CommandPtr RetractCommand(); private: - frc::PWMSparkMax m_motor{IntakeConstants::kMotorPort}; + wpi::PWMSparkMax m_motor{IntakeConstants::kMotorPort}; // Double solenoid connected to two channels of a PCM with the default CAN ID - frc::DoubleSolenoid m_piston{0, frc::PneumaticsModuleType::CTREPCM, + wpi::DoubleSolenoid m_piston{0, wpi::PneumaticsModuleType::CTREPCM, IntakeConstants::kSolenoidPorts[0], IntakeConstants::kSolenoidPorts[1]}; }; diff --git a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Pneumatics.hpp b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Pneumatics.hpp index c97c61b15d..0faba9eea5 100644 --- a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Pneumatics.hpp +++ b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Pneumatics.hpp @@ -13,18 +13,18 @@ #include "Constants.hpp" -class Pneumatics : frc2::SubsystemBase { +class Pneumatics : wpi::cmd::SubsystemBase { public: Pneumatics(); /** Returns a command that disables the compressor indefinitely. */ - frc2::CommandPtr DisableCompressorCommand(); + wpi::cmd::CommandPtr DisableCompressorCommand(); /** * Query the analog pressure sensor. * * @return the measured pressure, in PSI */ - units::pounds_per_square_inch_t GetPressure(); + wpi::units::pounds_per_square_inch_t GetPressure(); private: // External analog pressure sensor @@ -35,9 +35,9 @@ class Pneumatics : frc2::SubsystemBase { // pressure is 250r-25 static constexpr double kScale = 250; static constexpr double kOffset = -25; - frc::AnalogPotentiometer m_pressureTransducer{/* the AnalogIn port*/ 2, + wpi::AnalogPotentiometer m_pressureTransducer{/* the AnalogIn port*/ 2, kScale, kOffset}; // Compressor connected to a PH with a default CAN ID - frc::Compressor m_compressor{0, frc::PneumaticsModuleType::CTREPCM}; + wpi::Compressor m_compressor{0, wpi::PneumaticsModuleType::CTREPCM}; }; diff --git a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Shooter.hpp b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Shooter.hpp index 992a8c65a7..9861bf0616 100644 --- a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Shooter.hpp +++ b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Shooter.hpp @@ -17,7 +17,7 @@ #include "Constants.hpp" -class Shooter : public frc2::SubsystemBase { +class Shooter : public wpi::cmd::SubsystemBase { public: Shooter(); @@ -28,16 +28,16 @@ class Shooter : public frc2::SubsystemBase { * * @param setpointRotationsPerSecond The desired shooter velocity */ - frc2::CommandPtr ShootCommand(units::turns_per_second_t setpoint); + wpi::cmd::CommandPtr ShootCommand(wpi::units::turns_per_second_t setpoint); private: - frc::PWMSparkMax m_shooterMotor{ShooterConstants::kShooterMotorPort}; - frc::PWMSparkMax m_feederMotor{ShooterConstants::kFeederMotorPort}; + wpi::PWMSparkMax m_shooterMotor{ShooterConstants::kShooterMotorPort}; + wpi::PWMSparkMax m_feederMotor{ShooterConstants::kFeederMotorPort}; - frc::Encoder m_shooterEncoder{ShooterConstants::kEncoderPorts[0], + wpi::Encoder m_shooterEncoder{ShooterConstants::kEncoderPorts[0], ShooterConstants::kEncoderPorts[1], ShooterConstants::kEncoderReversed}; - frc::SimpleMotorFeedforward m_shooterFeedforward{ + wpi::math::SimpleMotorFeedforward m_shooterFeedforward{ ShooterConstants::kS, ShooterConstants::kV}; - frc::PIDController m_shooterFeedback{ShooterConstants::kP, 0.0, 0.0}; + wpi::math::PIDController m_shooterFeedback{ShooterConstants::kP, 0.0, 0.0}; }; diff --git a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Storage.hpp b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Storage.hpp index f29d53f38d..6e16daffdd 100644 --- a/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Storage.hpp +++ b/wpilibcExamples/src/main/cpp/examples/RapidReactCommandBot/include/subsystems/Storage.hpp @@ -12,16 +12,16 @@ #include "Constants.hpp" -class Storage : frc2::SubsystemBase { +class Storage : wpi::cmd::SubsystemBase { public: Storage(); /** Returns a command that runs the storage motor indefinitely. */ - frc2::CommandPtr RunCommand(); + wpi::cmd::CommandPtr RunCommand(); /** Whether the ball storage is full. */ - frc2::Trigger HasCargo{[this] { return m_ballSensor.Get(); }}; + wpi::cmd::Trigger HasCargo{[this] { return m_ballSensor.Get(); }}; private: - frc::PWMSparkMax m_motor{StorageConstants::kMotorPort}; - frc::DigitalInput m_ballSensor{StorageConstants::kBallSensorPort}; + wpi::PWMSparkMax m_motor{StorageConstants::kMotorPort}; + wpi::DigitalInput m_ballSensor{StorageConstants::kBallSensorPort}; }; diff --git a/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/Robot.cpp index 534158dc96..35984f0b9d 100644 --- a/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/Robot.cpp @@ -17,7 +17,7 @@ Robot::Robot() {} * LiveWindow and SmartDashboard integrated updating. */ void Robot::RobotPeriodic() { - frc2::CommandScheduler::GetInstance().Run(); + wpi::cmd::CommandScheduler::GetInstance().Run(); } /** @@ -37,7 +37,7 @@ void Robot::AutonomousInit() { m_autonomousCommand = m_container.GetAutonomousCommand(); if (m_autonomousCommand != nullptr) { - frc2::CommandScheduler::GetInstance().Schedule(m_autonomousCommand); + wpi::cmd::CommandScheduler::GetInstance().Schedule(m_autonomousCommand); } } @@ -66,6 +66,6 @@ void Robot::TestPeriodic() {} #ifndef RUNNING_FRC_TESTS int main() { - return frc::StartRobot(); + return wpi::StartRobot(); } #endif diff --git a/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/RobotContainer.cpp b/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/RobotContainer.cpp index d191e2cb7b..99b9a38b84 100644 --- a/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/RobotContainer.cpp +++ b/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/RobotContainer.cpp @@ -21,15 +21,15 @@ void RobotContainer::ConfigureButtonBindings() { [this] { return -m_controller.GetRawAxis(2); })); // Example of how to use the onboard IO - m_onboardButtonA.OnTrue(frc2::cmd::Print("Button A Pressed")) - .OnFalse(frc2::cmd::Print("Button A Released")); + m_onboardButtonA.OnTrue(wpi::cmd::cmd::Print("Button A Pressed")) + .OnFalse(wpi::cmd::cmd::Print("Button A Released")); // Setup SmartDashboard options. m_chooser.SetDefaultOption("Auto Routine Distance", &m_autoDistance); m_chooser.AddOption("Auto Routine Time", &m_autoTime); - frc::SmartDashboard::PutData("Auto Selector", &m_chooser); + wpi::SmartDashboard::PutData("Auto Selector", &m_chooser); } -frc2::Command* RobotContainer::GetAutonomousCommand() { +wpi::cmd::Command* RobotContainer::GetAutonomousCommand() { return m_chooser.GetSelected(); } diff --git a/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/commands/DriveDistance.cpp b/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/commands/DriveDistance.cpp index ae9499479f..61d67e3d08 100644 --- a/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/commands/DriveDistance.cpp +++ b/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/commands/DriveDistance.cpp @@ -20,5 +20,5 @@ void DriveDistance::End(bool interrupted) { } bool DriveDistance::IsFinished() { - return units::math::abs(m_drive->GetAverageDistance()) >= m_distance; + return wpi::units::math::abs(m_drive->GetAverageDistance()) >= m_distance; } diff --git a/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/commands/TurnDegrees.cpp b/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/commands/TurnDegrees.cpp index 94b3fea060..e92dbfa5cb 100644 --- a/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/commands/TurnDegrees.cpp +++ b/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/commands/TurnDegrees.cpp @@ -33,8 +33,8 @@ bool TurnDegrees::IsFinished() { return GetAverageTurningDistance() >= inchPerDegree * m_angle; } -units::meter_t TurnDegrees::GetAverageTurningDistance() { - auto l = units::math::abs(m_drive->GetLeftDistance()); - auto r = units::math::abs(m_drive->GetRightDistance()); +wpi::units::meter_t TurnDegrees::GetAverageTurningDistance() { + auto l = wpi::units::math::abs(m_drive->GetLeftDistance()); + auto r = wpi::units::math::abs(m_drive->GetRightDistance()); return (l + r) / 2; } diff --git a/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/subsystems/Drivetrain.cpp b/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/subsystems/Drivetrain.cpp index 3080cadc8c..efcd548406 100644 --- a/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/subsystems/Drivetrain.cpp +++ b/wpilibcExamples/src/main/cpp/examples/RomiReference/cpp/subsystems/Drivetrain.cpp @@ -15,8 +15,8 @@ using namespace DriveConstants; // The Romi has onboard encoders that are hardcoded // to use DIO pins 4/5 and 6/7 for the left and right Drivetrain::Drivetrain() { - wpi::SendableRegistry::AddChild(&m_drive, &m_leftMotor); - wpi::SendableRegistry::AddChild(&m_drive, &m_rightMotor); + wpi::util::SendableRegistry::AddChild(&m_drive, &m_leftMotor); + wpi::util::SendableRegistry::AddChild(&m_drive, &m_rightMotor); // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's @@ -51,27 +51,27 @@ int Drivetrain::GetRightEncoderCount() { return m_rightEncoder.Get(); } -units::meter_t Drivetrain::GetLeftDistance() { - return units::meter_t{m_leftEncoder.GetDistance()}; +wpi::units::meter_t Drivetrain::GetLeftDistance() { + return wpi::units::meter_t{m_leftEncoder.GetDistance()}; } -units::meter_t Drivetrain::GetRightDistance() { - return units::meter_t{m_rightEncoder.GetDistance()}; +wpi::units::meter_t Drivetrain::GetRightDistance() { + return wpi::units::meter_t{m_rightEncoder.GetDistance()}; } -units::meter_t Drivetrain::GetAverageDistance() { +wpi::units::meter_t Drivetrain::GetAverageDistance() { return (GetLeftDistance() + GetRightDistance()) / 2.0; } -units::radian_t Drivetrain::GetGyroAngleX() { +wpi::units::radian_t Drivetrain::GetGyroAngleX() { return m_gyro.GetAngleX(); } -units::radian_t Drivetrain::GetGyroAngleY() { +wpi::units::radian_t Drivetrain::GetGyroAngleY() { return m_gyro.GetAngleY(); } -units::radian_t Drivetrain::GetGyroAngleZ() { +wpi::units::radian_t Drivetrain::GetGyroAngleZ() { return m_gyro.GetAngleZ(); } diff --git a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/Robot.hpp b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/Robot.hpp index b89d567b62..ffeab02e6f 100644 --- a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/Robot.hpp +++ b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/Robot.hpp @@ -9,7 +9,7 @@ #include "RobotContainer.hpp" -class Robot : public frc::TimedRobot { +class Robot : public wpi::TimedRobot { public: Robot(); void RobotPeriodic() override; @@ -24,6 +24,6 @@ class Robot : public frc::TimedRobot { private: // Have it null by default so that if testing teleop it // doesn't have undefined behavior and potentially crash. - frc2::Command* m_autonomousCommand = nullptr; + wpi::cmd::Command* m_autonomousCommand = nullptr; RobotContainer m_container; }; diff --git a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/RobotContainer.hpp b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/RobotContainer.hpp index e7a30a9613..3109e5dad4 100644 --- a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/RobotContainer.hpp +++ b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/RobotContainer.hpp @@ -38,20 +38,20 @@ class RobotContainer { // Your subsystem configuration should take the overlays into account public: RobotContainer(); - frc2::Command* GetAutonomousCommand(); + wpi::cmd::Command* GetAutonomousCommand(); private: // Assumes a gamepad plugged into channel 0 - frc::Joystick m_controller{0}; - frc::SendableChooser m_chooser; + wpi::Joystick m_controller{0}; + wpi::SendableChooser m_chooser; // The robot's subsystems Drivetrain m_drive; - frc::OnBoardIO m_onboardIO{frc::OnBoardIO::ChannelMode::INPUT, - frc::OnBoardIO::ChannelMode::INPUT}; + wpi::romi::OnBoardIO m_onboardIO{wpi::romi::OnBoardIO::ChannelMode::INPUT, + wpi::romi::OnBoardIO::ChannelMode::INPUT}; // Example button - frc2::Trigger m_onboardButtonA{ + wpi::cmd::Trigger m_onboardButtonA{ [this] { return m_onboardIO.GetButtonAPressed(); }}; // Autonomous commands. diff --git a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/AutonomousDistance.hpp b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/AutonomousDistance.hpp index 227f0924de..bd29bdefe0 100644 --- a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/AutonomousDistance.hpp +++ b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/AutonomousDistance.hpp @@ -12,7 +12,7 @@ #include "subsystems/Drivetrain.hpp" class AutonomousDistance - : public frc2::CommandHelper { public: /** diff --git a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/AutonomousTime.hpp b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/AutonomousTime.hpp index 31cc56df0c..e2dde7998a 100644 --- a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/AutonomousTime.hpp +++ b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/AutonomousTime.hpp @@ -12,7 +12,7 @@ #include "subsystems/Drivetrain.hpp" class AutonomousTime - : public frc2::CommandHelper { + : public wpi::cmd::CommandHelper { public: /** * Creates a new Autonomous Drive based on time. This will drive out for a diff --git a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/DriveDistance.hpp b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/DriveDistance.hpp index 3b6abf364f..49fc11fb98 100644 --- a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/DriveDistance.hpp +++ b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/DriveDistance.hpp @@ -10,7 +10,7 @@ #include "subsystems/Drivetrain.hpp" -class DriveDistance : public frc2::CommandHelper { +class DriveDistance : public wpi::cmd::CommandHelper { public: /** * Creates a new DriveDistance. This command will drive your your robot for a @@ -20,7 +20,7 @@ class DriveDistance : public frc2::CommandHelper { * @param distance The distance the robot will drive * @param drive The drivetrain subsystem on which this command will run */ - DriveDistance(double speed, units::meter_t distance, Drivetrain* drive) + DriveDistance(double speed, wpi::units::meter_t distance, Drivetrain* drive) : m_speed(speed), m_distance(distance), m_drive(drive) { AddRequirements(m_drive); } @@ -32,6 +32,6 @@ class DriveDistance : public frc2::CommandHelper { private: double m_speed; - units::meter_t m_distance; + wpi::units::meter_t m_distance; Drivetrain* m_drive; }; diff --git a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/DriveTime.hpp b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/DriveTime.hpp index e8983b5acf..3ab5ad2a8a 100644 --- a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/DriveTime.hpp +++ b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/DriveTime.hpp @@ -11,7 +11,7 @@ #include "subsystems/Drivetrain.hpp" -class DriveTime : public frc2::CommandHelper { +class DriveTime : public wpi::cmd::CommandHelper { public: /** * Creates a new DriveTime. This command will drive your robot for a desired @@ -21,7 +21,7 @@ class DriveTime : public frc2::CommandHelper { * @param time How much time to drive * @param drive The drivetrain subsystem on which this command will run */ - DriveTime(double speed, units::second_t time, Drivetrain* drive) + DriveTime(double speed, wpi::units::second_t time, Drivetrain* drive) : m_speed(speed), m_duration(time), m_drive(drive) { AddRequirements(m_drive); } @@ -33,7 +33,7 @@ class DriveTime : public frc2::CommandHelper { private: double m_speed; - units::second_t m_duration; + wpi::units::second_t m_duration; Drivetrain* m_drive; - frc::Timer m_timer; + wpi::Timer m_timer; }; diff --git a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/TeleopArcadeDrive.hpp b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/TeleopArcadeDrive.hpp index f4682d6299..e0e7ce6f22 100644 --- a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/TeleopArcadeDrive.hpp +++ b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/TeleopArcadeDrive.hpp @@ -12,7 +12,7 @@ #include "subsystems/Drivetrain.hpp" class TeleopArcadeDrive - : public frc2::CommandHelper { + : public wpi::cmd::CommandHelper { public: /** * Creates a new ArcadeDrive. This command will drive your robot according to diff --git a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/TurnDegrees.hpp b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/TurnDegrees.hpp index 2dd2b4cf86..90df6e892a 100644 --- a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/TurnDegrees.hpp +++ b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/TurnDegrees.hpp @@ -11,7 +11,7 @@ #include "subsystems/Drivetrain.hpp" -class TurnDegrees : public frc2::CommandHelper { +class TurnDegrees : public wpi::cmd::CommandHelper { public: /** * Creates a new TurnDegrees. This command will turn your robot for a desired @@ -21,7 +21,7 @@ class TurnDegrees : public frc2::CommandHelper { * @param degrees Degrees to turn. Leverages encoders to compare distance. * @param drive The drive subsystem on which this command will run */ - TurnDegrees(double speed, units::degree_t angle, Drivetrain* drive) + TurnDegrees(double speed, wpi::units::degree_t angle, Drivetrain* drive) : m_speed(speed), m_angle(angle), m_drive(drive) { AddRequirements(m_drive); } @@ -33,8 +33,8 @@ class TurnDegrees : public frc2::CommandHelper { private: double m_speed; - units::degree_t m_angle; + wpi::units::degree_t m_angle; Drivetrain* m_drive; - units::meter_t GetAverageTurningDistance(); + wpi::units::meter_t GetAverageTurningDistance(); }; diff --git a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/TurnTime.hpp b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/TurnTime.hpp index 3a2b4fc33f..3d8ac60f0d 100644 --- a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/TurnTime.hpp +++ b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/commands/TurnTime.hpp @@ -11,7 +11,7 @@ #include "subsystems/Drivetrain.hpp" -class TurnTime : public frc2::CommandHelper { +class TurnTime : public wpi::cmd::CommandHelper { public: /** * Creates a new TurnTime. @@ -20,7 +20,7 @@ class TurnTime : public frc2::CommandHelper { * @param time How much time to turn * @param drive The drive subsystem on which this command will run */ - TurnTime(double speed, units::second_t time, Drivetrain* drive) + TurnTime(double speed, wpi::units::second_t time, Drivetrain* drive) : m_speed(speed), m_duration(time), m_drive(drive) { AddRequirements(m_drive); } @@ -32,7 +32,7 @@ class TurnTime : public frc2::CommandHelper { private: double m_speed; - units::second_t m_duration; + wpi::units::second_t m_duration; Drivetrain* m_drive; - frc::Timer m_timer; + wpi::Timer m_timer; }; diff --git a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/subsystems/Drivetrain.hpp b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/subsystems/Drivetrain.hpp index 67453f4f8f..eab1e2b789 100644 --- a/wpilibcExamples/src/main/cpp/examples/RomiReference/include/subsystems/Drivetrain.hpp +++ b/wpilibcExamples/src/main/cpp/examples/RomiReference/include/subsystems/Drivetrain.hpp @@ -13,10 +13,10 @@ #include #include -class Drivetrain : public frc2::SubsystemBase { +class Drivetrain : public wpi::cmd::SubsystemBase { public: static constexpr double kCountsPerRevolution = 1440.0; - static constexpr units::meter_t kWheelDiameter = 70_mm; + static constexpr wpi::units::meter_t kWheelDiameter = 70_mm; Drivetrain(); @@ -57,42 +57,42 @@ class Drivetrain : public frc2::SubsystemBase { * * @return the left-side distance driven */ - units::meter_t GetLeftDistance(); + wpi::units::meter_t GetLeftDistance(); /** * Gets the right distance driven. * * @return the right-side distance driven */ - units::meter_t GetRightDistance(); + wpi::units::meter_t GetRightDistance(); /** * Returns the average distance traveled by the left and right encoders. * * @return The average distance traveled by the left and right encoders. */ - units::meter_t GetAverageDistance(); + wpi::units::meter_t GetAverageDistance(); /** * Current angle of the Romi around the X-axis. * * @return The current angle of the Romi. */ - units::radian_t GetGyroAngleX(); + wpi::units::radian_t GetGyroAngleX(); /** * Current angle of the Romi around the Y-axis. * * @return The current angle of the Romi. */ - units::radian_t GetGyroAngleY(); + wpi::units::radian_t GetGyroAngleY(); /** * Current angle of the Romi around the Z-axis. * * @return The current angle of the Romi. */ - units::radian_t GetGyroAngleZ(); + wpi::units::radian_t GetGyroAngleZ(); /** * Reset the gyro. @@ -100,15 +100,15 @@ class Drivetrain : public frc2::SubsystemBase { void ResetGyro(); private: - frc::Spark m_leftMotor{0}; - frc::Spark m_rightMotor{1}; + wpi::Spark m_leftMotor{0}; + wpi::Spark m_rightMotor{1}; - frc::Encoder m_leftEncoder{4, 5}; - frc::Encoder m_rightEncoder{6, 7}; + wpi::Encoder m_leftEncoder{4, 5}; + wpi::Encoder m_rightEncoder{6, 7}; - frc::DifferentialDrive m_drive{ + wpi::DifferentialDrive m_drive{ [&](double output) { m_leftMotor.Set(output); }, [&](double output) { m_rightMotor.Set(output); }}; - frc::RomiGyro m_gyro; + wpi::romi::RomiGyro m_gyro; }; diff --git a/wpilibcExamples/src/main/cpp/examples/SelectCommand/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/SelectCommand/cpp/Robot.cpp index 36079cc8e9..9e238c07f8 100644 --- a/wpilibcExamples/src/main/cpp/examples/SelectCommand/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/SelectCommand/cpp/Robot.cpp @@ -18,7 +18,7 @@ Robot::Robot() {} * LiveWindow and SmartDashboard integrated updating. */ void Robot::RobotPeriodic() { - frc2::CommandScheduler::GetInstance().Run(); + wpi::cmd::CommandScheduler::GetInstance().Run(); } /** @@ -38,7 +38,7 @@ void Robot::AutonomousInit() { m_autonomousCommand = m_container.GetAutonomousCommand(); if (m_autonomousCommand != nullptr) { - frc2::CommandScheduler::GetInstance().Schedule(m_autonomousCommand); + wpi::cmd::CommandScheduler::GetInstance().Schedule(m_autonomousCommand); } } @@ -67,6 +67,6 @@ void Robot::TestPeriodic() {} #ifndef RUNNING_FRC_TESTS int main() { - return frc::StartRobot(); + return wpi::StartRobot(); } #endif diff --git a/wpilibcExamples/src/main/cpp/examples/SelectCommand/cpp/RobotContainer.cpp b/wpilibcExamples/src/main/cpp/examples/SelectCommand/cpp/RobotContainer.cpp index 70bab22b3c..9b832e3028 100644 --- a/wpilibcExamples/src/main/cpp/examples/SelectCommand/cpp/RobotContainer.cpp +++ b/wpilibcExamples/src/main/cpp/examples/SelectCommand/cpp/RobotContainer.cpp @@ -13,7 +13,7 @@ RobotContainer::RobotContainer() { m_chooser.AddOption("TWO", CommandSelector::TWO); m_chooser.AddOption("THREE", CommandSelector::THREE); - frc::SmartDashboard::PutData("Auto Chooser", &m_chooser); + wpi::SmartDashboard::PutData("Auto Chooser", &m_chooser); // Configure the button bindings ConfigureButtonBindings(); @@ -23,7 +23,7 @@ void RobotContainer::ConfigureButtonBindings() { // Configure your button bindings here } -frc2::Command* RobotContainer::GetAutonomousCommand() { +wpi::cmd::Command* RobotContainer::GetAutonomousCommand() { // Run the select command in autonomous return m_exampleSelectCommand.get(); } diff --git a/wpilibcExamples/src/main/cpp/examples/SelectCommand/include/Robot.hpp b/wpilibcExamples/src/main/cpp/examples/SelectCommand/include/Robot.hpp index 7a9d5e7e42..219b7b9799 100644 --- a/wpilibcExamples/src/main/cpp/examples/SelectCommand/include/Robot.hpp +++ b/wpilibcExamples/src/main/cpp/examples/SelectCommand/include/Robot.hpp @@ -9,7 +9,7 @@ #include "RobotContainer.hpp" -class Robot : public frc::TimedRobot { +class Robot : public wpi::TimedRobot { public: Robot(); void RobotPeriodic() override; @@ -24,7 +24,7 @@ class Robot : public frc::TimedRobot { private: // Have it null by default so that if testing teleop it // doesn't have undefined behavior and potentially crash. - frc2::Command* m_autonomousCommand = nullptr; + wpi::cmd::Command* m_autonomousCommand = nullptr; RobotContainer m_container; }; diff --git a/wpilibcExamples/src/main/cpp/examples/SelectCommand/include/RobotContainer.hpp b/wpilibcExamples/src/main/cpp/examples/SelectCommand/include/RobotContainer.hpp index f594b09ae1..1d362c7ef8 100644 --- a/wpilibcExamples/src/main/cpp/examples/SelectCommand/include/RobotContainer.hpp +++ b/wpilibcExamples/src/main/cpp/examples/SelectCommand/include/RobotContainer.hpp @@ -20,14 +20,14 @@ class RobotContainer { public: RobotContainer(); - frc2::Command* GetAutonomousCommand(); + wpi::cmd::Command* GetAutonomousCommand(); private: // The enum used as keys for selecting the command to run. enum CommandSelector { ONE, TWO, THREE }; // An example of how command selector may be used with SendableChooser - frc::SendableChooser m_chooser; + wpi::SendableChooser m_chooser; // The robot's subsystems and commands are defined here... @@ -35,12 +35,12 @@ class RobotContainer { // value returned by the selector method at runtime. Note that selectcommand // takes a generic type, so the selector does not have to be an enum; it could // be any desired type (string, integer, boolean, double...) - frc2::CommandPtr m_exampleSelectCommand = frc2::cmd::Select( + wpi::cmd::CommandPtr m_exampleSelectCommand = wpi::cmd::cmd::Select( [this] { return m_chooser.GetSelected(); }, // Maps selector values to commands - std::pair{ONE, frc2::cmd::Print("Command one was selected!")}, - std::pair{TWO, frc2::cmd::Print("Command two was selected!")}, - std::pair{THREE, frc2::cmd::Print("Command three was selected!")}); + std::pair{ONE, wpi::cmd::cmd::Print("Command one was selected!")}, + std::pair{TWO, wpi::cmd::cmd::Print("Command two was selected!")}, + std::pair{THREE, wpi::cmd::cmd::Print("Command three was selected!")}); void ConfigureButtonBindings(); }; diff --git a/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/cpp/Drivetrain.cpp b/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/cpp/Drivetrain.cpp index 33b5bbfc23..e24f4418d9 100644 --- a/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/cpp/Drivetrain.cpp +++ b/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/cpp/Drivetrain.cpp @@ -6,7 +6,7 @@ #include -void Drivetrain::SetSpeeds(const frc::DifferentialDriveWheelSpeeds& speeds) { +void Drivetrain::SetSpeeds(const wpi::math::DifferentialDriveWheelSpeeds& speeds) { auto leftFeedforward = m_feedforward.Calculate(speeds.left); auto rightFeedforward = m_feedforward.Calculate(speeds.right); double leftOutput = m_leftPIDController.Calculate(m_leftEncoder.GetRate(), @@ -14,26 +14,26 @@ void Drivetrain::SetSpeeds(const frc::DifferentialDriveWheelSpeeds& speeds) { double rightOutput = m_rightPIDController.Calculate(m_rightEncoder.GetRate(), speeds.right.value()); - m_leftLeader.SetVoltage(units::volt_t{leftOutput} + leftFeedforward); - m_rightLeader.SetVoltage(units::volt_t{rightOutput} + rightFeedforward); + m_leftLeader.SetVoltage(wpi::units::volt_t{leftOutput} + leftFeedforward); + m_rightLeader.SetVoltage(wpi::units::volt_t{rightOutput} + rightFeedforward); } -void Drivetrain::Drive(units::meters_per_second_t xSpeed, - units::radians_per_second_t rot) { +void Drivetrain::Drive(wpi::units::meters_per_second_t xSpeed, + wpi::units::radians_per_second_t rot) { SetSpeeds(m_kinematics.ToWheelSpeeds({xSpeed, 0_mps, rot})); } void Drivetrain::UpdateOdometry() { m_odometry.Update(m_imu.GetRotation2d(), - units::meter_t{m_leftEncoder.GetDistance()}, - units::meter_t{m_rightEncoder.GetDistance()}); + wpi::units::meter_t{m_leftEncoder.GetDistance()}, + wpi::units::meter_t{m_rightEncoder.GetDistance()}); } -void Drivetrain::ResetOdometry(const frc::Pose2d& pose) { +void Drivetrain::ResetOdometry(const wpi::math::Pose2d& pose) { m_drivetrainSimulator.SetPose(pose); m_odometry.ResetPosition(m_imu.GetRotation2d(), - units::meter_t{m_leftEncoder.GetDistance()}, - units::meter_t{m_rightEncoder.GetDistance()}, pose); + wpi::units::meter_t{m_leftEncoder.GetDistance()}, + wpi::units::meter_t{m_rightEncoder.GetDistance()}, pose); } void Drivetrain::SimulationPeriodic() { @@ -41,10 +41,10 @@ void Drivetrain::SimulationPeriodic() { // simulation, and write the simulated positions and velocities to our // simulated encoder and gyro. We negate the right side so that positive // voltages make the right side move forward. - m_drivetrainSimulator.SetInputs(units::volt_t{m_leftLeader.Get()} * - frc::RobotController::GetInputVoltage(), - units::volt_t{m_rightLeader.Get()} * - frc::RobotController::GetInputVoltage()); + m_drivetrainSimulator.SetInputs(wpi::units::volt_t{m_leftLeader.Get()} * + wpi::RobotController::GetInputVoltage(), + wpi::units::volt_t{m_rightLeader.Get()} * + wpi::RobotController::GetInputVoltage()); m_drivetrainSimulator.Update(20_ms); m_leftEncoderSim.SetDistance(m_drivetrainSimulator.GetLeftPosition().value()); diff --git a/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/cpp/Robot.cpp index cdf131f3c4..7cafbd1491 100644 --- a/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/cpp/Robot.cpp @@ -11,12 +11,12 @@ #include "Drivetrain.hpp" -class Robot : public frc::TimedRobot { +class Robot : public wpi::TimedRobot { public: Robot() { - m_trajectory = frc::TrajectoryGenerator::GenerateTrajectory( - frc::Pose2d{2_m, 2_m, 0_rad}, {}, frc::Pose2d{6_m, 4_m, 0_rad}, - frc::TrajectoryConfig(2_mps, 2_mps_sq)); + m_trajectory = wpi::math::TrajectoryGenerator::GenerateTrajectory( + wpi::math::Pose2d{2_m, 2_m, 0_rad}, {}, wpi::math::Pose2d{6_m, 4_m, 0_rad}, + wpi::math::TrajectoryConfig(2_mps, 2_mps_sq)); } void RobotPeriodic() override { m_drive.Periodic(); } @@ -52,21 +52,21 @@ class Robot : public frc::TimedRobot { void SimulationPeriodic() override { m_drive.SimulationPeriodic(); } private: - frc::XboxController m_controller{0}; + wpi::XboxController m_controller{0}; // Slew rate limiters to make joystick inputs more gentle; 1/3 sec from 0 // to 1. - frc::SlewRateLimiter m_speedLimiter{3 / 1_s}; - frc::SlewRateLimiter m_rotLimiter{3 / 1_s}; + wpi::math::SlewRateLimiter m_speedLimiter{3 / 1_s}; + wpi::math::SlewRateLimiter m_rotLimiter{3 / 1_s}; Drivetrain m_drive; - frc::Trajectory m_trajectory; - frc::LTVUnicycleController m_feedback{20_ms}; - frc::Timer m_timer; + wpi::math::Trajectory m_trajectory; + wpi::math::LTVUnicycleController m_feedback{20_ms}; + wpi::Timer m_timer; }; #ifndef RUNNING_FRC_TESTS int main() { - return frc::StartRobot(); + return wpi::StartRobot(); } #endif diff --git a/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/include/Drivetrain.hpp b/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/include/Drivetrain.hpp index c0767524fe..881aaab04f 100644 --- a/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/include/Drivetrain.hpp +++ b/wpilibcExamples/src/main/cpp/examples/SimpleDifferentialDriveSimulation/include/Drivetrain.hpp @@ -52,59 +52,59 @@ class Drivetrain { m_rightLeader.SetInverted(true); - frc::SmartDashboard::PutData("Field", &m_fieldSim); + wpi::SmartDashboard::PutData("Field", &m_fieldSim); } - static constexpr units::meters_per_second_t kMaxSpeed = + static constexpr wpi::units::meters_per_second_t kMaxSpeed = 3.0_mps; // 3 meters per second - static constexpr units::radians_per_second_t kMaxAngularSpeed{ + static constexpr wpi::units::radians_per_second_t kMaxAngularSpeed{ std::numbers::pi}; // 1/2 rotation per second - void SetSpeeds(const frc::DifferentialDriveWheelSpeeds& speeds); - void Drive(units::meters_per_second_t xSpeed, - units::radians_per_second_t rot); + void SetSpeeds(const wpi::math::DifferentialDriveWheelSpeeds& speeds); + void Drive(wpi::units::meters_per_second_t xSpeed, + wpi::units::radians_per_second_t rot); void UpdateOdometry(); - void ResetOdometry(const frc::Pose2d& pose); + void ResetOdometry(const wpi::math::Pose2d& pose); - frc::Pose2d GetPose() const { return m_odometry.GetPose(); } + wpi::math::Pose2d GetPose() const { return m_odometry.GetPose(); } void SimulationPeriodic(); void Periodic(); private: - static constexpr units::meter_t kTrackwidth = 0.381_m * 2; + static constexpr wpi::units::meter_t kTrackwidth = 0.381_m * 2; static constexpr double kWheelRadius = 0.0508; // meters static constexpr int kEncoderResolution = 4096; - frc::PWMSparkMax m_leftLeader{1}; - frc::PWMSparkMax m_leftFollower{2}; - frc::PWMSparkMax m_rightLeader{3}; - frc::PWMSparkMax m_rightFollower{4}; + wpi::PWMSparkMax m_leftLeader{1}; + wpi::PWMSparkMax m_leftFollower{2}; + wpi::PWMSparkMax m_rightLeader{3}; + wpi::PWMSparkMax m_rightFollower{4}; - frc::Encoder m_leftEncoder{0, 1}; - frc::Encoder m_rightEncoder{2, 3}; + wpi::Encoder m_leftEncoder{0, 1}; + wpi::Encoder m_rightEncoder{2, 3}; - frc::PIDController m_leftPIDController{8.5, 0.0, 0.0}; - frc::PIDController m_rightPIDController{8.5, 0.0, 0.0}; + wpi::math::PIDController m_leftPIDController{8.5, 0.0, 0.0}; + wpi::math::PIDController m_rightPIDController{8.5, 0.0, 0.0}; - frc::OnboardIMU m_imu{frc::OnboardIMU::kFlat}; + wpi::OnboardIMU m_imu{wpi::OnboardIMU::kFlat}; - frc::DifferentialDriveKinematics m_kinematics{kTrackwidth}; - frc::DifferentialDriveOdometry m_odometry{ - m_imu.GetRotation2d(), units::meter_t{m_leftEncoder.GetDistance()}, - units::meter_t{m_rightEncoder.GetDistance()}}; + wpi::math::DifferentialDriveKinematics m_kinematics{kTrackwidth}; + wpi::math::DifferentialDriveOdometry m_odometry{ + m_imu.GetRotation2d(), wpi::units::meter_t{m_leftEncoder.GetDistance()}, + wpi::units::meter_t{m_rightEncoder.GetDistance()}}; // Gains are for example purposes only - must be determined for your own // robot! - frc::SimpleMotorFeedforward m_feedforward{1_V, 3_V / 1_mps}; + wpi::math::SimpleMotorFeedforward m_feedforward{1_V, 3_V / 1_mps}; // Simulation classes help us simulate our robot - frc::sim::EncoderSim m_leftEncoderSim{m_leftEncoder}; - frc::sim::EncoderSim m_rightEncoderSim{m_rightEncoder}; - frc::Field2d m_fieldSim; - frc::LinearSystem<2, 2, 2> m_drivetrainSystem = - frc::LinearSystemId::IdentifyDrivetrainSystem( + wpi::sim::EncoderSim m_leftEncoderSim{m_leftEncoder}; + wpi::sim::EncoderSim m_rightEncoderSim{m_rightEncoder}; + wpi::Field2d m_fieldSim; + wpi::math::LinearSystem<2, 2, 2> m_drivetrainSystem = + wpi::math::LinearSystemId::IdentifyDrivetrainSystem( 1.98_V / 1_mps, 0.2_V / 1_mps_sq, 1.5_V / 1_mps, 0.3_V / 1_mps_sq); - frc::sim::DifferentialDrivetrainSim m_drivetrainSimulator{ - m_drivetrainSystem, kTrackwidth, frc::DCMotor::CIM(2), 8, 2_in}; + wpi::sim::DifferentialDrivetrainSim m_drivetrainSimulator{ + m_drivetrainSystem, kTrackwidth, wpi::math::DCMotor::CIM(2), 8, 2_in}; }; diff --git a/wpilibcExamples/src/main/cpp/examples/Solenoid/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/Solenoid/cpp/Robot.cpp index 0d33e6fc44..ae6df0d8d5 100644 --- a/wpilibcExamples/src/main/cpp/examples/Solenoid/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/Solenoid/cpp/Robot.cpp @@ -9,9 +9,9 @@ Robot::Robot() { // Publish elements to shuffleboard. - frc::SmartDashboard::PutData("Single Solenoid", &m_solenoid); - frc::SmartDashboard::PutData("Double Solenoid", &m_doubleSolenoid); - frc::SmartDashboard::PutData("Compressor", &m_compressor); + wpi::SmartDashboard::PutData("Single Solenoid", &m_solenoid); + wpi::SmartDashboard::PutData("Double Solenoid", &m_doubleSolenoid); + wpi::SmartDashboard::PutData("Compressor", &m_compressor); } void Robot::TeleopPeriodic() { @@ -20,17 +20,17 @@ void Robot::TeleopPeriodic() { // Get the pressure (in PSI) from the analog sensor connected to the PH. // This function is supported only on the PH! // On a PCM, this function will return 0. - frc::SmartDashboard::PutNumber("PH Pressure [PSI]", + wpi::SmartDashboard::PutNumber("PH Pressure [PSI]", m_compressor.GetPressure().value()); // Get compressor current draw. - frc::SmartDashboard::PutNumber("Compressor Current", + wpi::SmartDashboard::PutNumber("Compressor Current", m_compressor.GetCurrent().value()); // Get whether the compressor is active. - frc::SmartDashboard::PutBoolean("Compressor Active", + wpi::SmartDashboard::PutBoolean("Compressor Active", m_compressor.IsEnabled()); // Get the digital pressure switch connected to the PCM/PH. // The switch is open when the pressure is over ~120 PSI. - frc::SmartDashboard::PutBoolean("Pressure Switch", + wpi::SmartDashboard::PutBoolean("Pressure Switch", m_compressor.GetPressureSwitchValue()); /* @@ -45,9 +45,9 @@ void Robot::TeleopPeriodic() { * If a button is pressed, set the solenoid to the respective channel. */ if (m_stick.GetRawButtonPressed(kDoubleSolenoidForward)) { - m_doubleSolenoid.Set(frc::DoubleSolenoid::kForward); + m_doubleSolenoid.Set(wpi::DoubleSolenoid::kForward); } else if (m_stick.GetRawButtonPressed(kDoubleSolenoidReverse)) { - m_doubleSolenoid.Set(frc::DoubleSolenoid::kReverse); + m_doubleSolenoid.Set(wpi::DoubleSolenoid::kReverse); } // On button press, toggle the compressor with the mode selected from the @@ -89,6 +89,6 @@ void Robot::TeleopPeriodic() { #ifndef RUNNING_FRC_TESTS int main() { - return frc::StartRobot(); + return wpi::StartRobot(); } #endif diff --git a/wpilibcExamples/src/main/cpp/examples/Solenoid/include/Robot.hpp b/wpilibcExamples/src/main/cpp/examples/Solenoid/include/Robot.hpp index d72be2d7be..11ce33e648 100644 --- a/wpilibcExamples/src/main/cpp/examples/Solenoid/include/Robot.hpp +++ b/wpilibcExamples/src/main/cpp/examples/Solenoid/include/Robot.hpp @@ -33,27 +33,27 @@ * single solenoids only take a single channel. */ -class Robot : public frc::TimedRobot { +class Robot : public wpi::TimedRobot { public: Robot(); void TeleopPeriodic() override; private: - frc::Joystick m_stick{0}; + wpi::Joystick m_stick{0}; // Solenoid corresponds to a single solenoid. // In this case, it's connected to channel 0 of a PH with the default CAN // ID. - frc::Solenoid m_solenoid{0, frc::PneumaticsModuleType::REVPH, 0}; + wpi::Solenoid m_solenoid{0, wpi::PneumaticsModuleType::REVPH, 0}; // DoubleSolenoid corresponds to a double solenoid. // In this case, it's connected to channels 1 and 2 of a PH with the default // CAN ID. - frc::DoubleSolenoid m_doubleSolenoid{0, frc::PneumaticsModuleType::REVPH, 1, + wpi::DoubleSolenoid m_doubleSolenoid{0, wpi::PneumaticsModuleType::REVPH, 1, 2}; // Compressor connected to a PH with a default CAN ID - frc::Compressor m_compressor{0, frc::PneumaticsModuleType::REVPH}; + wpi::Compressor m_compressor{0, wpi::PneumaticsModuleType::REVPH}; static constexpr int kSolenoidButton = 1; static constexpr int kDoubleSolenoidForward = 2; diff --git a/wpilibcExamples/src/main/cpp/examples/StateSpaceArm/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/StateSpaceArm/cpp/Robot.cpp index bacaf7a575..79eef8764a 100644 --- a/wpilibcExamples/src/main/cpp/examples/StateSpaceArm/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/StateSpaceArm/cpp/Robot.cpp @@ -22,18 +22,18 @@ * This is a sample program to demonstrate how to use a state-space controller * to control an arm. */ -class Robot : public frc::TimedRobot { +class Robot : public wpi::TimedRobot { static constexpr int kMotorPort = 0; static constexpr int kEncoderAChannel = 0; static constexpr int kEncoderBChannel = 1; static constexpr int kJoystickPort = 0; - static constexpr units::radian_t kRaisedPosition = 90_deg; - static constexpr units::radian_t kLoweredPosition = 0_deg; + static constexpr wpi::units::radian_t kRaisedPosition = 90_deg; + static constexpr wpi::units::radian_t kLoweredPosition = 0_deg; // Moment of inertia of the arm. Can be estimated with CAD. If finding this - // constant is difficult, LinearSystem.identifyPositionSystem may be better. - static constexpr units::kilogram_square_meter_t kArmMOI = 1.2_kg_sq_m; + // constant is difficult, wpi::math::LinearSystem.identifyPositionSystem may be better. + static constexpr wpi::units::kilogram_square_meter_t kArmMOI = 1.2_kg_sq_m; // Reduction between motors and encoder, as output over input. If the arm // spins slower than the motors, this number should be greater than one. @@ -45,13 +45,13 @@ class Robot : public frc::TimedRobot { // States: [position, velocity], in radians and radians per second. // Inputs (what we can "put in"): [voltage], in volts. // Outputs (what we can measure): [position], in radians. - frc::LinearSystem<2, 1, 1> m_armPlant = - frc::LinearSystemId::SingleJointedArmSystem(frc::DCMotor::NEO(2), kArmMOI, + wpi::math::LinearSystem<2, 1, 1> m_armPlant = + wpi::math::LinearSystemId::SingleJointedArmSystem(wpi::math::DCMotor::NEO(2), kArmMOI, kArmGearing) .Slice(0); // The observer fuses our encoder data and voltage inputs to reject noise. - frc::KalmanFilter<2, 1, 1> m_observer{ + wpi::math::KalmanFilter<2, 1, 1> m_observer{ m_armPlant, {0.015, 0.17}, // How accurate we think our model is {0.01}, // How accurate we think our encoder position @@ -60,7 +60,7 @@ class Robot : public frc::TimedRobot { 20_ms}; // A LQR uses feedback to create voltage commands. - frc::LinearQuadraticRegulator<2, 1> m_controller{ + wpi::math::LinearQuadraticRegulator<2, 1> m_controller{ m_armPlant, // qelms. Velocity error tolerance, in radians and radians per second. // Decrease this to more heavily penalize state excursion, or make the @@ -78,19 +78,19 @@ class Robot : public frc::TimedRobot { // The state-space loop combines a controller, observer, feedforward and plant // for easy control. - frc::LinearSystemLoop<2, 1, 1> m_loop{m_armPlant, m_controller, m_observer, + wpi::math::LinearSystemLoop<2, 1, 1> m_loop{m_armPlant, m_controller, m_observer, 12_V, 20_ms}; // An encoder set up to measure arm position in radians per second. - frc::Encoder m_encoder{kEncoderAChannel, kEncoderBChannel}; + wpi::Encoder m_encoder{kEncoderAChannel, kEncoderBChannel}; - frc::PWMSparkMax m_motor{kMotorPort}; - frc::XboxController m_joystick{kJoystickPort}; + wpi::PWMSparkMax m_motor{kMotorPort}; + wpi::XboxController m_joystick{kJoystickPort}; - frc::TrapezoidProfile m_profile{ + wpi::math::TrapezoidProfile m_profile{ {45_deg_per_s, 90_deg_per_s / 1_s}}; - frc::TrapezoidProfile::State m_lastProfiledReference; + wpi::math::TrapezoidProfile::State m_lastProfiledReference; public: Robot() { @@ -99,17 +99,17 @@ class Robot : public frc::TimedRobot { } void TeleopInit() override { - m_loop.Reset(frc::Vectord<2>{m_encoder.GetDistance(), m_encoder.GetRate()}); + m_loop.Reset(wpi::math::Vectord<2>{m_encoder.GetDistance(), m_encoder.GetRate()}); m_lastProfiledReference = { - units::radian_t{m_encoder.GetDistance()}, - units::radians_per_second_t{m_encoder.GetRate()}}; + wpi::units::radian_t{m_encoder.GetDistance()}, + wpi::units::radians_per_second_t{m_encoder.GetRate()}}; } void TeleopPeriodic() override { // Sets the target position of our arm. This is similar to setting the // setpoint of a PID controller. - frc::TrapezoidProfile::State goal; + wpi::math::TrapezoidProfile::State goal; if (m_joystick.GetRightBumperButton()) { // We pressed the bumper, so let's set our next reference goal = {kRaisedPosition, 0_rad_per_s}; @@ -120,11 +120,11 @@ class Robot : public frc::TimedRobot { m_lastProfiledReference = m_profile.Calculate(20_ms, m_lastProfiledReference, goal); - m_loop.SetNextR(frc::Vectord<2>{m_lastProfiledReference.position.value(), + m_loop.SetNextR(wpi::math::Vectord<2>{m_lastProfiledReference.position.value(), m_lastProfiledReference.velocity.value()}); // Correct our Kalman filter's state vector estimate with encoder data. - m_loop.Correct(frc::Vectord<1>{m_encoder.GetDistance()}); + m_loop.Correct(wpi::math::Vectord<1>{m_encoder.GetDistance()}); // Update our LQR to generate new voltage commands and use the voltages to // predict the next state with out Kalman filter. @@ -133,12 +133,12 @@ class Robot : public frc::TimedRobot { // Send the new calculated voltage to the motors. // voltage = duty cycle * battery voltage, so // duty cycle = voltage / battery voltage - m_motor.SetVoltage(units::volt_t{m_loop.U(0)}); + m_motor.SetVoltage(wpi::units::volt_t{m_loop.U(0)}); } }; #ifndef RUNNING_FRC_TESTS int main() { - return frc::StartRobot(); + return wpi::StartRobot(); } #endif diff --git a/wpilibcExamples/src/main/cpp/examples/StateSpaceElevator/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/StateSpaceElevator/cpp/Robot.cpp index cafca88950..29d5ebbcb7 100644 --- a/wpilibcExamples/src/main/cpp/examples/StateSpaceElevator/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/StateSpaceElevator/cpp/Robot.cpp @@ -24,17 +24,17 @@ * This is a sample program to demonstrate how to use a state-space controller * to control an elevator. */ -class Robot : public frc::TimedRobot { +class Robot : public wpi::TimedRobot { static constexpr int kMotorPort = 0; static constexpr int kEncoderAChannel = 0; static constexpr int kEncoderBChannel = 1; static constexpr int kJoystickPort = 0; - static constexpr units::meter_t kRaisedPosition = 2_ft; - static constexpr units::meter_t kLoweredPosition = 0_ft; + static constexpr wpi::units::meter_t kRaisedPosition = 2_ft; + static constexpr wpi::units::meter_t kLoweredPosition = 0_ft; - static constexpr units::meter_t kDrumRadius = 0.75_in; - static constexpr units::kilogram_t kCarriageMass = 4.5_kg; + static constexpr wpi::units::meter_t kDrumRadius = 0.75_in; + static constexpr wpi::units::kilogram_t kCarriageMass = 4.5_kg; static constexpr double kGearRatio = 6.0; // The plant holds a state-space model of our elevator. This system has the @@ -43,16 +43,16 @@ class Robot : public frc::TimedRobot { // States: [position, velocity], in meters and meters per second. // Inputs (what we can "put in"): [voltage], in volts. // Outputs (what we can measure): [position], in meters. - frc::LinearSystem<2, 1, 1> m_elevatorPlant = - frc::LinearSystemId::ElevatorSystem(frc::DCMotor::NEO(2), kCarriageMass, + wpi::math::LinearSystem<2, 1, 1> m_elevatorPlant = + wpi::math::LinearSystemId::ElevatorSystem(wpi::math::DCMotor::NEO(2), kCarriageMass, kDrumRadius, kGearRatio) .Slice(0); // The observer fuses our encoder data and voltage inputs to reject noise. - frc::KalmanFilter<2, 1, 1> m_observer{ + wpi::math::KalmanFilter<2, 1, 1> m_observer{ m_elevatorPlant, - {units::meter_t{2_in}.value(), - units::meters_per_second_t{40_in / 1_s} + {wpi::units::meter_t{2_in}.value(), + wpi::units::meters_per_second_t{40_in / 1_s} .value()}, // How accurate we think our model is {0.001}, // How accurate we think our encoder position // data is. In this case we very highly trust our encoder position @@ -60,13 +60,13 @@ class Robot : public frc::TimedRobot { 20_ms}; // A LQR uses feedback to create voltage commands. - frc::LinearQuadraticRegulator<2, 1> m_controller{ + wpi::math::LinearQuadraticRegulator<2, 1> m_controller{ m_elevatorPlant, // qelms. State error tolerance, in meters and meters per second. // Decrease this to more heavily penalize state excursion, or make the // controller behave more aggressively. - {units::meter_t{1_in}.value(), - units::meters_per_second_t{10_in / 1_s}.value()}, + {wpi::units::meter_t{1_in}.value(), + wpi::units::meters_per_second_t{10_in / 1_s}.value()}, // relms. Control effort (voltage) tolerance. Decrease this to more // heavily penalize control effort, or make the controller less // aggressive. 12 is a good starting point because that is the @@ -78,18 +78,18 @@ class Robot : public frc::TimedRobot { // The state-space loop combines a controller, observer, feedforward and plant // for easy control. - frc::LinearSystemLoop<2, 1, 1> m_loop{m_elevatorPlant, m_controller, + wpi::math::LinearSystemLoop<2, 1, 1> m_loop{m_elevatorPlant, m_controller, m_observer, 12_V, 20_ms}; // An encoder set up to measure elevator height in meters. - frc::Encoder m_encoder{kEncoderAChannel, kEncoderBChannel}; + wpi::Encoder m_encoder{kEncoderAChannel, kEncoderBChannel}; - frc::PWMSparkMax m_motor{kMotorPort}; - frc::XboxController m_joystick{kJoystickPort}; + wpi::PWMSparkMax m_motor{kMotorPort}; + wpi::XboxController m_joystick{kJoystickPort}; - frc::TrapezoidProfile m_profile{{3_fps, 6_fps_sq}}; + wpi::math::TrapezoidProfile m_profile{{3_fps, 6_fps_sq}}; - frc::TrapezoidProfile::State m_lastProfiledReference; + wpi::math::TrapezoidProfile::State m_lastProfiledReference; public: Robot() { @@ -100,16 +100,16 @@ class Robot : public frc::TimedRobot { void TeleopInit() override { // Reset our loop to make sure it's in a known state. - m_loop.Reset(frc::Vectord<2>{m_encoder.GetDistance(), m_encoder.GetRate()}); + m_loop.Reset(wpi::math::Vectord<2>{m_encoder.GetDistance(), m_encoder.GetRate()}); - m_lastProfiledReference = {units::meter_t{m_encoder.GetDistance()}, - units::meters_per_second_t{m_encoder.GetRate()}}; + m_lastProfiledReference = {wpi::units::meter_t{m_encoder.GetDistance()}, + wpi::units::meters_per_second_t{m_encoder.GetRate()}}; } void TeleopPeriodic() override { // Sets the target height of our elevator. This is similar to setting the // setpoint of a PID controller. - frc::TrapezoidProfile::State goal; + wpi::math::TrapezoidProfile::State goal; if (m_joystick.GetRightBumperButton()) { // We pressed the bumper, so let's set our next reference goal = {kRaisedPosition, 0_fps}; @@ -120,11 +120,11 @@ class Robot : public frc::TimedRobot { m_lastProfiledReference = m_profile.Calculate(20_ms, m_lastProfiledReference, goal); - m_loop.SetNextR(frc::Vectord<2>{m_lastProfiledReference.position.value(), + m_loop.SetNextR(wpi::math::Vectord<2>{m_lastProfiledReference.position.value(), m_lastProfiledReference.velocity.value()}); // Correct our Kalman filter's state vector estimate with encoder data. - m_loop.Correct(frc::Vectord<1>{m_encoder.GetDistance()}); + m_loop.Correct(wpi::math::Vectord<1>{m_encoder.GetDistance()}); // Update our LQR to generate new voltage commands and use the voltages to // predict the next state with out Kalman filter. @@ -133,12 +133,12 @@ class Robot : public frc::TimedRobot { // Send the new calculated voltage to the motors. // voltage = duty cycle * battery voltage, so // duty cycle = voltage / battery voltage - m_motor.SetVoltage(units::volt_t{m_loop.U(0)}); + m_motor.SetVoltage(wpi::units::volt_t{m_loop.U(0)}); } }; #ifndef RUNNING_FRC_TESTS int main() { - return frc::StartRobot(); + return wpi::StartRobot(); } #endif diff --git a/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheel/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheel/cpp/Robot.cpp index c4bab2cb24..3cca5bbe74 100644 --- a/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheel/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheel/cpp/Robot.cpp @@ -21,14 +21,14 @@ * This is a sample program to demonstrate how to use a state-space controller * to control a flywheel. */ -class Robot : public frc::TimedRobot { +class Robot : public wpi::TimedRobot { static constexpr int kMotorPort = 0; static constexpr int kEncoderAChannel = 0; static constexpr int kEncoderBChannel = 1; static constexpr int kJoystickPort = 0; - static constexpr units::radians_per_second_t kSpinup = 500_rpm; + static constexpr wpi::units::radians_per_second_t kSpinup = 500_rpm; - static constexpr units::kilogram_square_meter_t kFlywheelMomentOfInertia = + static constexpr wpi::units::kilogram_square_meter_t kFlywheelMomentOfInertia = 0.00032_kg_sq_m; // Reduction between motors and encoder, as output over input. If the flywheel @@ -41,19 +41,19 @@ class Robot : public frc::TimedRobot { // States: [velocity], in radians per second. // Inputs (what we can "put in"): [voltage], in volts. // Outputs (what we can measure): [velocity], in radians per second. - frc::LinearSystem<1, 1, 1> m_flywheelPlant = - frc::LinearSystemId::FlywheelSystem( - frc::DCMotor::NEO(2), kFlywheelMomentOfInertia, kFlywheelGearing); + wpi::math::LinearSystem<1, 1, 1> m_flywheelPlant = + wpi::math::LinearSystemId::FlywheelSystem( + wpi::math::DCMotor::NEO(2), kFlywheelMomentOfInertia, kFlywheelGearing); // The observer fuses our encoder data and voltage inputs to reject noise. - frc::KalmanFilter<1, 1, 1> m_observer{ + wpi::math::KalmanFilter<1, 1, 1> m_observer{ m_flywheelPlant, {3.0}, // How accurate we think our model is {0.01}, // How accurate we think our encoder data is 20_ms}; // A LQR uses feedback to create voltage commands. - frc::LinearQuadraticRegulator<1, 1> m_controller{ + wpi::math::LinearQuadraticRegulator<1, 1> m_controller{ m_flywheelPlant, // qelms. Velocity error tolerance, in radians per second. Decrease this // to more heavily penalize state excursion, or make the controller behave @@ -70,14 +70,14 @@ class Robot : public frc::TimedRobot { // The state-space loop combines a controller, observer, feedforward and plant // for easy control. - frc::LinearSystemLoop<1, 1, 1> m_loop{m_flywheelPlant, m_controller, + wpi::math::LinearSystemLoop<1, 1, 1> m_loop{m_flywheelPlant, m_controller, m_observer, 12_V, 20_ms}; // An encoder set up to measure flywheel velocity in radians per second. - frc::Encoder m_encoder{kEncoderAChannel, kEncoderBChannel}; + wpi::Encoder m_encoder{kEncoderAChannel, kEncoderBChannel}; - frc::PWMSparkMax m_motor{kMotorPort}; - frc::XboxController m_joystick{kJoystickPort}; + wpi::PWMSparkMax m_motor{kMotorPort}; + wpi::XboxController m_joystick{kJoystickPort}; public: Robot() { @@ -86,7 +86,7 @@ class Robot : public frc::TimedRobot { } void TeleopInit() override { - m_loop.Reset(frc::Vectord<1>{m_encoder.GetRate()}); + m_loop.Reset(wpi::math::Vectord<1>{m_encoder.GetRate()}); } void TeleopPeriodic() override { @@ -94,14 +94,14 @@ class Robot : public frc::TimedRobot { // setpoint of a PID controller. if (m_joystick.GetRightBumperButton()) { // We pressed the bumper, so let's set our next reference - m_loop.SetNextR(frc::Vectord<1>{kSpinup.value()}); + m_loop.SetNextR(wpi::math::Vectord<1>{kSpinup.value()}); } else { // We released the bumper, so let's spin down - m_loop.SetNextR(frc::Vectord<1>{0.0}); + m_loop.SetNextR(wpi::math::Vectord<1>{0.0}); } // Correct our Kalman filter's state vector estimate with encoder data. - m_loop.Correct(frc::Vectord<1>{m_encoder.GetRate()}); + m_loop.Correct(wpi::math::Vectord<1>{m_encoder.GetRate()}); // Update our LQR to generate new voltage commands and use the voltages to // predict the next state with out Kalman filter. @@ -110,12 +110,12 @@ class Robot : public frc::TimedRobot { // Send the new calculated voltage to the motors. // voltage = duty cycle * battery voltage, so // duty cycle = voltage / battery voltage - m_motor.SetVoltage(units::volt_t{m_loop.U(0)}); + m_motor.SetVoltage(wpi::units::volt_t{m_loop.U(0)}); } }; #ifndef RUNNING_FRC_TESTS int main() { - return frc::StartRobot(); + return wpi::StartRobot(); } #endif diff --git a/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheelSysId/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheelSysId/cpp/Robot.cpp index 17af787545..061cbc0978 100644 --- a/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheelSysId/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/StateSpaceFlywheelSysId/cpp/Robot.cpp @@ -20,12 +20,12 @@ * This is a sample program to demonstrate how to use a state-space controller * to control a flywheel. */ -class Robot : public frc::TimedRobot { +class Robot : public wpi::TimedRobot { static constexpr int kMotorPort = 0; static constexpr int kEncoderAChannel = 0; static constexpr int kEncoderBChannel = 1; static constexpr int kJoystickPort = 0; - static constexpr units::radians_per_second_t kSpinup = 500_rpm; + static constexpr wpi::units::radians_per_second_t kSpinup = 500_rpm; // Volts per (radian per second) static constexpr auto kFlywheelKv = 0.023_V / 1_rad_per_s; @@ -41,19 +41,19 @@ class Robot : public frc::TimedRobot { // Outputs (what we can measure): [velocity], in radians per second. // // The Kv and Ka constants are found using the FRC Characterization toolsuite. - frc::LinearSystem<1, 1, 1> m_flywheelPlant = - frc::LinearSystemId::IdentifyVelocitySystem(kFlywheelKv, + wpi::math::LinearSystem<1, 1, 1> m_flywheelPlant = + wpi::math::LinearSystemId::IdentifyVelocitySystem(kFlywheelKv, kFlywheelKa); // The observer fuses our encoder data and voltage inputs to reject noise. - frc::KalmanFilter<1, 1, 1> m_observer{ + wpi::math::KalmanFilter<1, 1, 1> m_observer{ m_flywheelPlant, {3.0}, // How accurate we think our model is {0.01}, // How accurate we think our encoder data is 20_ms}; // A LQR uses feedback to create voltage commands. - frc::LinearQuadraticRegulator<1, 1> m_controller{ + wpi::math::LinearQuadraticRegulator<1, 1> m_controller{ m_flywheelPlant, // qelms. Velocity error tolerance, in radians per second. Decrease this // to more heavily penalize state excursion, or make the controller behave @@ -70,14 +70,14 @@ class Robot : public frc::TimedRobot { // The state-space loop combines a controller, observer, feedforward and plant // for easy control. - frc::LinearSystemLoop<1, 1, 1> m_loop{m_flywheelPlant, m_controller, + wpi::math::LinearSystemLoop<1, 1, 1> m_loop{m_flywheelPlant, m_controller, m_observer, 12_V, 20_ms}; // An encoder set up to measure flywheel velocity in radians per second. - frc::Encoder m_encoder{kEncoderAChannel, kEncoderBChannel}; + wpi::Encoder m_encoder{kEncoderAChannel, kEncoderBChannel}; - frc::PWMSparkMax m_motor{kMotorPort}; - frc::XboxController m_joystick{kJoystickPort}; + wpi::PWMSparkMax m_motor{kMotorPort}; + wpi::XboxController m_joystick{kJoystickPort}; public: Robot() { @@ -86,7 +86,7 @@ class Robot : public frc::TimedRobot { } void TeleopInit() override { - m_loop.Reset(frc::Vectord<1>{m_encoder.GetRate()}); + m_loop.Reset(wpi::math::Vectord<1>{m_encoder.GetRate()}); } void TeleopPeriodic() override { @@ -94,14 +94,14 @@ class Robot : public frc::TimedRobot { // setpoint of a PID controller. if (m_joystick.GetRightBumperButton()) { // We pressed the bumper, so let's set our next reference - m_loop.SetNextR(frc::Vectord<1>{kSpinup.value()}); + m_loop.SetNextR(wpi::math::Vectord<1>{kSpinup.value()}); } else { // We released the bumper, so let's spin down - m_loop.SetNextR(frc::Vectord<1>{0.0}); + m_loop.SetNextR(wpi::math::Vectord<1>{0.0}); } // Correct our Kalman filter's state vector estimate with encoder data. - m_loop.Correct(frc::Vectord<1>{m_encoder.GetRate()}); + m_loop.Correct(wpi::math::Vectord<1>{m_encoder.GetRate()}); // Update our LQR to generate new voltage commands and use the voltages to // predict the next state with out Kalman filter. @@ -110,12 +110,12 @@ class Robot : public frc::TimedRobot { // Send the new calculated voltage to the motors. // voltage = duty cycle * battery voltage, so // duty cycle = voltage / battery voltage - m_motor.SetVoltage(units::volt_t{m_loop.U(0)}); + m_motor.SetVoltage(wpi::units::volt_t{m_loop.U(0)}); } }; #ifndef RUNNING_FRC_TESTS int main() { - return frc::StartRobot(); + return wpi::StartRobot(); } #endif diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveBot/cpp/Drivetrain.cpp b/wpilibcExamples/src/main/cpp/examples/SwerveBot/cpp/Drivetrain.cpp index 3e1d132d8a..726d500e91 100644 --- a/wpilibcExamples/src/main/cpp/examples/SwerveBot/cpp/Drivetrain.cpp +++ b/wpilibcExamples/src/main/cpp/examples/SwerveBot/cpp/Drivetrain.cpp @@ -4,11 +4,11 @@ #include "Drivetrain.hpp" -void Drivetrain::Drive(units::meters_per_second_t xSpeed, - units::meters_per_second_t ySpeed, - units::radians_per_second_t rot, bool fieldRelative, - units::second_t period) { - frc::ChassisSpeeds chassisSpeeds{xSpeed, ySpeed, rot}; +void Drivetrain::Drive(wpi::units::meters_per_second_t xSpeed, + wpi::units::meters_per_second_t ySpeed, + wpi::units::radians_per_second_t rot, bool fieldRelative, + wpi::units::second_t period) { + wpi::math::ChassisSpeeds chassisSpeeds{xSpeed, ySpeed, rot}; if (fieldRelative) { chassisSpeeds = chassisSpeeds.ToRobotRelative(m_imu.GetRotation2d()); } diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveBot/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/SwerveBot/cpp/Robot.cpp index e50c6681d5..1177303d88 100644 --- a/wpilibcExamples/src/main/cpp/examples/SwerveBot/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/SwerveBot/cpp/Robot.cpp @@ -9,7 +9,7 @@ #include "Drivetrain.hpp" -class Robot : public frc::TimedRobot { +class Robot : public wpi::TimedRobot { public: void AutonomousPeriodic() override { DriveWithJoystick(false); @@ -19,27 +19,27 @@ class Robot : public frc::TimedRobot { void TeleopPeriodic() override { DriveWithJoystick(true); } private: - frc::XboxController m_controller{0}; + wpi::XboxController m_controller{0}; Drivetrain m_swerve; // Slew rate limiters to make joystick inputs more gentle; 1/3 sec from 0 // to 1. - frc::SlewRateLimiter m_xspeedLimiter{3 / 1_s}; - frc::SlewRateLimiter m_yspeedLimiter{3 / 1_s}; - frc::SlewRateLimiter m_rotLimiter{3 / 1_s}; + wpi::math::SlewRateLimiter m_xspeedLimiter{3 / 1_s}; + wpi::math::SlewRateLimiter m_yspeedLimiter{3 / 1_s}; + wpi::math::SlewRateLimiter m_rotLimiter{3 / 1_s}; void DriveWithJoystick(bool fieldRelative) { // Get the x speed. We are inverting this because Xbox controllers return // negative values when we push forward. const auto xSpeed = -m_xspeedLimiter.Calculate( - frc::ApplyDeadband(m_controller.GetLeftY(), 0.02)) * + wpi::math::ApplyDeadband(m_controller.GetLeftY(), 0.02)) * Drivetrain::kMaxSpeed; // Get the y speed or sideways/strafe speed. We are inverting this because // we want a positive value when we pull to the left. Xbox controllers // return positive values when you pull to the right by default. const auto ySpeed = -m_yspeedLimiter.Calculate( - frc::ApplyDeadband(m_controller.GetLeftX(), 0.02)) * + wpi::math::ApplyDeadband(m_controller.GetLeftX(), 0.02)) * Drivetrain::kMaxSpeed; // Get the rate of angular rotation. We are inverting this because we want a @@ -47,7 +47,7 @@ class Robot : public frc::TimedRobot { // mathematics). Xbox controllers return positive values when you pull to // the right by default. const auto rot = -m_rotLimiter.Calculate( - frc::ApplyDeadband(m_controller.GetRightX(), 0.02)) * + wpi::math::ApplyDeadband(m_controller.GetRightX(), 0.02)) * Drivetrain::kMaxAngularSpeed; m_swerve.Drive(xSpeed, ySpeed, rot, fieldRelative, GetPeriod()); @@ -56,6 +56,6 @@ class Robot : public frc::TimedRobot { #ifndef RUNNING_FRC_TESTS int main() { - return frc::StartRobot(); + return wpi::StartRobot(); } #endif diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveBot/cpp/SwerveModule.cpp b/wpilibcExamples/src/main/cpp/examples/SwerveBot/cpp/SwerveModule.cpp index 7b8ecc19fe..c80aeb13d2 100644 --- a/wpilibcExamples/src/main/cpp/examples/SwerveBot/cpp/SwerveModule.cpp +++ b/wpilibcExamples/src/main/cpp/examples/SwerveBot/cpp/SwerveModule.cpp @@ -33,22 +33,22 @@ SwerveModule::SwerveModule(const int driveMotorChannel, // Limit the PID Controller's input range between -pi and pi and set the input // to be continuous. m_turningPIDController.EnableContinuousInput( - -units::radian_t{std::numbers::pi}, units::radian_t{std::numbers::pi}); + -wpi::units::radian_t{std::numbers::pi}, wpi::units::radian_t{std::numbers::pi}); } -frc::SwerveModuleState SwerveModule::GetState() const { - return {units::meters_per_second_t{m_driveEncoder.GetRate()}, - units::radian_t{m_turningEncoder.GetDistance()}}; +wpi::math::SwerveModuleState SwerveModule::GetState() const { + return {wpi::units::meters_per_second_t{m_driveEncoder.GetRate()}, + wpi::units::radian_t{m_turningEncoder.GetDistance()}}; } -frc::SwerveModulePosition SwerveModule::GetPosition() const { - return {units::meter_t{m_driveEncoder.GetDistance()}, - units::radian_t{m_turningEncoder.GetDistance()}}; +wpi::math::SwerveModulePosition SwerveModule::GetPosition() const { + return {wpi::units::meter_t{m_driveEncoder.GetDistance()}, + wpi::units::radian_t{m_turningEncoder.GetDistance()}}; } -void SwerveModule::SetDesiredState(frc::SwerveModuleState& referenceState) { - frc::Rotation2d encoderRotation{ - units::radian_t{m_turningEncoder.GetDistance()}}; +void SwerveModule::SetDesiredState(wpi::math::SwerveModuleState& referenceState) { + wpi::math::Rotation2d encoderRotation{ + wpi::units::radian_t{m_turningEncoder.GetDistance()}}; // Optimize the reference state to avoid spinning further than 90 degrees referenceState.Optimize(encoderRotation); @@ -67,13 +67,13 @@ void SwerveModule::SetDesiredState(frc::SwerveModuleState& referenceState) { // Calculate the turning motor output from the turning PID controller. const auto turnOutput = m_turningPIDController.Calculate( - units::radian_t{m_turningEncoder.GetDistance()}, + wpi::units::radian_t{m_turningEncoder.GetDistance()}, referenceState.angle.Radians()); const auto turnFeedforward = m_turnFeedforward.Calculate( m_turningPIDController.GetSetpoint().velocity); // Set the motor outputs. - m_driveMotor.SetVoltage(units::volt_t{driveOutput} + driveFeedforward); - m_turningMotor.SetVoltage(units::volt_t{turnOutput} + turnFeedforward); + m_driveMotor.SetVoltage(wpi::units::volt_t{driveOutput} + driveFeedforward); + m_turningMotor.SetVoltage(wpi::units::volt_t{turnOutput} + turnFeedforward); } diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveBot/include/Drivetrain.hpp b/wpilibcExamples/src/main/cpp/examples/SwerveBot/include/Drivetrain.hpp index 2b7860eb84..2fb4b49086 100644 --- a/wpilibcExamples/src/main/cpp/examples/SwerveBot/include/Drivetrain.hpp +++ b/wpilibcExamples/src/main/cpp/examples/SwerveBot/include/Drivetrain.hpp @@ -20,34 +20,34 @@ class Drivetrain { public: Drivetrain() { m_imu.ResetYaw(); } - void Drive(units::meters_per_second_t xSpeed, - units::meters_per_second_t ySpeed, units::radians_per_second_t rot, - bool fieldRelative, units::second_t period); + void Drive(wpi::units::meters_per_second_t xSpeed, + wpi::units::meters_per_second_t ySpeed, wpi::units::radians_per_second_t rot, + bool fieldRelative, wpi::units::second_t period); void UpdateOdometry(); - static constexpr units::meters_per_second_t kMaxSpeed = + static constexpr wpi::units::meters_per_second_t kMaxSpeed = 3.0_mps; // 3 meters per second - static constexpr units::radians_per_second_t kMaxAngularSpeed{ + static constexpr wpi::units::radians_per_second_t kMaxAngularSpeed{ std::numbers::pi}; // 1/2 rotation per second private: - frc::Translation2d m_frontLeftLocation{+0.381_m, +0.381_m}; - frc::Translation2d m_frontRightLocation{+0.381_m, -0.381_m}; - frc::Translation2d m_backLeftLocation{-0.381_m, +0.381_m}; - frc::Translation2d m_backRightLocation{-0.381_m, -0.381_m}; + wpi::math::Translation2d m_frontLeftLocation{+0.381_m, +0.381_m}; + wpi::math::Translation2d m_frontRightLocation{+0.381_m, -0.381_m}; + wpi::math::Translation2d m_backLeftLocation{-0.381_m, +0.381_m}; + wpi::math::Translation2d m_backRightLocation{-0.381_m, -0.381_m}; SwerveModule m_frontLeft{1, 2, 0, 1, 2, 3}; SwerveModule m_frontRight{3, 4, 4, 5, 6, 7}; SwerveModule m_backLeft{5, 6, 8, 9, 10, 11}; SwerveModule m_backRight{7, 8, 12, 13, 14, 15}; - frc::OnboardIMU m_imu{frc::OnboardIMU::kFlat}; + wpi::OnboardIMU m_imu{wpi::OnboardIMU::kFlat}; - frc::SwerveDriveKinematics<4> m_kinematics{ + wpi::math::SwerveDriveKinematics<4> m_kinematics{ m_frontLeftLocation, m_frontRightLocation, m_backLeftLocation, m_backRightLocation}; - frc::SwerveDriveOdometry<4> m_odometry{ + wpi::math::SwerveDriveOdometry<4> m_odometry{ m_kinematics, m_imu.GetRotation2d(), {m_frontLeft.GetPosition(), m_frontRight.GetPosition(), diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveBot/include/SwerveModule.hpp b/wpilibcExamples/src/main/cpp/examples/SwerveBot/include/SwerveModule.hpp index 79fb5eae3a..1533d278a8 100644 --- a/wpilibcExamples/src/main/cpp/examples/SwerveBot/include/SwerveModule.hpp +++ b/wpilibcExamples/src/main/cpp/examples/SwerveBot/include/SwerveModule.hpp @@ -23,9 +23,9 @@ class SwerveModule { SwerveModule(int driveMotorChannel, int turningMotorChannel, int driveEncoderChannelA, int driveEncoderChannelB, int turningEncoderChannelA, int turningEncoderChannelB); - frc::SwerveModuleState GetState() const; - frc::SwerveModulePosition GetPosition() const; - void SetDesiredState(frc::SwerveModuleState& state); + wpi::math::SwerveModuleState GetState() const; + wpi::math::SwerveModulePosition GetPosition() const; + void SetDesiredState(wpi::math::SwerveModuleState& state); private: static constexpr double kWheelRadius = 0.0508; @@ -36,21 +36,21 @@ class SwerveModule { static constexpr auto kModuleMaxAngularAcceleration = std::numbers::pi * 2_rad_per_s / 1_s; // radians per second^2 - frc::PWMSparkMax m_driveMotor; - frc::PWMSparkMax m_turningMotor; + wpi::PWMSparkMax m_driveMotor; + wpi::PWMSparkMax m_turningMotor; - frc::Encoder m_driveEncoder; - frc::Encoder m_turningEncoder; + wpi::Encoder m_driveEncoder; + wpi::Encoder m_turningEncoder; - frc::PIDController m_drivePIDController{1.0, 0, 0}; - frc::ProfiledPIDController m_turningPIDController{ + wpi::math::PIDController m_drivePIDController{1.0, 0, 0}; + wpi::math::ProfiledPIDController m_turningPIDController{ 1.0, 0.0, 0.0, {kModuleMaxAngularVelocity, kModuleMaxAngularAcceleration}}; - frc::SimpleMotorFeedforward m_driveFeedforward{1_V, + wpi::math::SimpleMotorFeedforward m_driveFeedforward{1_V, 3_V / 1_mps}; - frc::SimpleMotorFeedforward m_turnFeedforward{ + wpi::math::SimpleMotorFeedforward m_turnFeedforward{ 1_V, 0.5_V / 1_rad_per_s}; }; diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/cpp/Drivetrain.cpp b/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/cpp/Drivetrain.cpp index f75f86a8d2..f1e0d00e6b 100644 --- a/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/cpp/Drivetrain.cpp +++ b/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/cpp/Drivetrain.cpp @@ -8,11 +8,11 @@ #include "ExampleGlobalMeasurementSensor.hpp" -void Drivetrain::Drive(units::meters_per_second_t xSpeed, - units::meters_per_second_t ySpeed, - units::radians_per_second_t rot, bool fieldRelative, - units::second_t period) { - frc::ChassisSpeeds chassisSpeeds{xSpeed, ySpeed, rot}; +void Drivetrain::Drive(wpi::units::meters_per_second_t xSpeed, + wpi::units::meters_per_second_t ySpeed, + wpi::units::radians_per_second_t rot, bool fieldRelative, + wpi::units::second_t period) { + wpi::math::ChassisSpeeds chassisSpeeds{xSpeed, ySpeed, rot}; if (fieldRelative) { chassisSpeeds = chassisSpeeds.ToRobotRelative( m_poseEstimator.GetEstimatedPosition().Rotation()); @@ -40,5 +40,5 @@ void Drivetrain::UpdateOdometry() { m_poseEstimator.AddVisionMeasurement( ExampleGlobalMeasurementSensor::GetEstimatedGlobalPose( m_poseEstimator.GetEstimatedPosition()), - frc::Timer::GetTimestamp() - 0.3_s); + wpi::Timer::GetTimestamp() - 0.3_s); } diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/cpp/Robot.cpp index 4382b8ef17..e8956a6d2b 100644 --- a/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/cpp/Robot.cpp @@ -8,7 +8,7 @@ #include "Drivetrain.hpp" -class Robot : public frc::TimedRobot { +class Robot : public wpi::TimedRobot { public: void AutonomousPeriodic() override { DriveWithJoystick(false); @@ -18,14 +18,14 @@ class Robot : public frc::TimedRobot { void TeleopPeriodic() override { DriveWithJoystick(true); } private: - frc::XboxController m_controller{0}; + wpi::XboxController m_controller{0}; Drivetrain m_swerve; // Slew rate limiters to make joystick inputs more gentle; 1/3 sec from 0 // to 1. - frc::SlewRateLimiter m_xspeedLimiter{3 / 1_s}; - frc::SlewRateLimiter m_yspeedLimiter{3 / 1_s}; - frc::SlewRateLimiter m_rotLimiter{3 / 1_s}; + wpi::math::SlewRateLimiter m_xspeedLimiter{3 / 1_s}; + wpi::math::SlewRateLimiter m_yspeedLimiter{3 / 1_s}; + wpi::math::SlewRateLimiter m_rotLimiter{3 / 1_s}; void DriveWithJoystick(bool fieldRelative) { // Get the x speed. We are inverting this because Xbox controllers return @@ -52,6 +52,6 @@ class Robot : public frc::TimedRobot { #ifndef RUNNING_FRC_TESTS int main() { - return frc::StartRobot(); + return wpi::StartRobot(); } #endif diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/cpp/SwerveModule.cpp b/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/cpp/SwerveModule.cpp index 408295180f..fbbd410046 100644 --- a/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/cpp/SwerveModule.cpp +++ b/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/cpp/SwerveModule.cpp @@ -33,22 +33,22 @@ SwerveModule::SwerveModule(const int driveMotorChannel, // Limit the PID Controller's input range between -pi and pi and set the input // to be continuous. m_turningPIDController.EnableContinuousInput( - -units::radian_t{std::numbers::pi}, units::radian_t{std::numbers::pi}); + -wpi::units::radian_t{std::numbers::pi}, wpi::units::radian_t{std::numbers::pi}); } -frc::SwerveModuleState SwerveModule::GetState() const { - return {units::meters_per_second_t{m_driveEncoder.GetRate()}, - units::radian_t{m_turningEncoder.GetDistance()}}; +wpi::math::SwerveModuleState SwerveModule::GetState() const { + return {wpi::units::meters_per_second_t{m_driveEncoder.GetRate()}, + wpi::units::radian_t{m_turningEncoder.GetDistance()}}; } -frc::SwerveModulePosition SwerveModule::GetPosition() const { - return {units::meter_t{m_driveEncoder.GetDistance()}, - units::radian_t{m_turningEncoder.GetDistance()}}; +wpi::math::SwerveModulePosition SwerveModule::GetPosition() const { + return {wpi::units::meter_t{m_driveEncoder.GetDistance()}, + wpi::units::radian_t{m_turningEncoder.GetDistance()}}; } -void SwerveModule::SetDesiredState(frc::SwerveModuleState& referenceState) { - frc::Rotation2d encoderRotation{ - units::radian_t{m_turningEncoder.GetDistance()}}; +void SwerveModule::SetDesiredState(wpi::math::SwerveModuleState& referenceState) { + wpi::math::Rotation2d encoderRotation{ + wpi::units::radian_t{m_turningEncoder.GetDistance()}}; // Optimize the reference state to avoid spinning further than 90 degrees referenceState.Optimize(encoderRotation); @@ -67,13 +67,13 @@ void SwerveModule::SetDesiredState(frc::SwerveModuleState& referenceState) { // Calculate the turning motor output from the turning PID controller. const auto turnOutput = m_turningPIDController.Calculate( - units::radian_t{m_turningEncoder.GetDistance()}, + wpi::units::radian_t{m_turningEncoder.GetDistance()}, referenceState.angle.Radians()); const auto turnFeedforward = m_turnFeedforward.Calculate( m_turningPIDController.GetSetpoint().velocity); // Set the motor outputs. - m_driveMotor.SetVoltage(units::volt_t{driveOutput} + driveFeedforward); - m_turningMotor.SetVoltage(units::volt_t{turnOutput} + turnFeedforward); + m_driveMotor.SetVoltage(wpi::units::volt_t{driveOutput} + driveFeedforward); + m_turningMotor.SetVoltage(wpi::units::volt_t{turnOutput} + turnFeedforward); } diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/include/Drivetrain.hpp b/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/include/Drivetrain.hpp index 6a8d900b0d..88d36615c6 100644 --- a/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/include/Drivetrain.hpp +++ b/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/include/Drivetrain.hpp @@ -21,40 +21,40 @@ class Drivetrain { public: Drivetrain() { m_imu.ResetYaw(); } - void Drive(units::meters_per_second_t xSpeed, - units::meters_per_second_t ySpeed, units::radians_per_second_t rot, - bool fieldRelative, units::second_t period); + void Drive(wpi::units::meters_per_second_t xSpeed, + wpi::units::meters_per_second_t ySpeed, wpi::units::radians_per_second_t rot, + bool fieldRelative, wpi::units::second_t period); void UpdateOdometry(); static constexpr auto kMaxSpeed = 3.0_mps; // 3 meters per second - static constexpr units::radians_per_second_t kMaxAngularSpeed{ + static constexpr wpi::units::radians_per_second_t kMaxAngularSpeed{ std::numbers::pi}; // 1/2 rotation per second private: - frc::Translation2d m_frontLeftLocation{+0.381_m, +0.381_m}; - frc::Translation2d m_frontRightLocation{+0.381_m, -0.381_m}; - frc::Translation2d m_backLeftLocation{-0.381_m, +0.381_m}; - frc::Translation2d m_backRightLocation{-0.381_m, -0.381_m}; + wpi::math::Translation2d m_frontLeftLocation{+0.381_m, +0.381_m}; + wpi::math::Translation2d m_frontRightLocation{+0.381_m, -0.381_m}; + wpi::math::Translation2d m_backLeftLocation{-0.381_m, +0.381_m}; + wpi::math::Translation2d m_backRightLocation{-0.381_m, -0.381_m}; SwerveModule m_frontLeft{1, 2, 0, 1, 2, 3}; SwerveModule m_frontRight{3, 4, 4, 5, 6, 7}; SwerveModule m_backLeft{5, 6, 8, 9, 10, 11}; SwerveModule m_backRight{7, 8, 12, 13, 14, 15}; - frc::OnboardIMU m_imu{frc::OnboardIMU::kFlat}; + wpi::OnboardIMU m_imu{wpi::OnboardIMU::kFlat}; - frc::SwerveDriveKinematics<4> m_kinematics{ + wpi::math::SwerveDriveKinematics<4> m_kinematics{ m_frontLeftLocation, m_frontRightLocation, m_backLeftLocation, m_backRightLocation}; // Gains are for example purposes only - must be determined for your own // robot! - frc::SwerveDrivePoseEstimator<4> m_poseEstimator{ + wpi::math::SwerveDrivePoseEstimator<4> m_poseEstimator{ m_kinematics, - frc::Rotation2d{}, + wpi::math::Rotation2d{}, {m_frontLeft.GetPosition(), m_frontRight.GetPosition(), m_backLeft.GetPosition(), m_backRight.GetPosition()}, - frc::Pose2d{}, + wpi::math::Pose2d{}, {0.1, 0.1, 0.1}, {0.1, 0.1, 0.1}}; }; diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/include/ExampleGlobalMeasurementSensor.hpp b/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/include/ExampleGlobalMeasurementSensor.hpp index d4f9b4e52f..16f4123f08 100644 --- a/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/include/ExampleGlobalMeasurementSensor.hpp +++ b/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/include/ExampleGlobalMeasurementSensor.hpp @@ -13,12 +13,12 @@ */ class ExampleGlobalMeasurementSensor { public: - static frc::Pose2d GetEstimatedGlobalPose( - const frc::Pose2d& estimatedRobotPose) { - auto randVec = frc::MakeWhiteNoiseVector(0.1, 0.1, 0.1); - return frc::Pose2d{estimatedRobotPose.X() + units::meter_t{randVec(0)}, - estimatedRobotPose.Y() + units::meter_t{randVec(1)}, + static wpi::math::Pose2d GetEstimatedGlobalPose( + const wpi::math::Pose2d& estimatedRobotPose) { + auto randVec = wpi::math::MakeWhiteNoiseVector(0.1, 0.1, 0.1); + return wpi::math::Pose2d{estimatedRobotPose.X() + wpi::units::meter_t{randVec(0)}, + estimatedRobotPose.Y() + wpi::units::meter_t{randVec(1)}, estimatedRobotPose.Rotation() + - frc::Rotation2d{units::radian_t{randVec(2)}}}; + wpi::math::Rotation2d{wpi::units::radian_t{randVec(2)}}}; } }; diff --git a/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/include/SwerveModule.hpp b/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/include/SwerveModule.hpp index 044c8b4f0e..f00bc07e7e 100644 --- a/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/include/SwerveModule.hpp +++ b/wpilibcExamples/src/main/cpp/examples/SwerveDrivePoseEstimator/include/SwerveModule.hpp @@ -23,9 +23,9 @@ class SwerveModule { SwerveModule(int driveMotorChannel, int turningMotorChannel, int driveEncoderChannelA, int driveEncoderChannelB, int turningEncoderChannelA, int turningEncoderChannelB); - frc::SwerveModuleState GetState() const; - frc::SwerveModulePosition GetPosition() const; - void SetDesiredState(frc::SwerveModuleState& state); + wpi::math::SwerveModuleState GetState() const; + wpi::math::SwerveModulePosition GetPosition() const; + void SetDesiredState(wpi::math::SwerveModuleState& state); private: static constexpr auto kWheelRadius = 0.0508_m; @@ -36,21 +36,21 @@ class SwerveModule { static constexpr auto kModuleMaxAngularAcceleration = std::numbers::pi * 2_rad_per_s / 1_s; // radians per second^2 - frc::PWMSparkMax m_driveMotor; - frc::PWMSparkMax m_turningMotor; + wpi::PWMSparkMax m_driveMotor; + wpi::PWMSparkMax m_turningMotor; - frc::Encoder m_driveEncoder; - frc::Encoder m_turningEncoder; + wpi::Encoder m_driveEncoder; + wpi::Encoder m_turningEncoder; - frc::PIDController m_drivePIDController{1.0, 0, 0}; - frc::ProfiledPIDController m_turningPIDController{ + wpi::math::PIDController m_drivePIDController{1.0, 0, 0}; + wpi::math::ProfiledPIDController m_turningPIDController{ 1.0, 0.0, 0.0, {kModuleMaxAngularVelocity, kModuleMaxAngularAcceleration}}; - frc::SimpleMotorFeedforward m_driveFeedforward{1_V, + wpi::math::SimpleMotorFeedforward m_driveFeedforward{1_V, 3_V / 1_mps}; - frc::SimpleMotorFeedforward m_turnFeedforward{ + wpi::math::SimpleMotorFeedforward m_turnFeedforward{ 1_V, 0.5_V / 1_rad_per_s}; }; diff --git a/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/cpp/Robot.cpp index 9b66f55e3d..c1390561da 100644 --- a/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/cpp/Robot.cpp @@ -9,7 +9,7 @@ Robot::Robot() {} void Robot::RobotPeriodic() { - frc2::CommandScheduler::GetInstance().Run(); + wpi::cmd::CommandScheduler::GetInstance().Run(); } void Robot::DisabledInit() {} @@ -22,7 +22,7 @@ void Robot::AutonomousInit() { m_autonomousCommand = m_container.GetAutonomousCommand(); if (m_autonomousCommand) { - frc2::CommandScheduler::GetInstance().Schedule(m_autonomousCommand.value()); + wpi::cmd::CommandScheduler::GetInstance().Schedule(m_autonomousCommand.value()); } } @@ -41,7 +41,7 @@ void Robot::TeleopPeriodic() {} void Robot::TeleopExit() {} void Robot::TestInit() { - frc2::CommandScheduler::GetInstance().CancelAll(); + wpi::cmd::CommandScheduler::GetInstance().CancelAll(); } void Robot::TestPeriodic() {} @@ -50,6 +50,6 @@ void Robot::TestExit() {} #ifndef RUNNING_FRC_TESTS int main() { - return frc::StartRobot(); + return wpi::StartRobot(); } #endif diff --git a/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/cpp/SysIdRoutineBot.cpp b/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/cpp/SysIdRoutineBot.cpp index 83f5444991..4928c0e06b 100644 --- a/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/cpp/SysIdRoutineBot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/cpp/SysIdRoutineBot.cpp @@ -18,27 +18,27 @@ void SysIdRoutineBot::ConfigureBindings() { // Using bumpers as a modifier and combining it with the buttons so that we // can have both sets of bindings at once (m_driverController.A() && m_driverController.RightBumper()) - .WhileTrue(m_drive.SysIdQuasistatic(frc2::sysid::Direction::kForward)); + .WhileTrue(m_drive.SysIdQuasistatic(wpi::cmd::sysid::Direction::kForward)); (m_driverController.B() && m_driverController.RightBumper()) - .WhileTrue(m_drive.SysIdQuasistatic(frc2::sysid::Direction::kReverse)); + .WhileTrue(m_drive.SysIdQuasistatic(wpi::cmd::sysid::Direction::kReverse)); (m_driverController.X() && m_driverController.RightBumper()) - .WhileTrue(m_drive.SysIdDynamic(frc2::sysid::Direction::kForward)); + .WhileTrue(m_drive.SysIdDynamic(wpi::cmd::sysid::Direction::kForward)); (m_driverController.Y() && m_driverController.RightBumper()) - .WhileTrue(m_drive.SysIdDynamic(frc2::sysid::Direction::kReverse)); + .WhileTrue(m_drive.SysIdDynamic(wpi::cmd::sysid::Direction::kReverse)); m_shooter.SetDefaultCommand(m_shooter.RunShooterCommand( [this] { return m_driverController.GetLeftTriggerAxis(); })); (m_driverController.A() && m_driverController.LeftBumper()) - .WhileTrue(m_shooter.SysIdQuasistatic(frc2::sysid::Direction::kForward)); + .WhileTrue(m_shooter.SysIdQuasistatic(wpi::cmd::sysid::Direction::kForward)); (m_driverController.B() && m_driverController.LeftBumper()) - .WhileTrue(m_shooter.SysIdQuasistatic(frc2::sysid::Direction::kReverse)); + .WhileTrue(m_shooter.SysIdQuasistatic(wpi::cmd::sysid::Direction::kReverse)); (m_driverController.X() && m_driverController.LeftBumper()) - .WhileTrue(m_shooter.SysIdDynamic(frc2::sysid::Direction::kForward)); + .WhileTrue(m_shooter.SysIdDynamic(wpi::cmd::sysid::Direction::kForward)); (m_driverController.Y() && m_driverController.LeftBumper()) - .WhileTrue(m_shooter.SysIdDynamic(frc2::sysid::Direction::kReverse)); + .WhileTrue(m_shooter.SysIdDynamic(wpi::cmd::sysid::Direction::kReverse)); } -frc2::CommandPtr SysIdRoutineBot::GetAutonomousCommand() { +wpi::cmd::CommandPtr SysIdRoutineBot::GetAutonomousCommand() { return m_drive.Run([] {}); } diff --git a/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/cpp/subsystems/Drive.cpp b/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/cpp/subsystems/Drive.cpp index 94fde5eb2d..2cec8fe5d3 100644 --- a/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/cpp/subsystems/Drive.cpp +++ b/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/cpp/subsystems/Drive.cpp @@ -7,9 +7,9 @@ #include Drive::Drive() { - m_leftMotor.AddFollower(frc::PWMSparkMax{constants::drive::kLeftMotor2Port}); + m_leftMotor.AddFollower(wpi::PWMSparkMax{constants::drive::kLeftMotor2Port}); m_rightMotor.AddFollower( - frc::PWMSparkMax{constants::drive::kRightMotor2Port}); + wpi::PWMSparkMax{constants::drive::kRightMotor2Port}); m_rightMotor.SetInverted(true); @@ -21,17 +21,17 @@ Drive::Drive() { m_drive.SetSafetyEnabled(false); } -frc2::CommandPtr Drive::ArcadeDriveCommand(std::function fwd, +wpi::cmd::CommandPtr Drive::ArcadeDriveCommand(std::function fwd, std::function rot) { - return frc2::cmd::Run([this, fwd, rot] { m_drive.ArcadeDrive(fwd(), rot()); }, + return wpi::cmd::cmd::Run([this, fwd, rot] { m_drive.ArcadeDrive(fwd(), rot()); }, {this}) .WithName("Arcade Drive"); } -frc2::CommandPtr Drive::SysIdQuasistatic(frc2::sysid::Direction direction) { +wpi::cmd::CommandPtr Drive::SysIdQuasistatic(wpi::cmd::sysid::Direction direction) { return m_sysIdRoutine.Quasistatic(direction); } -frc2::CommandPtr Drive::SysIdDynamic(frc2::sysid::Direction direction) { +wpi::cmd::CommandPtr Drive::SysIdDynamic(wpi::cmd::sysid::Direction direction) { return m_sysIdRoutine.Dynamic(direction); } diff --git a/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/cpp/subsystems/Shooter.cpp b/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/cpp/subsystems/Shooter.cpp index fb0a2d8fa6..d54b2ada92 100644 --- a/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/cpp/subsystems/Shooter.cpp +++ b/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/cpp/subsystems/Shooter.cpp @@ -13,25 +13,25 @@ Shooter::Shooter() { constants::shooter::kEncoderDistancePerPulse.value()); } -frc2::CommandPtr Shooter::RunShooterCommand( +wpi::cmd::CommandPtr Shooter::RunShooterCommand( std::function shooterSpeed) { - return frc2::cmd::Run( + return wpi::cmd::cmd::Run( [this, shooterSpeed] { m_shooterMotor.SetVoltage( - units::volt_t{m_shooterFeedback.Calculate( + wpi::units::volt_t{m_shooterFeedback.Calculate( m_shooterEncoder.GetRate(), shooterSpeed())} + m_shooterFeedforward.Calculate( - units::turns_per_second_t{shooterSpeed()})); + wpi::units::turns_per_second_t{shooterSpeed()})); m_feederMotor.Set(constants::shooter::kFeederSpeed); }, {this}) .WithName("Set Shooter Speed"); } -frc2::CommandPtr Shooter::SysIdQuasistatic(frc2::sysid::Direction direction) { +wpi::cmd::CommandPtr Shooter::SysIdQuasistatic(wpi::cmd::sysid::Direction direction) { return m_sysIdRoutine.Quasistatic(direction); } -frc2::CommandPtr Shooter::SysIdDynamic(frc2::sysid::Direction direction) { +wpi::cmd::CommandPtr Shooter::SysIdDynamic(wpi::cmd::sysid::Direction direction) { return m_sysIdRoutine.Dynamic(direction); } diff --git a/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/include/Constants.hpp b/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/include/Constants.hpp index 51c6058fe1..77cb1ccbae 100644 --- a/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/include/Constants.hpp +++ b/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/include/Constants.hpp @@ -27,39 +27,39 @@ inline constexpr bool kLeftEncoderReversed = false; inline constexpr bool kRightEncoderReversed = true; inline constexpr int kEncoderCpr = 1024; -inline constexpr units::meter_t kWheelDiameter = 6_in; -inline constexpr units::meter_t kEncoderDistancePerPulse = +inline constexpr wpi::units::meter_t kWheelDiameter = 6_in; +inline constexpr wpi::units::meter_t kEncoderDistancePerPulse = (kWheelDiameter * std::numbers::pi) / static_cast(kEncoderCpr); } // namespace drive namespace shooter { using kv_unit = - units::compound_unit, - units::inverse>; -using kv_unit_t = units::unit_t; + wpi::units::compound_unit, + wpi::units::inverse>; +using kv_unit_t = wpi::units::unit_t; using ka_unit = - units::compound_unit>; -using ka_unit_t = units::unit_t; + wpi::units::compound_unit>; +using ka_unit_t = wpi::units::unit_t; inline constexpr std::array kEncoderPorts = {4, 5}; inline constexpr bool kEncoderReversed = false; inline constexpr int kEncoderCpr = 1024; -inline constexpr units::turn_t kEncoderDistancePerPulse = +inline constexpr wpi::units::turn_t kEncoderDistancePerPulse = 1_tr / static_cast(kEncoderCpr); inline constexpr int kShooterMotorPort = 4; inline constexpr int kFeederMotorPort = 5; -inline constexpr units::turns_per_second_t kShooterFreeSpeed = 5300_tps; -inline constexpr units::turns_per_second_t kShooterTargetSpeed = 4000_tps; -inline constexpr units::turns_per_second_t kShooterTolerance = 50_tps; +inline constexpr wpi::units::turns_per_second_t kShooterFreeSpeed = 5300_tps; +inline constexpr wpi::units::turns_per_second_t kShooterTargetSpeed = 4000_tps; +inline constexpr wpi::units::turns_per_second_t kShooterTolerance = 50_tps; inline constexpr double kP = 1.0; -inline constexpr units::volt_t kS = 0.05_V; +inline constexpr wpi::units::volt_t kS = 0.05_V; inline constexpr kv_unit_t kV = 12_V / kShooterFreeSpeed; inline constexpr ka_unit_t kA = 0_V * 1_s * 1_s / 1_tr; @@ -77,8 +77,8 @@ inline constexpr int kBallSensorPort = 6; } // namespace storage namespace autonomous { -inline constexpr units::second_t kTimeout = 3_s; -inline constexpr units::meter_t kDriveDistance = 2_m; +inline constexpr wpi::units::second_t kTimeout = 3_s; +inline constexpr wpi::units::meter_t kDriveDistance = 2_m; inline constexpr double kDriveSpeed = 0.5; } // namespace autonomous diff --git a/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/include/Robot.hpp b/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/include/Robot.hpp index e7ff10a265..249141697b 100644 --- a/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/include/Robot.hpp +++ b/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/include/Robot.hpp @@ -11,7 +11,7 @@ #include "SysIdRoutineBot.hpp" -class Robot : public frc::TimedRobot { +class Robot : public wpi::TimedRobot { public: Robot(); void RobotPeriodic() override; @@ -29,7 +29,7 @@ class Robot : public frc::TimedRobot { void TestExit() override; private: - std::optional m_autonomousCommand; + std::optional m_autonomousCommand; SysIdRoutineBot m_container; }; diff --git a/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/include/SysIdRoutineBot.hpp b/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/include/SysIdRoutineBot.hpp index dd8f994ffb..1671736957 100644 --- a/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/include/SysIdRoutineBot.hpp +++ b/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/include/SysIdRoutineBot.hpp @@ -15,11 +15,11 @@ class SysIdRoutineBot { public: SysIdRoutineBot(); - frc2::CommandPtr GetAutonomousCommand(); + wpi::cmd::CommandPtr GetAutonomousCommand(); private: void ConfigureBindings(); - frc2::CommandXboxController m_driverController{ + wpi::cmd::CommandXboxController m_driverController{ constants::oi::kDriverControllerPort}; Drive m_drive; Shooter m_shooter; diff --git a/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/include/subsystems/Drive.hpp b/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/include/subsystems/Drive.hpp index 164bcfef04..a3130d2513 100644 --- a/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/include/subsystems/Drive.hpp +++ b/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/include/subsystems/Drive.hpp @@ -15,47 +15,47 @@ #include "Constants.hpp" -class Drive : public frc2::SubsystemBase { +class Drive : public wpi::cmd::SubsystemBase { public: Drive(); - frc2::CommandPtr ArcadeDriveCommand(std::function fwd, + wpi::cmd::CommandPtr ArcadeDriveCommand(std::function fwd, std::function rot); - frc2::CommandPtr SysIdQuasistatic(frc2::sysid::Direction direction); - frc2::CommandPtr SysIdDynamic(frc2::sysid::Direction direction); + wpi::cmd::CommandPtr SysIdQuasistatic(wpi::cmd::sysid::Direction direction); + wpi::cmd::CommandPtr SysIdDynamic(wpi::cmd::sysid::Direction direction); private: - frc::PWMSparkMax m_leftMotor{constants::drive::kLeftMotor1Port}; - frc::PWMSparkMax m_rightMotor{constants::drive::kRightMotor1Port}; - frc::DifferentialDrive m_drive{[this](auto val) { m_leftMotor.Set(val); }, + wpi::PWMSparkMax m_leftMotor{constants::drive::kLeftMotor1Port}; + wpi::PWMSparkMax m_rightMotor{constants::drive::kRightMotor1Port}; + wpi::DifferentialDrive m_drive{[this](auto val) { m_leftMotor.Set(val); }, [this](auto val) { m_rightMotor.Set(val); }}; - frc::Encoder m_leftEncoder{constants::drive::kLeftEncoderPorts[0], + wpi::Encoder m_leftEncoder{constants::drive::kLeftEncoderPorts[0], constants::drive::kLeftEncoderPorts[1], constants::drive::kLeftEncoderReversed}; - frc::Encoder m_rightEncoder{constants::drive::kRightEncoderPorts[0], + wpi::Encoder m_rightEncoder{constants::drive::kRightEncoderPorts[0], constants::drive::kRightEncoderPorts[1], constants::drive::kRightEncoderReversed}; - frc2::sysid::SysIdRoutine m_sysIdRoutine{ - frc2::sysid::Config{std::nullopt, std::nullopt, std::nullopt, nullptr}, - frc2::sysid::Mechanism{ - [this](units::volt_t driveVoltage) { + wpi::cmd::sysid::SysIdRoutine m_sysIdRoutine{ + wpi::cmd::sysid::Config{std::nullopt, std::nullopt, std::nullopt, nullptr}, + wpi::cmd::sysid::Mechanism{ + [this](wpi::units::volt_t driveVoltage) { m_leftMotor.SetVoltage(driveVoltage); m_rightMotor.SetVoltage(driveVoltage); }, - [this](frc::sysid::SysIdRoutineLog* log) { + [this](wpi::sysid::SysIdRoutineLog* log) { log->Motor("drive-left") .voltage(m_leftMotor.Get() * - frc::RobotController::GetBatteryVoltage()) - .position(units::meter_t{m_leftEncoder.GetDistance()}) - .velocity(units::meters_per_second_t{m_leftEncoder.GetRate()}); + wpi::RobotController::GetBatteryVoltage()) + .position(wpi::units::meter_t{m_leftEncoder.GetDistance()}) + .velocity(wpi::units::meters_per_second_t{m_leftEncoder.GetRate()}); log->Motor("drive-right") .voltage(m_rightMotor.Get() * - frc::RobotController::GetBatteryVoltage()) - .position(units::meter_t{m_rightEncoder.GetDistance()}) - .velocity(units::meters_per_second_t{m_rightEncoder.GetRate()}); + wpi::RobotController::GetBatteryVoltage()) + .position(wpi::units::meter_t{m_rightEncoder.GetDistance()}) + .velocity(wpi::units::meters_per_second_t{m_rightEncoder.GetRate()}); }, this}}; }; diff --git a/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/include/subsystems/Shooter.hpp b/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/include/subsystems/Shooter.hpp index 8041518a1a..c762d7a9c5 100644 --- a/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/include/subsystems/Shooter.hpp +++ b/wpilibcExamples/src/main/cpp/examples/SysIdRoutine/include/subsystems/Shooter.hpp @@ -16,38 +16,38 @@ #include "Constants.hpp" -class Shooter : public frc2::SubsystemBase { +class Shooter : public wpi::cmd::SubsystemBase { public: Shooter(); - frc2::CommandPtr RunShooterCommand(std::function shooterSpeed); - frc2::CommandPtr SysIdQuasistatic(frc2::sysid::Direction direction); - frc2::CommandPtr SysIdDynamic(frc2::sysid::Direction direction); + wpi::cmd::CommandPtr RunShooterCommand(std::function shooterSpeed); + wpi::cmd::CommandPtr SysIdQuasistatic(wpi::cmd::sysid::Direction direction); + wpi::cmd::CommandPtr SysIdDynamic(wpi::cmd::sysid::Direction direction); private: - frc::PWMSparkMax m_shooterMotor{constants::shooter::kShooterMotorPort}; - frc::PWMSparkMax m_feederMotor{constants::shooter::kFeederMotorPort}; + wpi::PWMSparkMax m_shooterMotor{constants::shooter::kShooterMotorPort}; + wpi::PWMSparkMax m_feederMotor{constants::shooter::kFeederMotorPort}; - frc::Encoder m_shooterEncoder{constants::shooter::kEncoderPorts[0], + wpi::Encoder m_shooterEncoder{constants::shooter::kEncoderPorts[0], constants::shooter::kEncoderPorts[1], constants::shooter::kEncoderReversed}; - frc2::sysid::SysIdRoutine m_sysIdRoutine{ - frc2::sysid::Config{std::nullopt, std::nullopt, std::nullopt, nullptr}, - frc2::sysid::Mechanism{ - [this](units::volt_t driveVoltage) { + wpi::cmd::sysid::SysIdRoutine m_sysIdRoutine{ + wpi::cmd::sysid::Config{std::nullopt, std::nullopt, std::nullopt, nullptr}, + wpi::cmd::sysid::Mechanism{ + [this](wpi::units::volt_t driveVoltage) { m_shooterMotor.SetVoltage(driveVoltage); }, - [this](frc::sysid::SysIdRoutineLog* log) { + [this](wpi::sysid::SysIdRoutineLog* log) { log->Motor("shooter-wheel") .voltage(m_shooterMotor.Get() * - frc::RobotController::GetBatteryVoltage()) - .position(units::turn_t{m_shooterEncoder.GetDistance()}) + wpi::RobotController::GetBatteryVoltage()) + .position(wpi::units::turn_t{m_shooterEncoder.GetDistance()}) .velocity( - units::turns_per_second_t{m_shooterEncoder.GetRate()}); + wpi::units::turns_per_second_t{m_shooterEncoder.GetRate()}); }, this}}; - frc::PIDController m_shooterFeedback{constants::shooter::kP, 0, 0}; - frc::SimpleMotorFeedforward m_shooterFeedforward{ + wpi::math::PIDController m_shooterFeedback{constants::shooter::kP, 0, 0}; + wpi::math::SimpleMotorFeedforward m_shooterFeedforward{ constants::shooter::kS, constants::shooter::kV, constants::shooter::kA}; }; diff --git a/wpilibcExamples/src/main/cpp/examples/TankDrive/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/TankDrive/cpp/Robot.cpp index a803c23494..5bd3cbfdd5 100644 --- a/wpilibcExamples/src/main/cpp/examples/TankDrive/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/TankDrive/cpp/Robot.cpp @@ -11,19 +11,19 @@ * This is a demo program showing the use of the DifferentialDrive class. * Runs the motors with tank steering. */ -class Robot : public frc::TimedRobot { - frc::PWMSparkMax m_leftMotor{0}; - frc::PWMSparkMax m_rightMotor{1}; - frc::DifferentialDrive m_robotDrive{ +class Robot : public wpi::TimedRobot { + wpi::PWMSparkMax m_leftMotor{0}; + wpi::PWMSparkMax m_rightMotor{1}; + wpi::DifferentialDrive m_robotDrive{ [&](double output) { m_leftMotor.Set(output); }, [&](double output) { m_rightMotor.Set(output); }}; - frc::Joystick m_leftStick{0}; - frc::Joystick m_rightStick{1}; + wpi::Joystick m_leftStick{0}; + wpi::Joystick m_rightStick{1}; public: Robot() { - wpi::SendableRegistry::AddChild(&m_robotDrive, &m_leftMotor); - wpi::SendableRegistry::AddChild(&m_robotDrive, &m_rightMotor); + wpi::util::SendableRegistry::AddChild(&m_robotDrive, &m_leftMotor); + wpi::util::SendableRegistry::AddChild(&m_robotDrive, &m_rightMotor); // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's @@ -39,6 +39,6 @@ class Robot : public frc::TimedRobot { #ifndef RUNNING_FRC_TESTS int main() { - return frc::StartRobot(); + return wpi::StartRobot(); } #endif diff --git a/wpilibcExamples/src/main/cpp/examples/TankDriveXboxController/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/TankDriveXboxController/cpp/Robot.cpp index bf95821712..667d40b2fa 100644 --- a/wpilibcExamples/src/main/cpp/examples/TankDriveXboxController/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/TankDriveXboxController/cpp/Robot.cpp @@ -11,18 +11,18 @@ * This is a demo program showing the use of the DifferentialDrive class. * Runs the motors with tank steering and an Xbox controller. */ -class Robot : public frc::TimedRobot { - frc::PWMSparkMax m_leftMotor{0}; - frc::PWMSparkMax m_rightMotor{1}; - frc::DifferentialDrive m_robotDrive{ +class Robot : public wpi::TimedRobot { + wpi::PWMSparkMax m_leftMotor{0}; + wpi::PWMSparkMax m_rightMotor{1}; + wpi::DifferentialDrive m_robotDrive{ [&](double output) { m_leftMotor.Set(output); }, [&](double output) { m_rightMotor.Set(output); }}; - frc::XboxController m_driverController{0}; + wpi::XboxController m_driverController{0}; public: Robot() { - wpi::SendableRegistry::AddChild(&m_robotDrive, &m_leftMotor); - wpi::SendableRegistry::AddChild(&m_robotDrive, &m_rightMotor); + wpi::util::SendableRegistry::AddChild(&m_robotDrive, &m_leftMotor); + wpi::util::SendableRegistry::AddChild(&m_robotDrive, &m_rightMotor); // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's @@ -39,6 +39,6 @@ class Robot : public frc::TimedRobot { #ifndef RUNNING_FRC_TESTS int main() { - return frc::StartRobot(); + return wpi::StartRobot(); } #endif diff --git a/wpilibcExamples/src/main/cpp/examples/UnitTest/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/UnitTest/cpp/Robot.cpp index 402f648df8..ee6d5fe86a 100644 --- a/wpilibcExamples/src/main/cpp/examples/UnitTest/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/UnitTest/cpp/Robot.cpp @@ -27,6 +27,6 @@ void Robot::TeleopPeriodic() { #ifndef RUNNING_FRC_TESTS int main() { - return frc::StartRobot(); + return wpi::StartRobot(); } #endif diff --git a/wpilibcExamples/src/main/cpp/examples/UnitTest/cpp/subsystems/Intake.cpp b/wpilibcExamples/src/main/cpp/examples/UnitTest/cpp/subsystems/Intake.cpp index 2f5241ee6f..ff6ae2719a 100644 --- a/wpilibcExamples/src/main/cpp/examples/UnitTest/cpp/subsystems/Intake.cpp +++ b/wpilibcExamples/src/main/cpp/examples/UnitTest/cpp/subsystems/Intake.cpp @@ -5,11 +5,11 @@ #include "subsystems/Intake.hpp" void Intake::Deploy() { - m_piston.Set(frc::DoubleSolenoid::Value::kForward); + m_piston.Set(wpi::DoubleSolenoid::Value::kForward); } void Intake::Retract() { - m_piston.Set(frc::DoubleSolenoid::Value::kReverse); + m_piston.Set(wpi::DoubleSolenoid::Value::kReverse); m_motor.Set(0); // turn off the motor } @@ -22,5 +22,5 @@ void Intake::Activate(double speed) { } bool Intake::IsDeployed() const { - return m_piston.Get() == frc::DoubleSolenoid::Value::kForward; + return m_piston.Get() == wpi::DoubleSolenoid::Value::kForward; } diff --git a/wpilibcExamples/src/main/cpp/examples/UnitTest/include/Robot.hpp b/wpilibcExamples/src/main/cpp/examples/UnitTest/include/Robot.hpp index e47864d3a5..3f850ede06 100644 --- a/wpilibcExamples/src/main/cpp/examples/UnitTest/include/Robot.hpp +++ b/wpilibcExamples/src/main/cpp/examples/UnitTest/include/Robot.hpp @@ -10,11 +10,11 @@ #include "Constants.hpp" #include "subsystems/Intake.hpp" -class Robot : public frc::TimedRobot { +class Robot : public wpi::TimedRobot { public: void TeleopPeriodic() override; private: Intake m_intake; - frc::Joystick m_joystick{OperatorConstants::kJoystickIndex}; + wpi::Joystick m_joystick{OperatorConstants::kJoystickIndex}; }; diff --git a/wpilibcExamples/src/main/cpp/examples/UnitTest/include/subsystems/Intake.hpp b/wpilibcExamples/src/main/cpp/examples/UnitTest/include/subsystems/Intake.hpp index 9305a51c6b..44a82c0fd0 100644 --- a/wpilibcExamples/src/main/cpp/examples/UnitTest/include/subsystems/Intake.hpp +++ b/wpilibcExamples/src/main/cpp/examples/UnitTest/include/subsystems/Intake.hpp @@ -17,8 +17,8 @@ class Intake { bool IsDeployed() const; private: - frc::PWMSparkMax m_motor{IntakeConstants::kMotorPort}; - frc::DoubleSolenoid m_piston{0, frc::PneumaticsModuleType::CTREPCM, + wpi::PWMSparkMax m_motor{IntakeConstants::kMotorPort}; + wpi::DoubleSolenoid m_piston{0, wpi::PneumaticsModuleType::CTREPCM, IntakeConstants::kPistonFwdChannel, IntakeConstants::kPistonRevChannel}; }; diff --git a/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/Robot.cpp index 534158dc96..35984f0b9d 100644 --- a/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/Robot.cpp @@ -17,7 +17,7 @@ Robot::Robot() {} * LiveWindow and SmartDashboard integrated updating. */ void Robot::RobotPeriodic() { - frc2::CommandScheduler::GetInstance().Run(); + wpi::cmd::CommandScheduler::GetInstance().Run(); } /** @@ -37,7 +37,7 @@ void Robot::AutonomousInit() { m_autonomousCommand = m_container.GetAutonomousCommand(); if (m_autonomousCommand != nullptr) { - frc2::CommandScheduler::GetInstance().Schedule(m_autonomousCommand); + wpi::cmd::CommandScheduler::GetInstance().Schedule(m_autonomousCommand); } } @@ -66,6 +66,6 @@ void Robot::TestPeriodic() {} #ifndef RUNNING_FRC_TESTS int main() { - return frc::StartRobot(); + return wpi::StartRobot(); } #endif diff --git a/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/RobotContainer.cpp b/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/RobotContainer.cpp index 98965eecf2..54428959a6 100644 --- a/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/RobotContainer.cpp +++ b/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/RobotContainer.cpp @@ -22,23 +22,23 @@ void RobotContainer::ConfigureButtonBindings() { [this] { return -m_controller.GetRawAxis(2); })); // Example of how to use the onboard IO - m_userButton.OnTrue(frc2::cmd::Print("USER Button Pressed")) - .OnFalse(frc2::cmd::Print("USER Button Released")); + m_userButton.OnTrue(wpi::cmd::cmd::Print("USER Button Pressed")) + .OnFalse(wpi::cmd::cmd::Print("USER Button Released")); - frc2::JoystickButton(&m_controller, 1) - .OnTrue(frc2::cmd::RunOnce([this] { m_arm.SetAngle(45_deg); }, {})) - .OnFalse(frc2::cmd::RunOnce([this] { m_arm.SetAngle(0_deg); }, {})); + wpi::cmd::JoystickButton(&m_controller, 1) + .OnTrue(wpi::cmd::cmd::RunOnce([this] { m_arm.SetAngle(45_deg); }, {})) + .OnFalse(wpi::cmd::cmd::RunOnce([this] { m_arm.SetAngle(0_deg); }, {})); - frc2::JoystickButton(&m_controller, 2) - .OnTrue(frc2::cmd::RunOnce([this] { m_arm.SetAngle(90_deg); }, {})) - .OnFalse(frc2::cmd::RunOnce([this] { m_arm.SetAngle(0_deg); }, {})); + wpi::cmd::JoystickButton(&m_controller, 2) + .OnTrue(wpi::cmd::cmd::RunOnce([this] { m_arm.SetAngle(90_deg); }, {})) + .OnFalse(wpi::cmd::cmd::RunOnce([this] { m_arm.SetAngle(0_deg); }, {})); // Setup SmartDashboard options. m_chooser.SetDefaultOption("Auto Routine Distance", &m_autoDistance); m_chooser.AddOption("Auto Routine Time", &m_autoTime); - frc::SmartDashboard::PutData("Auto Selector", &m_chooser); + wpi::SmartDashboard::PutData("Auto Selector", &m_chooser); } -frc2::Command* RobotContainer::GetAutonomousCommand() { +wpi::cmd::Command* RobotContainer::GetAutonomousCommand() { return m_chooser.GetSelected(); } diff --git a/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/commands/DriveDistance.cpp b/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/commands/DriveDistance.cpp index ae9499479f..61d67e3d08 100644 --- a/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/commands/DriveDistance.cpp +++ b/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/commands/DriveDistance.cpp @@ -20,5 +20,5 @@ void DriveDistance::End(bool interrupted) { } bool DriveDistance::IsFinished() { - return units::math::abs(m_drive->GetAverageDistance()) >= m_distance; + return wpi::units::math::abs(m_drive->GetAverageDistance()) >= m_distance; } diff --git a/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/commands/TurnDegrees.cpp b/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/commands/TurnDegrees.cpp index 8b0f96e708..ffe5a9a98e 100644 --- a/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/commands/TurnDegrees.cpp +++ b/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/commands/TurnDegrees.cpp @@ -33,8 +33,8 @@ bool TurnDegrees::IsFinished() { return GetAverageTurningDistance() >= inchPerDegree * m_angle; } -units::meter_t TurnDegrees::GetAverageTurningDistance() { - auto l = units::math::abs(m_drive->GetLeftDistance()); - auto r = units::math::abs(m_drive->GetRightDistance()); +wpi::units::meter_t TurnDegrees::GetAverageTurningDistance() { + auto l = wpi::units::math::abs(m_drive->GetLeftDistance()); + auto r = wpi::units::math::abs(m_drive->GetRightDistance()); return (l + r) / 2; } diff --git a/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/subsystems/Arm.cpp b/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/subsystems/Arm.cpp index 1bf4a48b64..ad3c122a7e 100644 --- a/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/subsystems/Arm.cpp +++ b/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/subsystems/Arm.cpp @@ -8,6 +8,6 @@ void Arm::Periodic() { // This method will be called once per scheduler run. } -void Arm::SetAngle(units::radian_t angle) { +void Arm::SetAngle(wpi::units::radian_t angle) { m_armServo.SetAngle(angle); } diff --git a/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/subsystems/Drivetrain.cpp b/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/subsystems/Drivetrain.cpp index 5bcdcd7202..6089fdc4c3 100644 --- a/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/subsystems/Drivetrain.cpp +++ b/wpilibcExamples/src/main/cpp/examples/XRPReference/cpp/subsystems/Drivetrain.cpp @@ -15,8 +15,8 @@ using namespace DriveConstants; // The XRP has onboard encoders that are hardcoded // to use DIO pins 4/5 and 6/7 for the left and right Drivetrain::Drivetrain() { - wpi::SendableRegistry::AddChild(&m_drive, &m_leftMotor); - wpi::SendableRegistry::AddChild(&m_drive, &m_rightMotor); + wpi::util::SendableRegistry::AddChild(&m_drive, &m_leftMotor); + wpi::util::SendableRegistry::AddChild(&m_drive, &m_rightMotor); // We need to invert one side of the drivetrain so that positive voltages // result in both sides moving forward. Depending on how your robot's @@ -51,27 +51,27 @@ int Drivetrain::GetRightEncoderCount() { return m_rightEncoder.Get(); } -units::meter_t Drivetrain::GetLeftDistance() { - return units::meter_t{m_leftEncoder.GetDistance()}; +wpi::units::meter_t Drivetrain::GetLeftDistance() { + return wpi::units::meter_t{m_leftEncoder.GetDistance()}; } -units::meter_t Drivetrain::GetRightDistance() { - return units::meter_t{m_rightEncoder.GetDistance()}; +wpi::units::meter_t Drivetrain::GetRightDistance() { + return wpi::units::meter_t{m_rightEncoder.GetDistance()}; } -units::meter_t Drivetrain::GetAverageDistance() { +wpi::units::meter_t Drivetrain::GetAverageDistance() { return (GetLeftDistance() + GetRightDistance()) / 2.0; } -units::radian_t Drivetrain::GetGyroAngleX() { +wpi::units::radian_t Drivetrain::GetGyroAngleX() { return m_gyro.GetAngleX(); } -units::radian_t Drivetrain::GetGyroAngleY() { +wpi::units::radian_t Drivetrain::GetGyroAngleY() { return m_gyro.GetAngleY(); } -units::radian_t Drivetrain::GetGyroAngleZ() { +wpi::units::radian_t Drivetrain::GetGyroAngleZ() { return m_gyro.GetAngleZ(); } diff --git a/wpilibcExamples/src/main/cpp/examples/XRPReference/include/Robot.hpp b/wpilibcExamples/src/main/cpp/examples/XRPReference/include/Robot.hpp index b89d567b62..ffeab02e6f 100644 --- a/wpilibcExamples/src/main/cpp/examples/XRPReference/include/Robot.hpp +++ b/wpilibcExamples/src/main/cpp/examples/XRPReference/include/Robot.hpp @@ -9,7 +9,7 @@ #include "RobotContainer.hpp" -class Robot : public frc::TimedRobot { +class Robot : public wpi::TimedRobot { public: Robot(); void RobotPeriodic() override; @@ -24,6 +24,6 @@ class Robot : public frc::TimedRobot { private: // Have it null by default so that if testing teleop it // doesn't have undefined behavior and potentially crash. - frc2::Command* m_autonomousCommand = nullptr; + wpi::cmd::Command* m_autonomousCommand = nullptr; RobotContainer m_container; }; diff --git a/wpilibcExamples/src/main/cpp/examples/XRPReference/include/RobotContainer.hpp b/wpilibcExamples/src/main/cpp/examples/XRPReference/include/RobotContainer.hpp index 4e45d6be82..4592c1313b 100644 --- a/wpilibcExamples/src/main/cpp/examples/XRPReference/include/RobotContainer.hpp +++ b/wpilibcExamples/src/main/cpp/examples/XRPReference/include/RobotContainer.hpp @@ -39,20 +39,20 @@ class RobotContainer { // Your subsystem configuration should take the overlays into account public: RobotContainer(); - frc2::Command* GetAutonomousCommand(); + wpi::cmd::Command* GetAutonomousCommand(); private: // Assumes a gamepad plugged into channel 0 - frc::Joystick m_controller{0}; - frc::SendableChooser m_chooser; + wpi::Joystick m_controller{0}; + wpi::SendableChooser m_chooser; // The robot's subsystems Drivetrain m_drive; Arm m_arm; - frc::XRPOnBoardIO m_onboardIO; + wpi::xrp::XRPOnBoardIO m_onboardIO; // Example button - frc2::Trigger m_userButton{ + wpi::cmd::Trigger m_userButton{ [this] { return m_onboardIO.GetUserButtonPressed(); }}; // Autonomous commands. diff --git a/wpilibcExamples/src/main/cpp/examples/XRPReference/include/commands/AutonomousDistance.hpp b/wpilibcExamples/src/main/cpp/examples/XRPReference/include/commands/AutonomousDistance.hpp index 227f0924de..bd29bdefe0 100644 --- a/wpilibcExamples/src/main/cpp/examples/XRPReference/include/commands/AutonomousDistance.hpp +++ b/wpilibcExamples/src/main/cpp/examples/XRPReference/include/commands/AutonomousDistance.hpp @@ -12,7 +12,7 @@ #include "subsystems/Drivetrain.hpp" class AutonomousDistance - : public frc2::CommandHelper { public: /** diff --git a/wpilibcExamples/src/main/cpp/examples/XRPReference/include/commands/AutonomousTime.hpp b/wpilibcExamples/src/main/cpp/examples/XRPReference/include/commands/AutonomousTime.hpp index 31cc56df0c..e2dde7998a 100644 --- a/wpilibcExamples/src/main/cpp/examples/XRPReference/include/commands/AutonomousTime.hpp +++ b/wpilibcExamples/src/main/cpp/examples/XRPReference/include/commands/AutonomousTime.hpp @@ -12,7 +12,7 @@ #include "subsystems/Drivetrain.hpp" class AutonomousTime - : public frc2::CommandHelper { + : public wpi::cmd::CommandHelper { public: /** * Creates a new Autonomous Drive based on time. This will drive out for a diff --git a/wpilibcExamples/src/main/cpp/examples/XRPReference/include/commands/DriveDistance.hpp b/wpilibcExamples/src/main/cpp/examples/XRPReference/include/commands/DriveDistance.hpp index 3b6abf364f..49fc11fb98 100644 --- a/wpilibcExamples/src/main/cpp/examples/XRPReference/include/commands/DriveDistance.hpp +++ b/wpilibcExamples/src/main/cpp/examples/XRPReference/include/commands/DriveDistance.hpp @@ -10,7 +10,7 @@ #include "subsystems/Drivetrain.hpp" -class DriveDistance : public frc2::CommandHelper { +class DriveDistance : public wpi::cmd::CommandHelper { public: /** * Creates a new DriveDistance. This command will drive your your robot for a @@ -20,7 +20,7 @@ class DriveDistance : public frc2::CommandHelper { * @param distance The distance the robot will drive * @param drive The drivetrain subsystem on which this command will run */ - DriveDistance(double speed, units::meter_t distance, Drivetrain* drive) + DriveDistance(double speed, wpi::units::meter_t distance, Drivetrain* drive) : m_speed(speed), m_distance(distance), m_drive(drive) { AddRequirements(m_drive); } @@ -32,6 +32,6 @@ class DriveDistance : public frc2::CommandHelper { private: double m_speed; - units::meter_t m_distance; + wpi::units::meter_t m_distance; Drivetrain* m_drive; }; diff --git a/wpilibcExamples/src/main/cpp/examples/XRPReference/include/commands/DriveTime.hpp b/wpilibcExamples/src/main/cpp/examples/XRPReference/include/commands/DriveTime.hpp index e8983b5acf..3ab5ad2a8a 100644 --- a/wpilibcExamples/src/main/cpp/examples/XRPReference/include/commands/DriveTime.hpp +++ b/wpilibcExamples/src/main/cpp/examples/XRPReference/include/commands/DriveTime.hpp @@ -11,7 +11,7 @@ #include "subsystems/Drivetrain.hpp" -class DriveTime : public frc2::CommandHelper { +class DriveTime : public wpi::cmd::CommandHelper { public: /** * Creates a new DriveTime. This command will drive your robot for a desired @@ -21,7 +21,7 @@ class DriveTime : public frc2::CommandHelper { * @param time How much time to drive * @param drive The drivetrain subsystem on which this command will run */ - DriveTime(double speed, units::second_t time, Drivetrain* drive) + DriveTime(double speed, wpi::units::second_t time, Drivetrain* drive) : m_speed(speed), m_duration(time), m_drive(drive) { AddRequirements(m_drive); } @@ -33,7 +33,7 @@ class DriveTime : public frc2::CommandHelper { private: double m_speed; - units::second_t m_duration; + wpi::units::second_t m_duration; Drivetrain* m_drive; - frc::Timer m_timer; + wpi::Timer m_timer; }; diff --git a/wpilibcExamples/src/main/cpp/examples/XRPReference/include/commands/TeleopArcadeDrive.hpp b/wpilibcExamples/src/main/cpp/examples/XRPReference/include/commands/TeleopArcadeDrive.hpp index f4682d6299..e0e7ce6f22 100644 --- a/wpilibcExamples/src/main/cpp/examples/XRPReference/include/commands/TeleopArcadeDrive.hpp +++ b/wpilibcExamples/src/main/cpp/examples/XRPReference/include/commands/TeleopArcadeDrive.hpp @@ -12,7 +12,7 @@ #include "subsystems/Drivetrain.hpp" class TeleopArcadeDrive - : public frc2::CommandHelper { + : public wpi::cmd::CommandHelper { public: /** * Creates a new ArcadeDrive. This command will drive your robot according to diff --git a/wpilibcExamples/src/main/cpp/examples/XRPReference/include/commands/TurnDegrees.hpp b/wpilibcExamples/src/main/cpp/examples/XRPReference/include/commands/TurnDegrees.hpp index 75fd83a885..119b116d65 100644 --- a/wpilibcExamples/src/main/cpp/examples/XRPReference/include/commands/TurnDegrees.hpp +++ b/wpilibcExamples/src/main/cpp/examples/XRPReference/include/commands/TurnDegrees.hpp @@ -11,7 +11,7 @@ #include "subsystems/Drivetrain.hpp" -class TurnDegrees : public frc2::CommandHelper { +class TurnDegrees : public wpi::cmd::CommandHelper { public: /** * Creates a new TurnDegrees. This command will turn your robot for a desired @@ -21,7 +21,7 @@ class TurnDegrees : public frc2::CommandHelper { * @param angle Degrees to turn. Leverages encoders to compare distance. * @param drive The drive subsystem on which this command will run */ - TurnDegrees(double speed, units::degree_t angle, Drivetrain* drive) + TurnDegrees(double speed, wpi::units::degree_t angle, Drivetrain* drive) : m_speed(speed), m_angle(angle), m_drive(drive) { AddRequirements(m_drive); } @@ -33,8 +33,8 @@ class TurnDegrees : public frc2::CommandHelper { private: double m_speed; - units::degree_t m_angle; + wpi::units::degree_t m_angle; Drivetrain* m_drive; - units::meter_t GetAverageTurningDistance(); + wpi::units::meter_t GetAverageTurningDistance(); }; diff --git a/wpilibcExamples/src/main/cpp/examples/XRPReference/include/commands/TurnTime.hpp b/wpilibcExamples/src/main/cpp/examples/XRPReference/include/commands/TurnTime.hpp index 3a2b4fc33f..3d8ac60f0d 100644 --- a/wpilibcExamples/src/main/cpp/examples/XRPReference/include/commands/TurnTime.hpp +++ b/wpilibcExamples/src/main/cpp/examples/XRPReference/include/commands/TurnTime.hpp @@ -11,7 +11,7 @@ #include "subsystems/Drivetrain.hpp" -class TurnTime : public frc2::CommandHelper { +class TurnTime : public wpi::cmd::CommandHelper { public: /** * Creates a new TurnTime. @@ -20,7 +20,7 @@ class TurnTime : public frc2::CommandHelper { * @param time How much time to turn * @param drive The drive subsystem on which this command will run */ - TurnTime(double speed, units::second_t time, Drivetrain* drive) + TurnTime(double speed, wpi::units::second_t time, Drivetrain* drive) : m_speed(speed), m_duration(time), m_drive(drive) { AddRequirements(m_drive); } @@ -32,7 +32,7 @@ class TurnTime : public frc2::CommandHelper { private: double m_speed; - units::second_t m_duration; + wpi::units::second_t m_duration; Drivetrain* m_drive; - frc::Timer m_timer; + wpi::Timer m_timer; }; diff --git a/wpilibcExamples/src/main/cpp/examples/XRPReference/include/subsystems/Arm.hpp b/wpilibcExamples/src/main/cpp/examples/XRPReference/include/subsystems/Arm.hpp index 22c30451b2..6aa94b6e7c 100644 --- a/wpilibcExamples/src/main/cpp/examples/XRPReference/include/subsystems/Arm.hpp +++ b/wpilibcExamples/src/main/cpp/examples/XRPReference/include/subsystems/Arm.hpp @@ -8,7 +8,7 @@ #include #include -class Arm : public frc2::SubsystemBase { +class Arm : public wpi::cmd::SubsystemBase { public: /** * Will be called periodically whenever the CommandScheduler runs. @@ -20,8 +20,8 @@ class Arm : public frc2::SubsystemBase { * * @param angle the commanded angle */ - void SetAngle(units::radian_t angle); + void SetAngle(wpi::units::radian_t angle); private: - frc::XRPServo m_armServo{4}; + wpi::xrp::XRPServo m_armServo{4}; }; diff --git a/wpilibcExamples/src/main/cpp/examples/XRPReference/include/subsystems/Drivetrain.hpp b/wpilibcExamples/src/main/cpp/examples/XRPReference/include/subsystems/Drivetrain.hpp index 186b2eae79..32cad6090a 100644 --- a/wpilibcExamples/src/main/cpp/examples/XRPReference/include/subsystems/Drivetrain.hpp +++ b/wpilibcExamples/src/main/cpp/examples/XRPReference/include/subsystems/Drivetrain.hpp @@ -13,14 +13,14 @@ #include #include -class Drivetrain : public frc2::SubsystemBase { +class Drivetrain : public wpi::cmd::SubsystemBase { public: static constexpr double kGearRatio = (30.0 / 14.0) * (28.0 / 16.0) * (36.0 / 9.0) * (26.0 / 8.0); // 48.75:1 static constexpr double kCountsPerMotorShaftRev = 12.0; static constexpr double kCountsPerRevolution = kCountsPerMotorShaftRev * kGearRatio; // 585.0 - static constexpr units::meter_t kWheelDiameter = 60_mm; + static constexpr wpi::units::meter_t kWheelDiameter = 60_mm; Drivetrain(); @@ -61,42 +61,42 @@ class Drivetrain : public frc2::SubsystemBase { * * @return the left-side distance driven */ - units::meter_t GetLeftDistance(); + wpi::units::meter_t GetLeftDistance(); /** * Gets the right distance driven. * * @return the right-side distance driven */ - units::meter_t GetRightDistance(); + wpi::units::meter_t GetRightDistance(); /** * Returns the average distance traveled by the left and right encoders. * * @return The average distance traveled by the left and right encoders. */ - units::meter_t GetAverageDistance(); + wpi::units::meter_t GetAverageDistance(); /** * Current angle of the XRP around the X-axis. * * @return The current angle of the XRP. */ - units::radian_t GetGyroAngleX(); + wpi::units::radian_t GetGyroAngleX(); /** * Current angle of the XRP around the Y-axis. * * @return The current angle of the XRP. */ - units::radian_t GetGyroAngleY(); + wpi::units::radian_t GetGyroAngleY(); /** * Current angle of the XRP around the Z-axis. * * @return The current angle of the XRP. */ - units::radian_t GetGyroAngleZ(); + wpi::units::radian_t GetGyroAngleZ(); /** * Reset the gyro. @@ -104,15 +104,15 @@ class Drivetrain : public frc2::SubsystemBase { void ResetGyro(); private: - frc::XRPMotor m_leftMotor{0}; - frc::XRPMotor m_rightMotor{1}; + wpi::xrp::XRPMotor m_leftMotor{0}; + wpi::xrp::XRPMotor m_rightMotor{1}; - frc::Encoder m_leftEncoder{4, 5}; - frc::Encoder m_rightEncoder{6, 7}; + wpi::Encoder m_leftEncoder{4, 5}; + wpi::Encoder m_rightEncoder{6, 7}; - frc::DifferentialDrive m_drive{ + wpi::DifferentialDrive m_drive{ [&](double output) { m_leftMotor.Set(output); }, [&](double output) { m_rightMotor.Set(output); }}; - frc::XRPGyro m_gyro; + wpi::xrp::XRPGyro m_gyro; }; diff --git a/wpilibcExamples/src/main/cpp/snippets/ADXLAccelerometers/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/snippets/ADXLAccelerometers/cpp/Robot.cpp index 9dc1b03872..f7dbfdc83d 100644 --- a/wpilibcExamples/src/main/cpp/snippets/ADXLAccelerometers/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/snippets/ADXLAccelerometers/cpp/Robot.cpp @@ -11,7 +11,7 @@ * ADXL346, 362 Accelerometer snippets for frc-docs. * https://docs.wpilib.org/en/stable/docs/software/hardware-apis/sensors/accelerometers-software.html */ -class Robot : public frc::TimedRobot { +class Robot : public wpi::TimedRobot { public: Robot() {} @@ -27,12 +27,12 @@ class Robot : public frc::TimedRobot { private: // Creates an ADXL345 accelerometer object on the MXP I2C port // with a measurement range from -8 to 8 G's - frc::ADXL345_I2C m_accelerometer{frc::I2C::Port::kPort0, - frc::ADXL345_I2C::Range::kRange_8G}; + wpi::ADXL345_I2C m_accelerometer{wpi::I2C::Port::kPort0, + wpi::ADXL345_I2C::Range::kRange_8G}; }; #ifndef RUNNING_FRC_TESTS int main() { - return frc::StartRobot(); + return wpi::StartRobot(); } #endif diff --git a/wpilibcExamples/src/main/cpp/snippets/AccelerometerCollision/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/snippets/AccelerometerCollision/cpp/Robot.cpp index 2aced8d66f..59474f0a4e 100644 --- a/wpilibcExamples/src/main/cpp/snippets/AccelerometerCollision/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/snippets/AccelerometerCollision/cpp/Robot.cpp @@ -11,7 +11,7 @@ * Collision detection snippets for frc-docs. * https://docs.wpilib.org/en/stable/docs/software/hardware-apis/sensors/accelerometers-software.html */ -class Robot : public frc::TimedRobot { +class Robot : public wpi::TimedRobot { public: void RobotPeriodic() override { // Gets the current accelerations in the X and Y directions @@ -23,18 +23,18 @@ class Robot : public frc::TimedRobot { m_prevXAccel = xAccel; m_prevYAccel = yAccel; - frc::SmartDashboard::PutNumber("X Jerk", xJerk.value()); - frc::SmartDashboard::PutNumber("Y Jerk", yJerk.value()); + wpi::SmartDashboard::PutNumber("X Jerk", xJerk.value()); + wpi::SmartDashboard::PutNumber("Y Jerk", yJerk.value()); } private: - units::meters_per_second_squared_t m_prevXAccel = 0.0_mps_sq; - units::meters_per_second_squared_t m_prevYAccel = 0.0_mps_sq; - frc::OnboardIMU m_accelerometer{frc::OnboardIMU::MountOrientation::kFlat}; + wpi::units::meters_per_second_squared_t m_prevXAccel = 0.0_mps_sq; + wpi::units::meters_per_second_squared_t m_prevYAccel = 0.0_mps_sq; + wpi::OnboardIMU m_accelerometer{wpi::OnboardIMU::MountOrientation::kFlat}; }; #ifndef RUNNING_FRC_TESTS int main() { - return frc::StartRobot(); + return wpi::StartRobot(); } #endif diff --git a/wpilibcExamples/src/main/cpp/snippets/AccelerometerFilter/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/snippets/AccelerometerFilter/cpp/Robot.cpp index a0c8c8bb50..75917b31f2 100644 --- a/wpilibcExamples/src/main/cpp/snippets/AccelerometerFilter/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/snippets/AccelerometerFilter/cpp/Robot.cpp @@ -12,27 +12,27 @@ * Accelerometer filtering snippets for frc-docs. * https://docs.wpilib.org/en/stable/docs/software/hardware-apis/sensors/accelerometers-software.html */ -class Robot : public frc::TimedRobot { +class Robot : public wpi::TimedRobot { public: void RobotPeriodic() override { - units::meters_per_second_squared_t XAccel = m_accelerometer.GetAccelX(); + wpi::units::meters_per_second_squared_t XAccel = m_accelerometer.GetAccelX(); // Get the filtered X acceleration - units::meters_per_second_squared_t filteredXAccel = + wpi::units::meters_per_second_squared_t filteredXAccel = m_xAccelFilter.Calculate(XAccel); - frc::SmartDashboard::PutNumber("X Acceleration", XAccel.value()); - frc::SmartDashboard::PutNumber("Filtered X Acceleration", + wpi::SmartDashboard::PutNumber("X Acceleration", XAccel.value()); + wpi::SmartDashboard::PutNumber("Filtered X Acceleration", filteredXAccel.value()); } private: - frc::OnboardIMU m_accelerometer{frc::OnboardIMU::MountOrientation::kFlat}; - frc::LinearFilter m_xAccelFilter = - frc::LinearFilter::MovingAverage(10); + wpi::OnboardIMU m_accelerometer{wpi::OnboardIMU::MountOrientation::kFlat}; + wpi::math::LinearFilter m_xAccelFilter = + wpi::math::LinearFilter::MovingAverage(10); }; #ifndef RUNNING_FRC_TESTS int main() { - return frc::StartRobot(); + return wpi::StartRobot(); } #endif diff --git a/wpilibcExamples/src/main/cpp/snippets/AnalogAccelerometer/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/snippets/AnalogAccelerometer/cpp/Robot.cpp index 8f0e7564d2..5e5f0b14f6 100644 --- a/wpilibcExamples/src/main/cpp/snippets/AnalogAccelerometer/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/snippets/AnalogAccelerometer/cpp/Robot.cpp @@ -10,7 +10,7 @@ * AnalogAccelerometer snippets for frc-docs. * https://docs.wpilib.org/en/stable/docs/software/hardware-apis/sensors/accelerometers-software.html */ -class Robot : public frc::TimedRobot { +class Robot : public wpi::TimedRobot { public: Robot() { // Sets the sensitivity of the accelerometer to 1 volt per G @@ -26,11 +26,11 @@ class Robot : public frc::TimedRobot { private: // Creates an analog accelerometer on analog input 0 - frc::AnalogAccelerometer m_accelerometer{0}; + wpi::AnalogAccelerometer m_accelerometer{0}; }; #ifndef RUNNING_FRC_TESTS int main() { - return frc::StartRobot(); + return wpi::StartRobot(); } #endif diff --git a/wpilibcExamples/src/main/cpp/snippets/AnalogEncoder/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/snippets/AnalogEncoder/cpp/Robot.cpp index 2f78a7cd07..35aa7a2f00 100644 --- a/wpilibcExamples/src/main/cpp/snippets/AnalogEncoder/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/snippets/AnalogEncoder/cpp/Robot.cpp @@ -9,7 +9,7 @@ * AnalogEncoder snippets for frc-docs. * https://docs.wpilib.org/en/stable/docs/software/hardware-apis/sensors/encoders-software.html */ -class Robot : public frc::TimedRobot { +class Robot : public wpi::TimedRobot { public: Robot() {} @@ -20,16 +20,16 @@ class Robot : public frc::TimedRobot { private: // Initializes an analog encoder on Analog Input pin 0 - frc::AnalogEncoder m_encoder{0}; + wpi::AnalogEncoder m_encoder{0}; // Initializes an analog encoder on DIO pins 0 to return a value of 4 for // a full rotation, with the encoder reporting 0 half way through rotation (2 // out of 4) - frc::AnalogEncoder m_encoderFR{0, 4.0, 2.0}; + wpi::AnalogEncoder m_encoderFR{0, 4.0, 2.0}; }; #ifndef RUNNING_FRC_TESTS int main() { - return frc::StartRobot(); + return wpi::StartRobot(); } #endif diff --git a/wpilibcExamples/src/main/cpp/snippets/AnalogInput/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/snippets/AnalogInput/cpp/Robot.cpp index 14f184e081..93a164ac26 100644 --- a/wpilibcExamples/src/main/cpp/snippets/AnalogInput/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/snippets/AnalogInput/cpp/Robot.cpp @@ -9,7 +9,7 @@ * AnalogInput snippets for frc-docs. * https://docs.wpilib.org/en/stable/docs/software/hardware-apis/sensors/analog-input-software.html */ -class Robot : public frc::TimedRobot { +class Robot : public wpi::TimedRobot { public: Robot() { // Sets the AnalogInput to 4-bit oversampling. 16 samples will be added @@ -44,11 +44,11 @@ class Robot : public frc::TimedRobot { private: // Initializes an AnalogInput on port 0 - frc::AnalogInput m_analog{0}; + wpi::AnalogInput m_analog{0}; }; #ifndef RUNNING_FRC_TESTS int main() { - return frc::StartRobot(); + return wpi::StartRobot(); } #endif diff --git a/wpilibcExamples/src/main/cpp/snippets/AnalogPotentiometer/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/snippets/AnalogPotentiometer/cpp/Robot.cpp index a2958e6a90..8129c73d40 100644 --- a/wpilibcExamples/src/main/cpp/snippets/AnalogPotentiometer/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/snippets/AnalogPotentiometer/cpp/Robot.cpp @@ -10,7 +10,7 @@ * AnalogPotentiometer snippets for frc-docs. * https://docs.wpilib.org/en/stable/docs/software/hardware-apis/sensors/analog-potentiometers-software.html */ -class Robot : public frc::TimedRobot { +class Robot : public wpi::TimedRobot { public: Robot() { // Set averaging bits to 2 @@ -27,19 +27,19 @@ class Robot : public frc::TimedRobot { // The full range of motion (in meaningful external units) is 0-180 (this // could be degrees, for instance) The "starting point" of the motion, i.e. // where the mechanism is located when the potentiometer reads 0v, is 30. - frc::AnalogPotentiometer m_pot{0, 180, 30}; + wpi::AnalogPotentiometer m_pot{0, 180, 30}; // Initializes an AnalogInput on port 1 - frc::AnalogInput m_input{1}; + wpi::AnalogInput m_input{1}; // Initializes an AnalogPotentiometer with the given AnalogInput // The full range of motion (in meaningful external units) is 0-180 (this // could be degrees, for instance) The "starting point" of the motion, i.e. // where the mechanism is located when the potentiometer reads 0v, is 30. - frc::AnalogPotentiometer m_pot1{&m_input, 180, 30}; + wpi::AnalogPotentiometer m_pot1{&m_input, 180, 30}; }; #ifndef RUNNING_FRC_TESTS int main() { - return frc::StartRobot(); + return wpi::StartRobot(); } #endif diff --git a/wpilibcExamples/src/main/cpp/snippets/DigitalInput/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/snippets/DigitalInput/cpp/Robot.cpp index 14b35a7487..7421952b94 100644 --- a/wpilibcExamples/src/main/cpp/snippets/DigitalInput/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/snippets/DigitalInput/cpp/Robot.cpp @@ -9,7 +9,7 @@ * Digital Input snippets for frc-docs. * https://docs.wpilib.org/en/stable/docs/software/hardware-apis/sensors/digital-input-software.html */ -class Robot : public frc::TimedRobot { +class Robot : public wpi::TimedRobot { public: void TeleopPeriodic() override { // Gets the value of the digital input. Returns true if the circuit is @@ -19,11 +19,11 @@ class Robot : public frc::TimedRobot { private: // Initializes a DigitalInput on DIO 0 - frc::DigitalInput m_input{0}; + wpi::DigitalInput m_input{0}; }; #ifndef RUNNING_FRC_TESTS int main() { - return frc::StartRobot(); + return wpi::StartRobot(); } #endif diff --git a/wpilibcExamples/src/main/cpp/snippets/DutyCycleEncoder/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/snippets/DutyCycleEncoder/cpp/Robot.cpp index e31decd746..8f4a601e5a 100644 --- a/wpilibcExamples/src/main/cpp/snippets/DutyCycleEncoder/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/snippets/DutyCycleEncoder/cpp/Robot.cpp @@ -9,7 +9,7 @@ * DutyCycleEncoder snippets for frc-docs. * https://docs.wpilib.org/en/stable/docs/software/hardware-apis/sensors/encoders-software.html */ -class Robot : public frc::TimedRobot { +class Robot : public wpi::TimedRobot { public: Robot() {} @@ -23,16 +23,16 @@ class Robot : public frc::TimedRobot { private: // Initializes a duty cycle encoder on DIO pins 0 - frc::DutyCycleEncoder m_encoder{0}; + wpi::DutyCycleEncoder m_encoder{0}; // Initializes a duty cycle encoder on DIO pins 0 to return a value of 4 for // a full rotation, with the encoder reporting 0 half way through rotation (2 // out of 4) - frc::DutyCycleEncoder m_encoderFR{0, 4.0, 2.0}; + wpi::DutyCycleEncoder m_encoderFR{0, 4.0, 2.0}; }; #ifndef RUNNING_FRC_TESTS int main() { - return frc::StartRobot(); + return wpi::StartRobot(); } #endif diff --git a/wpilibcExamples/src/main/cpp/snippets/Encoder/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/snippets/Encoder/cpp/Robot.cpp index c793391338..ebf76d4cf4 100644 --- a/wpilibcExamples/src/main/cpp/snippets/Encoder/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/snippets/Encoder/cpp/Robot.cpp @@ -11,7 +11,7 @@ * https://docs.wpilib.org/en/stable/docs/software/hardware-apis/sensors/encoders-software.html */ WPI_IGNORE_DEPRECATED -class Robot : public frc::TimedRobot { +class Robot : public wpi::TimedRobot { public: Robot() { // Configures the encoder to return a distance of 4 for every 256 pulses @@ -52,15 +52,15 @@ class Robot : public frc::TimedRobot { private: // Initializes an encoder on DIO pins 0 and 1 // Defaults to 4X decoding and non-inverted - frc::Encoder m_encoder{0, 1}; + wpi::Encoder m_encoder{0, 1}; // Initializes an encoder on DIO pins 0 and 1 // 2X encoding and non-inverted - frc::Encoder m_encoder2x{0, 1, false, frc::Encoder::EncodingType::k2X}; + wpi::Encoder m_encoder2x{0, 1, false, wpi::Encoder::EncodingType::k2X}; }; #ifndef RUNNING_FRC_TESTS int main() { - return frc::StartRobot(); + return wpi::StartRobot(); } #endif diff --git a/wpilibcExamples/src/main/cpp/snippets/EncoderDrive/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/snippets/EncoderDrive/cpp/Robot.cpp index beb66bcc12..d00a3141ec 100644 --- a/wpilibcExamples/src/main/cpp/snippets/EncoderDrive/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/snippets/EncoderDrive/cpp/Robot.cpp @@ -11,7 +11,7 @@ * Encoder drive to distance snippets for frc-docs. * https://docs.wpilib.org/en/stable/docs/software/hardware-apis/sensors/encoders-software.html */ -class Robot : public frc::TimedRobot { +class Robot : public wpi::TimedRobot { public: Robot() { // Configures the encoder's distance-per-pulse @@ -37,18 +37,18 @@ class Robot : public frc::TimedRobot { private: // Creates an encoder on DIO ports 0 and 1. - frc::Encoder m_encoder{0, 1}; + wpi::Encoder m_encoder{0, 1}; // Initialize motor controllers and drive - frc::Spark leftLeader{0}; - frc::Spark leftFollower{1}; - frc::Spark rightLeader{2}; - frc::Spark rightFollower{3}; - frc::DifferentialDrive drive{[&](double output) { leftLeader.Set(output); }, + wpi::Spark leftLeader{0}; + wpi::Spark leftFollower{1}; + wpi::Spark rightLeader{2}; + wpi::Spark rightFollower{3}; + wpi::DifferentialDrive drive{[&](double output) { leftLeader.Set(output); }, [&](double output) { rightLeader.Set(output); }}; }; #ifndef RUNNING_FRC_TESTS int main() { - return frc::StartRobot(); + return wpi::StartRobot(); } #endif diff --git a/wpilibcExamples/src/main/cpp/snippets/EncoderHoming/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/snippets/EncoderHoming/cpp/Robot.cpp index 34b0510a3e..d22b283fac 100644 --- a/wpilibcExamples/src/main/cpp/snippets/EncoderHoming/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/snippets/EncoderHoming/cpp/Robot.cpp @@ -11,7 +11,7 @@ * Encoder mechanism homing snippets for frc-docs. * https://docs.wpilib.org/en/stable/docs/software/hardware-apis/sensors/encoders-software.html */ -class Robot : public frc::TimedRobot { +class Robot : public wpi::TimedRobot { public: void AutonomousPeriodic() override { // Runs the motor backwards at half speed until the limit switch is pressed @@ -25,14 +25,14 @@ class Robot : public frc::TimedRobot { } private: - frc::Encoder m_encoder{0, 1}; - frc::Spark m_spark{0}; + wpi::Encoder m_encoder{0, 1}; + wpi::Spark m_spark{0}; // Limit switch on DIO 2 - frc::DigitalInput m_limit{2}; + wpi::DigitalInput m_limit{2}; }; #ifndef RUNNING_FRC_TESTS int main() { - return frc::StartRobot(); + return wpi::StartRobot(); } #endif diff --git a/wpilibcExamples/src/main/cpp/snippets/LimitSwitch/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/snippets/LimitSwitch/cpp/Robot.cpp index 66123dbb3f..68ed3e35a5 100644 --- a/wpilibcExamples/src/main/cpp/snippets/LimitSwitch/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/snippets/LimitSwitch/cpp/Robot.cpp @@ -12,7 +12,7 @@ * Limit Switch snippets for frc-docs. * https://docs.wpilib.org/en/stable/docs/software/hardware-apis/sensors/limit-switch.html */ -class Robot : public frc::TimedRobot { +class Robot : public wpi::TimedRobot { public: void TeleopPeriodic() override { SetMotorSpeed(m_joystick.GetRawAxis(2)); } void SetMotorSpeed(double speed) { @@ -37,14 +37,14 @@ class Robot : public frc::TimedRobot { } private: - frc::DigitalInput m_toplimitSwitch{0}; - frc::DigitalInput m_bottomlimitSwitch{1}; - frc::PWMVictorSPX m_motor{0}; - frc::Joystick m_joystick{0}; + wpi::DigitalInput m_toplimitSwitch{0}; + wpi::DigitalInput m_bottomlimitSwitch{1}; + wpi::PWMVictorSPX m_motor{0}; + wpi::Joystick m_joystick{0}; }; #ifndef RUNNING_FRC_TESTS int main() { - return frc::StartRobot(); + return wpi::StartRobot(); } #endif diff --git a/wpilibcExamples/src/main/cpp/snippets/OnboardIMU/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/snippets/OnboardIMU/cpp/Robot.cpp index c46e8b72a1..279091f43a 100644 --- a/wpilibcExamples/src/main/cpp/snippets/OnboardIMU/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/snippets/OnboardIMU/cpp/Robot.cpp @@ -12,7 +12,7 @@ * Onboard IMU snippets for frc-docs. * https://docs.wpilib.org/en/stable/docs/software/hardware-apis/sensors/accelerometers-software.html */ -class Robot : public frc::TimedRobot { +class Robot : public wpi::TimedRobot { public: void TeleopPeriodic() override { // Gets the current acceleration in the X axis @@ -35,11 +35,11 @@ class Robot : public frc::TimedRobot { private: // Creates an object for the Systemcore IMU - frc::OnboardIMU m_IMU{frc::OnboardIMU::MountOrientation::kFlat}; + wpi::OnboardIMU m_IMU{wpi::OnboardIMU::MountOrientation::kFlat}; }; #ifndef RUNNING_FRC_TESTS int main() { - return frc::StartRobot(); + return wpi::StartRobot(); } #endif diff --git a/wpilibcExamples/src/main/cpp/snippets/ProfiledPIDFeedforward/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/snippets/ProfiledPIDFeedforward/cpp/Robot.cpp index d9015f9e15..1d79c22253 100644 --- a/wpilibcExamples/src/main/cpp/snippets/ProfiledPIDFeedforward/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/snippets/ProfiledPIDFeedforward/cpp/Robot.cpp @@ -13,19 +13,19 @@ #include /** - * ProfiledPIDController with feedforward snippets for frc-docs. + * wpi::math::ProfiledPIDController with feedforward snippets for frc-docs. * https://docs.wpilib.org/en/stable/docs/software/advanced-controls/controllers/profiled-pidcontroller.html */ -class Robot : public frc::TimedRobot { +class Robot : public wpi::TimedRobot { public: Robot() { m_encoder.SetDistancePerPulse(1.0 / 256.0); } - // Controls a simple motor's position using a SimpleMotorFeedforward - // and a ProfiledPIDController - void GoToPosition(units::meter_t goalPosition) { + // Controls a simple motor's position using a wpi::math::SimpleMotorFeedforward + // and a wpi::math::ProfiledPIDController + void GoToPosition(wpi::units::meter_t goalPosition) { auto pidVal = m_controller.Calculate( - units::meter_t{m_encoder.GetDistance()}, goalPosition); - m_motor.SetVoltage(units::volt_t{pidVal} + + wpi::units::meter_t{m_encoder.GetDistance()}, goalPosition); + m_motor.SetVoltage(wpi::units::volt_t{pidVal} + m_feedforward.Calculate( m_lastSpeed, m_controller.GetSetpoint().velocity)); m_lastSpeed = m_controller.GetSetpoint().velocity; @@ -37,18 +37,18 @@ class Robot : public frc::TimedRobot { } private: - frc::ProfiledPIDController m_controller{ + wpi::math::ProfiledPIDController m_controller{ 1.0, 0.0, 0.0, {5_mps, 10_mps_sq}}; - frc::SimpleMotorFeedforward m_feedforward{0.5_V, 1.5_V / 1_mps, + wpi::math::SimpleMotorFeedforward m_feedforward{0.5_V, 1.5_V / 1_mps, 0.3_V / 1_mps_sq}; - frc::Encoder m_encoder{0, 1}; - frc::PWMSparkMax m_motor{0}; + wpi::Encoder m_encoder{0, 1}; + wpi::PWMSparkMax m_motor{0}; - units::meters_per_second_t m_lastSpeed = 0_mps; + wpi::units::meters_per_second_t m_lastSpeed = 0_mps; }; #ifndef RUNNING_FRC_TESTS int main() { - return frc::StartRobot(); + return wpi::StartRobot(); } #endif diff --git a/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/Robot.cpp index 91dbc4c72e..0da6ef185a 100644 --- a/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/Robot.cpp @@ -17,7 +17,7 @@ Robot::Robot() {} * LiveWindow and SmartDashboard integrated updating. */ void Robot::RobotPeriodic() { - frc2::CommandScheduler::GetInstance().Run(); + wpi::cmd::CommandScheduler::GetInstance().Run(); } /** @@ -37,7 +37,7 @@ void Robot::AutonomousInit() { m_autonomousCommand = m_container.GetAutonomousCommand(); if (m_autonomousCommand) { - frc2::CommandScheduler::GetInstance().Schedule(m_autonomousCommand.value()); + wpi::cmd::CommandScheduler::GetInstance().Schedule(m_autonomousCommand.value()); } } @@ -75,6 +75,6 @@ void Robot::SimulationPeriodic() {} #ifndef RUNNING_FRC_TESTS int main() { - return frc::StartRobot(); + return wpi::StartRobot(); } #endif diff --git a/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/RobotContainer.cpp b/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/RobotContainer.cpp index bd53e8b60b..c3e14f2554 100644 --- a/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/RobotContainer.cpp +++ b/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/RobotContainer.cpp @@ -20,7 +20,7 @@ void RobotContainer::ConfigureBindings() { // Configure your trigger bindings here // Schedule `ExampleCommand` when `exampleCondition` changes to `true` - frc2::Trigger([this] { + wpi::cmd::Trigger([this] { return m_subsystem.ExampleCondition(); }).OnTrue(ExampleCommand(&m_subsystem).ToPtr()); @@ -29,7 +29,7 @@ void RobotContainer::ConfigureBindings() { m_driverController.B().WhileTrue(m_subsystem.ExampleMethodCommand()); } -frc2::CommandPtr RobotContainer::GetAutonomousCommand() { +wpi::cmd::CommandPtr RobotContainer::GetAutonomousCommand() { // An example command will be run in autonomous return autos::ExampleAuto(&m_subsystem); } diff --git a/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/commands/Autos.cpp b/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/commands/Autos.cpp index 59f5904b11..6e9872a26b 100644 --- a/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/commands/Autos.cpp +++ b/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/commands/Autos.cpp @@ -8,7 +8,7 @@ #include "commands/ExampleCommand.hpp" -frc2::CommandPtr autos::ExampleAuto(ExampleSubsystem* subsystem) { - return frc2::cmd::Sequence(subsystem->ExampleMethodCommand(), +wpi::cmd::CommandPtr autos::ExampleAuto(ExampleSubsystem* subsystem) { + return wpi::cmd::cmd::Sequence(subsystem->ExampleMethodCommand(), ExampleCommand(subsystem).ToPtr()); } diff --git a/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/subsystems/ExampleSubsystem.cpp b/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/subsystems/ExampleSubsystem.cpp index 748a256b13..69ee3ad5a7 100644 --- a/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/subsystems/ExampleSubsystem.cpp +++ b/wpilibcExamples/src/main/cpp/templates/commandbased/cpp/subsystems/ExampleSubsystem.cpp @@ -8,7 +8,7 @@ ExampleSubsystem::ExampleSubsystem() { // Implementation of subsystem constructor goes here. } -frc2::CommandPtr ExampleSubsystem::ExampleMethodCommand() { +wpi::cmd::CommandPtr ExampleSubsystem::ExampleMethodCommand() { // Inline construction of command goes here. // Subsystem::RunOnce implicitly requires `this` subsystem. return RunOnce([/* this */] { /* one-time action goes here */ }); diff --git a/wpilibcExamples/src/main/cpp/templates/commandbased/include/Robot.hpp b/wpilibcExamples/src/main/cpp/templates/commandbased/include/Robot.hpp index 31de7f348a..aa768950ec 100644 --- a/wpilibcExamples/src/main/cpp/templates/commandbased/include/Robot.hpp +++ b/wpilibcExamples/src/main/cpp/templates/commandbased/include/Robot.hpp @@ -11,7 +11,7 @@ #include "RobotContainer.hpp" -class Robot : public frc::TimedRobot { +class Robot : public wpi::TimedRobot { public: Robot(); void RobotPeriodic() override; @@ -28,7 +28,7 @@ class Robot : public frc::TimedRobot { private: // Have it empty by default so that if testing teleop it // doesn't have undefined behavior and potentially crash. - std::optional m_autonomousCommand; + std::optional m_autonomousCommand; RobotContainer m_container; }; diff --git a/wpilibcExamples/src/main/cpp/templates/commandbased/include/RobotContainer.hpp b/wpilibcExamples/src/main/cpp/templates/commandbased/include/RobotContainer.hpp index 4b24ca59a1..0b743339a6 100644 --- a/wpilibcExamples/src/main/cpp/templates/commandbased/include/RobotContainer.hpp +++ b/wpilibcExamples/src/main/cpp/templates/commandbased/include/RobotContainer.hpp @@ -21,11 +21,11 @@ class RobotContainer { public: RobotContainer(); - frc2::CommandPtr GetAutonomousCommand(); + wpi::cmd::CommandPtr GetAutonomousCommand(); private: // Replace with CommandPS4Controller or CommandJoystick if needed - frc2::CommandXboxController m_driverController{ + wpi::cmd::CommandXboxController m_driverController{ OperatorConstants::kDriverControllerPort}; // The robot's subsystems are defined here... diff --git a/wpilibcExamples/src/main/cpp/templates/commandbased/include/commands/Autos.hpp b/wpilibcExamples/src/main/cpp/templates/commandbased/include/commands/Autos.hpp index 717284afe7..f6a1b1f86d 100644 --- a/wpilibcExamples/src/main/cpp/templates/commandbased/include/commands/Autos.hpp +++ b/wpilibcExamples/src/main/cpp/templates/commandbased/include/commands/Autos.hpp @@ -12,5 +12,5 @@ namespace autos { /** * Example static factory for an autonomous command. */ -frc2::CommandPtr ExampleAuto(ExampleSubsystem* subsystem); +wpi::cmd::CommandPtr ExampleAuto(ExampleSubsystem* subsystem); } // namespace autos diff --git a/wpilibcExamples/src/main/cpp/templates/commandbased/include/commands/ExampleCommand.hpp b/wpilibcExamples/src/main/cpp/templates/commandbased/include/commands/ExampleCommand.hpp index 85d72e3f68..3acf4b5b7f 100644 --- a/wpilibcExamples/src/main/cpp/templates/commandbased/include/commands/ExampleCommand.hpp +++ b/wpilibcExamples/src/main/cpp/templates/commandbased/include/commands/ExampleCommand.hpp @@ -17,7 +17,7 @@ * Command will *not* work! */ class ExampleCommand - : public frc2::CommandHelper { + : public wpi::cmd::CommandHelper { public: /** * Creates a new ExampleCommand. diff --git a/wpilibcExamples/src/main/cpp/templates/commandbased/include/subsystems/ExampleSubsystem.hpp b/wpilibcExamples/src/main/cpp/templates/commandbased/include/subsystems/ExampleSubsystem.hpp index c13c4aedda..1f57e8909d 100644 --- a/wpilibcExamples/src/main/cpp/templates/commandbased/include/subsystems/ExampleSubsystem.hpp +++ b/wpilibcExamples/src/main/cpp/templates/commandbased/include/subsystems/ExampleSubsystem.hpp @@ -7,14 +7,14 @@ #include #include -class ExampleSubsystem : public frc2::SubsystemBase { +class ExampleSubsystem : public wpi::cmd::SubsystemBase { public: ExampleSubsystem(); /** * Example command factory method. */ - frc2::CommandPtr ExampleMethodCommand(); + wpi::cmd::CommandPtr ExampleMethodCommand(); /** * An example method querying a boolean state of the subsystem (for example, a diff --git a/wpilibcExamples/src/main/cpp/templates/commandbasedskeleton/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/templates/commandbasedskeleton/cpp/Robot.cpp index 9b66f55e3d..c1390561da 100644 --- a/wpilibcExamples/src/main/cpp/templates/commandbasedskeleton/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/templates/commandbasedskeleton/cpp/Robot.cpp @@ -9,7 +9,7 @@ Robot::Robot() {} void Robot::RobotPeriodic() { - frc2::CommandScheduler::GetInstance().Run(); + wpi::cmd::CommandScheduler::GetInstance().Run(); } void Robot::DisabledInit() {} @@ -22,7 +22,7 @@ void Robot::AutonomousInit() { m_autonomousCommand = m_container.GetAutonomousCommand(); if (m_autonomousCommand) { - frc2::CommandScheduler::GetInstance().Schedule(m_autonomousCommand.value()); + wpi::cmd::CommandScheduler::GetInstance().Schedule(m_autonomousCommand.value()); } } @@ -41,7 +41,7 @@ void Robot::TeleopPeriodic() {} void Robot::TeleopExit() {} void Robot::TestInit() { - frc2::CommandScheduler::GetInstance().CancelAll(); + wpi::cmd::CommandScheduler::GetInstance().CancelAll(); } void Robot::TestPeriodic() {} @@ -50,6 +50,6 @@ void Robot::TestExit() {} #ifndef RUNNING_FRC_TESTS int main() { - return frc::StartRobot(); + return wpi::StartRobot(); } #endif diff --git a/wpilibcExamples/src/main/cpp/templates/commandbasedskeleton/cpp/RobotContainer.cpp b/wpilibcExamples/src/main/cpp/templates/commandbasedskeleton/cpp/RobotContainer.cpp index 30616bb7c9..2bee9a8925 100644 --- a/wpilibcExamples/src/main/cpp/templates/commandbasedskeleton/cpp/RobotContainer.cpp +++ b/wpilibcExamples/src/main/cpp/templates/commandbasedskeleton/cpp/RobotContainer.cpp @@ -12,6 +12,6 @@ RobotContainer::RobotContainer() { void RobotContainer::ConfigureBindings() {} -frc2::CommandPtr RobotContainer::GetAutonomousCommand() { - return frc2::cmd::Print("No autonomous command configured"); +wpi::cmd::CommandPtr RobotContainer::GetAutonomousCommand() { + return wpi::cmd::cmd::Print("No autonomous command configured"); } diff --git a/wpilibcExamples/src/main/cpp/templates/commandbasedskeleton/include/Robot.hpp b/wpilibcExamples/src/main/cpp/templates/commandbasedskeleton/include/Robot.hpp index fcf8c8c81f..8939b73080 100644 --- a/wpilibcExamples/src/main/cpp/templates/commandbasedskeleton/include/Robot.hpp +++ b/wpilibcExamples/src/main/cpp/templates/commandbasedskeleton/include/Robot.hpp @@ -11,7 +11,7 @@ #include "RobotContainer.hpp" -class Robot : public frc::TimedRobot { +class Robot : public wpi::TimedRobot { public: Robot(); void RobotPeriodic() override; @@ -29,7 +29,7 @@ class Robot : public frc::TimedRobot { void TestExit() override; private: - std::optional m_autonomousCommand; + std::optional m_autonomousCommand; RobotContainer m_container; }; diff --git a/wpilibcExamples/src/main/cpp/templates/commandbasedskeleton/include/RobotContainer.hpp b/wpilibcExamples/src/main/cpp/templates/commandbasedskeleton/include/RobotContainer.hpp index bb795a347c..712cf43ea4 100644 --- a/wpilibcExamples/src/main/cpp/templates/commandbasedskeleton/include/RobotContainer.hpp +++ b/wpilibcExamples/src/main/cpp/templates/commandbasedskeleton/include/RobotContainer.hpp @@ -10,7 +10,7 @@ class RobotContainer { public: RobotContainer(); - frc2::CommandPtr GetAutonomousCommand(); + wpi::cmd::CommandPtr GetAutonomousCommand(); private: void ConfigureBindings(); diff --git a/wpilibcExamples/src/main/cpp/templates/robotbaseskeleton/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/templates/robotbaseskeleton/cpp/Robot.cpp index 2f377a4032..5ea6e23547 100644 --- a/wpilibcExamples/src/main/cpp/templates/robotbaseskeleton/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/templates/robotbaseskeleton/cpp/Robot.cpp @@ -20,10 +20,10 @@ void Robot::Teleop() {} void Robot::Test() {} void Robot::StartCompetition() { - frc::internal::DriverStationModeThread modeThread; + wpi::internal::DriverStationModeThread modeThread; - wpi::Event event{false, false}; - frc::DriverStation::ProvideRefreshedDataEventHandle(event.GetHandle()); + wpi::util::Event event{false, false}; + wpi::DriverStation::ProvideRefreshedDataEventHandle(event.GetHandle()); // Tell the DS that the robot is ready to be enabled HAL_ObserveUserProgramStarting(); @@ -34,28 +34,28 @@ void Robot::StartCompetition() { Disabled(); modeThread.InDisabled(false); while (IsDisabled()) { - wpi::WaitForObject(event.GetHandle()); + wpi::util::WaitForObject(event.GetHandle()); } } else if (IsAutonomous()) { modeThread.InAutonomous(true); Autonomous(); modeThread.InAutonomous(false); while (IsAutonomousEnabled()) { - wpi::WaitForObject(event.GetHandle()); + wpi::util::WaitForObject(event.GetHandle()); } } else if (IsTest()) { modeThread.InTest(true); Test(); modeThread.InTest(false); while (IsTest() && IsEnabled()) { - wpi::WaitForObject(event.GetHandle()); + wpi::util::WaitForObject(event.GetHandle()); } } else { modeThread.InTeleop(true); Teleop(); modeThread.InTeleop(false); while (IsTeleopEnabled()) { - wpi::WaitForObject(event.GetHandle()); + wpi::util::WaitForObject(event.GetHandle()); } } } @@ -67,6 +67,6 @@ void Robot::EndCompetition() { #ifndef RUNNING_FRC_TESTS int main() { - return frc::StartRobot(); + return wpi::StartRobot(); } #endif diff --git a/wpilibcExamples/src/main/cpp/templates/robotbaseskeleton/include/Robot.hpp b/wpilibcExamples/src/main/cpp/templates/robotbaseskeleton/include/Robot.hpp index 7b8f1bad3f..d91687bcb4 100644 --- a/wpilibcExamples/src/main/cpp/templates/robotbaseskeleton/include/Robot.hpp +++ b/wpilibcExamples/src/main/cpp/templates/robotbaseskeleton/include/Robot.hpp @@ -8,7 +8,7 @@ #include -class Robot : public frc::RobotBase { +class Robot : public wpi::RobotBase { public: Robot(); void Disabled(); diff --git a/wpilibcExamples/src/main/cpp/templates/timed/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/templates/timed/cpp/Robot.cpp index a08a1cffd5..515fe84bc8 100644 --- a/wpilibcExamples/src/main/cpp/templates/timed/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/templates/timed/cpp/Robot.cpp @@ -10,7 +10,7 @@ Robot::Robot() { m_chooser.SetDefaultOption(kAutoNameDefault, kAutoNameDefault); m_chooser.AddOption(kAutoNameCustom, kAutoNameCustom); - frc::SmartDashboard::PutData("Auto Modes", &m_chooser); + wpi::SmartDashboard::PutData("Auto Modes", &m_chooser); } /** @@ -38,7 +38,7 @@ void Robot::AutonomousInit() { m_autoSelected = m_chooser.GetSelected(); // m_autoSelected = SmartDashboard::GetString("Auto Selector", // kAutoNameDefault); - wpi::print("Auto selected: {}\n", m_autoSelected); + wpi::util::print("Auto selected: {}\n", m_autoSelected); if (m_autoSelected == kAutoNameCustom) { // Custom Auto goes here @@ -73,6 +73,6 @@ void Robot::SimulationPeriodic() {} #ifndef RUNNING_FRC_TESTS int main() { - return frc::StartRobot(); + return wpi::StartRobot(); } #endif diff --git a/wpilibcExamples/src/main/cpp/templates/timed/include/Robot.hpp b/wpilibcExamples/src/main/cpp/templates/timed/include/Robot.hpp index 39e5ca91dd..e034f38868 100644 --- a/wpilibcExamples/src/main/cpp/templates/timed/include/Robot.hpp +++ b/wpilibcExamples/src/main/cpp/templates/timed/include/Robot.hpp @@ -9,7 +9,7 @@ #include #include -class Robot : public frc::TimedRobot { +class Robot : public wpi::TimedRobot { public: Robot(); void RobotPeriodic() override; @@ -25,7 +25,7 @@ class Robot : public frc::TimedRobot { void SimulationPeriodic() override; private: - frc::SendableChooser m_chooser; + wpi::SendableChooser m_chooser; const std::string kAutoNameDefault = "Default"; const std::string kAutoNameCustom = "My Auto"; std::string m_autoSelected; diff --git a/wpilibcExamples/src/main/cpp/templates/timedskeleton/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/templates/timedskeleton/cpp/Robot.cpp index 9fde8e5794..0067b83b4c 100644 --- a/wpilibcExamples/src/main/cpp/templates/timedskeleton/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/templates/timedskeleton/cpp/Robot.cpp @@ -24,6 +24,6 @@ void Robot::SimulationPeriodic() {} #ifndef RUNNING_FRC_TESTS int main() { - return frc::StartRobot(); + return wpi::StartRobot(); } #endif diff --git a/wpilibcExamples/src/main/cpp/templates/timedskeleton/include/Robot.hpp b/wpilibcExamples/src/main/cpp/templates/timedskeleton/include/Robot.hpp index 33a087e501..aebabcb187 100644 --- a/wpilibcExamples/src/main/cpp/templates/timedskeleton/include/Robot.hpp +++ b/wpilibcExamples/src/main/cpp/templates/timedskeleton/include/Robot.hpp @@ -6,7 +6,7 @@ #include -class Robot : public frc::TimedRobot { +class Robot : public wpi::TimedRobot { public: Robot(); void RobotPeriodic() override; diff --git a/wpilibcExamples/src/main/cpp/templates/timeslice/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/templates/timeslice/cpp/Robot.cpp index 61300c9504..4beafe288b 100644 --- a/wpilibcExamples/src/main/cpp/templates/timeslice/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/templates/timeslice/cpp/Robot.cpp @@ -8,7 +8,7 @@ #include // Run robot periodic() functions for 5 ms, and run controllers every 10 ms -Robot::Robot() : frc::TimesliceRobot{5_ms, 10_ms} { +Robot::Robot() : wpi::TimesliceRobot{5_ms, 10_ms} { // Runs for 2 ms after robot periodic functions Schedule([=] {}, 2_ms); @@ -21,7 +21,7 @@ Robot::Robot() : frc::TimesliceRobot{5_ms, 10_ms} { m_chooser.SetDefaultOption(kAutoNameDefault, kAutoNameDefault); m_chooser.AddOption(kAutoNameCustom, kAutoNameCustom); - frc::SmartDashboard::PutData("Auto Modes", &m_chooser); + wpi::SmartDashboard::PutData("Auto Modes", &m_chooser); } /** @@ -49,7 +49,7 @@ void Robot::AutonomousInit() { m_autoSelected = m_chooser.GetSelected(); // m_autoSelected = SmartDashboard::GetString("Auto Selector", // kAutoNameDefault); - wpi::print("Auto selected: {}\n", m_autoSelected); + wpi::util::print("Auto selected: {}\n", m_autoSelected); if (m_autoSelected == kAutoNameCustom) { // Custom Auto goes here @@ -80,6 +80,6 @@ void Robot::TestPeriodic() {} #ifndef RUNNING_FRC_TESTS int main() { - return frc::StartRobot(); + return wpi::StartRobot(); } #endif diff --git a/wpilibcExamples/src/main/cpp/templates/timeslice/include/Robot.hpp b/wpilibcExamples/src/main/cpp/templates/timeslice/include/Robot.hpp index f896468b13..927297d553 100644 --- a/wpilibcExamples/src/main/cpp/templates/timeslice/include/Robot.hpp +++ b/wpilibcExamples/src/main/cpp/templates/timeslice/include/Robot.hpp @@ -9,7 +9,7 @@ #include #include -class Robot : public frc::TimesliceRobot { +class Robot : public wpi::TimesliceRobot { public: Robot(); void RobotPeriodic() override; @@ -23,7 +23,7 @@ class Robot : public frc::TimesliceRobot { void TestPeriodic() override; private: - frc::SendableChooser m_chooser; + wpi::SendableChooser m_chooser; const std::string kAutoNameDefault = "Default"; const std::string kAutoNameCustom = "My Auto"; std::string m_autoSelected; diff --git a/wpilibcExamples/src/main/cpp/templates/timesliceskeleton/cpp/Robot.cpp b/wpilibcExamples/src/main/cpp/templates/timesliceskeleton/cpp/Robot.cpp index ed07740f93..10a6897371 100644 --- a/wpilibcExamples/src/main/cpp/templates/timesliceskeleton/cpp/Robot.cpp +++ b/wpilibcExamples/src/main/cpp/templates/timesliceskeleton/cpp/Robot.cpp @@ -5,7 +5,7 @@ #include "Robot.hpp" // Run robot periodic() functions for 5 ms, and run controllers every 10 ms -Robot::Robot() : frc::TimesliceRobot{5_ms, 10_ms} { +Robot::Robot() : wpi::TimesliceRobot{5_ms, 10_ms} { // Runs for 2 ms after robot periodic functions Schedule([=] {}, 2_ms); @@ -33,6 +33,6 @@ void Robot::TestPeriodic() {} #ifndef RUNNING_FRC_TESTS int main() { - return frc::StartRobot(); + return wpi::StartRobot(); } #endif diff --git a/wpilibcExamples/src/main/cpp/templates/timesliceskeleton/include/Robot.hpp b/wpilibcExamples/src/main/cpp/templates/timesliceskeleton/include/Robot.hpp index bc3b7a2bae..8edaad8882 100644 --- a/wpilibcExamples/src/main/cpp/templates/timesliceskeleton/include/Robot.hpp +++ b/wpilibcExamples/src/main/cpp/templates/timesliceskeleton/include/Robot.hpp @@ -6,7 +6,7 @@ #include -class Robot : public frc::TimesliceRobot { +class Robot : public wpi::TimesliceRobot { public: Robot(); diff --git a/wpilibcExamples/src/test/cpp/examples/ArmSimulation/cpp/ArmSimulationTest.cpp b/wpilibcExamples/src/test/cpp/examples/ArmSimulation/cpp/ArmSimulationTest.cpp index 8fcbe076da..81fef9c41d 100644 --- a/wpilibcExamples/src/test/cpp/examples/ArmSimulation/cpp/ArmSimulationTest.cpp +++ b/wpilibcExamples/src/test/cpp/examples/ArmSimulation/cpp/ArmSimulationTest.cpp @@ -18,22 +18,22 @@ #include "Constants.hpp" #include "Robot.hpp" -class ArmSimulationTest : public testing::TestWithParam { +class ArmSimulationTest : public testing::TestWithParam { Robot m_robot; std::optional m_thread; protected: - frc::sim::PWMMotorControllerSim m_motorSim{kMotorPort}; - frc::sim::EncoderSim m_encoderSim = - frc::sim::EncoderSim::CreateForChannel(kEncoderAChannel); - frc::sim::JoystickSim m_joystickSim{kJoystickPort}; + wpi::sim::PWMMotorControllerSim m_motorSim{kMotorPort}; + wpi::sim::EncoderSim m_encoderSim = + wpi::sim::EncoderSim::CreateForChannel(kEncoderAChannel); + wpi::sim::JoystickSim m_joystickSim{kJoystickPort}; public: void SetUp() override { - frc::sim::PauseTiming(); + wpi::sim::PauseTiming(); m_thread = std::thread([&] { m_robot.StartCompetition(); }); - frc::sim::StepTiming(0.0_ms); // Wait for Notifiers + wpi::sim::StepTiming(0.0_ms); // Wait for Notifiers } void TearDown() override { @@ -41,30 +41,30 @@ class ArmSimulationTest : public testing::TestWithParam { m_thread->join(); m_encoderSim.ResetData(); - frc::sim::DriverStationSim::ResetData(); - frc::Preferences::RemoveAll(); + wpi::sim::DriverStationSim::ResetData(); + wpi::Preferences::RemoveAll(); } }; TEST_P(ArmSimulationTest, Teleop) { - EXPECT_TRUE(frc::Preferences::ContainsKey(kArmPositionKey)); - EXPECT_TRUE(frc::Preferences::ContainsKey(kArmPKey)); - frc::Preferences::SetDouble(kArmPositionKey, GetParam().value()); - units::degree_t setpoint = GetParam(); + EXPECT_TRUE(wpi::Preferences::ContainsKey(kArmPositionKey)); + EXPECT_TRUE(wpi::Preferences::ContainsKey(kArmPKey)); + wpi::Preferences::SetDouble(kArmPositionKey, GetParam().value()); + wpi::units::degree_t setpoint = GetParam(); EXPECT_DOUBLE_EQ(setpoint.value(), - frc::Preferences::GetDouble(kArmPositionKey, NAN)); + wpi::Preferences::GetDouble(kArmPositionKey, NAN)); // teleop init { - frc::sim::DriverStationSim::SetAutonomous(false); - frc::sim::DriverStationSim::SetEnabled(true); - frc::sim::DriverStationSim::NotifyNewData(); + wpi::sim::DriverStationSim::SetAutonomous(false); + wpi::sim::DriverStationSim::SetEnabled(true); + wpi::sim::DriverStationSim::NotifyNewData(); EXPECT_TRUE(m_encoderSim.GetInitialized()); } { - frc::sim::StepTiming(3_s); + wpi::sim::StepTiming(3_s); // Ensure arm is still at minimum angle. EXPECT_NEAR(kMinAngle.value(), m_encoderSim.GetDistance(), 2.0); @@ -75,20 +75,20 @@ TEST_P(ArmSimulationTest, Teleop) { m_joystickSim.SetTrigger(true); m_joystickSim.NotifyNewData(); - frc::sim::StepTiming(1.5_s); + wpi::sim::StepTiming(1.5_s); EXPECT_NEAR(setpoint.value(), - units::radian_t(m_encoderSim.GetDistance()) - .convert() + wpi::units::radian_t(m_encoderSim.GetDistance()) + .convert() .value(), 2.0); // see setpoint is held. - frc::sim::StepTiming(0.5_s); + wpi::sim::StepTiming(0.5_s); EXPECT_NEAR(setpoint.value(), - units::radian_t(m_encoderSim.GetDistance()) - .convert() + wpi::units::radian_t(m_encoderSim.GetDistance()) + .convert() .value(), 2.0); } @@ -98,7 +98,7 @@ TEST_P(ArmSimulationTest, Teleop) { m_joystickSim.SetTrigger(false); m_joystickSim.NotifyNewData(); - frc::sim::StepTiming(3_s); + wpi::sim::StepTiming(3_s); EXPECT_NEAR(kMinAngle.value(), m_encoderSim.GetDistance(), 2.0); } @@ -109,31 +109,31 @@ TEST_P(ArmSimulationTest, Teleop) { m_joystickSim.NotifyNewData(); // advance 75 timesteps - frc::sim::StepTiming(1.5_s); + wpi::sim::StepTiming(1.5_s); EXPECT_NEAR(setpoint.value(), - units::radian_t(m_encoderSim.GetDistance()) - .convert() + wpi::units::radian_t(m_encoderSim.GetDistance()) + .convert() .value(), 2.0); // advance 25 timesteps to see setpoint is held. - frc::sim::StepTiming(0.5_s); + wpi::sim::StepTiming(0.5_s); EXPECT_NEAR(setpoint.value(), - units::radian_t(m_encoderSim.GetDistance()) - .convert() + wpi::units::radian_t(m_encoderSim.GetDistance()) + .convert() .value(), 2.0); } { // Disable - frc::sim::DriverStationSim::SetAutonomous(false); - frc::sim::DriverStationSim::SetEnabled(false); - frc::sim::DriverStationSim::NotifyNewData(); + wpi::sim::DriverStationSim::SetAutonomous(false); + wpi::sim::DriverStationSim::SetEnabled(false); + wpi::sim::DriverStationSim::NotifyNewData(); - frc::sim::StepTiming(3_s); + wpi::sim::StepTiming(3_s); ASSERT_NEAR(0.0, m_motorSim.GetSpeed(), 0.05); EXPECT_NEAR(kMinAngle.value(), m_encoderSim.GetDistance(), 2.0); @@ -143,7 +143,7 @@ TEST_P(ArmSimulationTest, Teleop) { INSTANTIATE_TEST_SUITE_P( ArmSimulationTests, ArmSimulationTest, testing::Values(kDefaultArmSetpoint, 25.0_deg, 50.0_deg), - [](const testing::TestParamInfo& info) { + [](const testing::TestParamInfo& info) { return testing::PrintToString(info.param.value()) .append(std::string(info.param.abbreviation())); }); diff --git a/wpilibcExamples/src/test/cpp/examples/DigitalCommunication/cpp/DigitalCommunicationTest.cpp b/wpilibcExamples/src/test/cpp/examples/DigitalCommunication/cpp/DigitalCommunicationTest.cpp index 0d02f5f016..248d3693a4 100644 --- a/wpilibcExamples/src/test/cpp/examples/DigitalCommunication/cpp/DigitalCommunicationTest.cpp +++ b/wpilibcExamples/src/test/cpp/examples/DigitalCommunication/cpp/DigitalCommunicationTest.cpp @@ -16,19 +16,19 @@ template class DigitalCommunicationTest : public testing::TestWithParam { public: - frc::sim::DIOSim m_allianceOutput{Robot::kAlliancePort}; - frc::sim::DIOSim m_enabledOutput{Robot::kEnabledPort}; - frc::sim::DIOSim m_autonomousOutput{Robot::kAutonomousPort}; - frc::sim::DIOSim m_alertOutput{Robot::kAlertPort}; + wpi::sim::DIOSim m_allianceOutput{Robot::kAlliancePort}; + wpi::sim::DIOSim m_enabledOutput{Robot::kEnabledPort}; + wpi::sim::DIOSim m_autonomousOutput{Robot::kAutonomousPort}; + wpi::sim::DIOSim m_alertOutput{Robot::kAlertPort}; Robot m_robot; std::optional m_thread; void SetUp() override { - frc::sim::PauseTiming(); - frc::sim::DriverStationSim::ResetData(); + wpi::sim::PauseTiming(); + wpi::sim::DriverStationSim::ResetData(); m_thread = std::thread([&] { m_robot.StartCompetition(); }); - frc::sim::StepTiming(0.0_ms); + wpi::sim::StepTiming(0.0_ms); // SimHooks.stepTiming(0.0); // Wait for Notifiers } @@ -46,13 +46,13 @@ class AllianceTest : public DigitalCommunicationTest {}; TEST_P(AllianceTest, Alliance) { auto alliance = GetParam(); - frc::sim::DriverStationSim::SetAllianceStationId(alliance); - frc::sim::DriverStationSim::NotifyNewData(); + wpi::sim::DriverStationSim::SetAllianceStationId(alliance); + wpi::sim::DriverStationSim::NotifyNewData(); EXPECT_TRUE(m_allianceOutput.GetInitialized()); EXPECT_FALSE(m_allianceOutput.GetIsInput()); - frc::sim::StepTiming(20_ms); + wpi::sim::StepTiming(20_ms); bool isRed = false; switch (alliance) { @@ -102,13 +102,13 @@ class EnabledTest : public DigitalCommunicationTest {}; TEST_P(EnabledTest, Enabled) { auto enabled = GetParam(); - frc::sim::DriverStationSim::SetEnabled(enabled); - frc::sim::DriverStationSim::NotifyNewData(); + wpi::sim::DriverStationSim::SetEnabled(enabled); + wpi::sim::DriverStationSim::NotifyNewData(); EXPECT_TRUE(m_enabledOutput.GetInitialized()); EXPECT_FALSE(m_enabledOutput.GetIsInput()); - frc::sim::StepTiming(20_ms); + wpi::sim::StepTiming(20_ms); EXPECT_EQ(enabled, m_enabledOutput.GetValue()); } @@ -120,13 +120,13 @@ class AutonomousTest : public DigitalCommunicationTest {}; TEST_P(AutonomousTest, Autonomous) { auto autonomous = GetParam(); - frc::sim::DriverStationSim::SetAutonomous(autonomous); - frc::sim::DriverStationSim::NotifyNewData(); + wpi::sim::DriverStationSim::SetAutonomous(autonomous); + wpi::sim::DriverStationSim::NotifyNewData(); EXPECT_TRUE(m_autonomousOutput.GetInitialized()); EXPECT_FALSE(m_autonomousOutput.GetIsInput()); - frc::sim::StepTiming(20_ms); + wpi::sim::StepTiming(20_ms); EXPECT_EQ(autonomous, m_autonomousOutput.GetValue()); } @@ -138,13 +138,13 @@ class AlertTest : public DigitalCommunicationTest {}; TEST_P(AlertTest, Alert) { auto matchTime = GetParam(); - frc::sim::DriverStationSim::SetMatchTime(matchTime); - frc::sim::DriverStationSim::NotifyNewData(); + wpi::sim::DriverStationSim::SetMatchTime(matchTime); + wpi::sim::DriverStationSim::NotifyNewData(); EXPECT_TRUE(m_alertOutput.GetInitialized()); EXPECT_FALSE(m_alertOutput.GetIsInput()); - frc::sim::StepTiming(20_ms); + wpi::sim::StepTiming(20_ms); EXPECT_EQ(matchTime <= 30 && matchTime >= 25, m_alertOutput.GetValue()); } diff --git a/wpilibcExamples/src/test/cpp/examples/ElevatorSimulation/cpp/ElevatorSimulationTest.cpp b/wpilibcExamples/src/test/cpp/examples/ElevatorSimulation/cpp/ElevatorSimulationTest.cpp index cb34ed35fb..04cfccb64e 100644 --- a/wpilibcExamples/src/test/cpp/examples/ElevatorSimulation/cpp/ElevatorSimulationTest.cpp +++ b/wpilibcExamples/src/test/cpp/examples/ElevatorSimulation/cpp/ElevatorSimulationTest.cpp @@ -25,17 +25,17 @@ class ElevatorSimulationTest : public testing::Test { std::optional m_thread; protected: - frc::sim::PWMMotorControllerSim m_motorSim{Constants::kMotorPort}; - frc::sim::EncoderSim m_encoderSim = - frc::sim::EncoderSim::CreateForChannel(Constants::kEncoderAChannel); - frc::sim::JoystickSim m_joystickSim{Constants::kJoystickPort}; + wpi::sim::PWMMotorControllerSim m_motorSim{Constants::kMotorPort}; + wpi::sim::EncoderSim m_encoderSim = + wpi::sim::EncoderSim::CreateForChannel(Constants::kEncoderAChannel); + wpi::sim::JoystickSim m_joystickSim{Constants::kJoystickPort}; public: void SetUp() override { - frc::sim::PauseTiming(); + wpi::sim::PauseTiming(); m_thread = std::thread([&] { m_robot.StartCompetition(); }); - frc::sim::StepTiming(0.0_ms); // Wait for Notifiers + wpi::sim::StepTiming(0.0_ms); // Wait for Notifiers } void TearDown() override { @@ -43,23 +43,23 @@ class ElevatorSimulationTest : public testing::Test { m_thread->join(); m_encoderSim.ResetData(); - frc::sim::DriverStationSim::ResetData(); + wpi::sim::DriverStationSim::ResetData(); } }; TEST_F(ElevatorSimulationTest, Teleop) { // teleop init { - frc::sim::DriverStationSim::SetAutonomous(false); - frc::sim::DriverStationSim::SetEnabled(true); - frc::sim::DriverStationSim::NotifyNewData(); + wpi::sim::DriverStationSim::SetAutonomous(false); + wpi::sim::DriverStationSim::SetEnabled(true); + wpi::sim::DriverStationSim::NotifyNewData(); EXPECT_TRUE(m_encoderSim.GetInitialized()); } { // advance 50 timesteps - frc::sim::StepTiming(1_s); + wpi::sim::StepTiming(1_s); // Ensure elevator is still at 0. EXPECT_NEAR(0.0, m_encoderSim.GetDistance(), 0.05); @@ -71,12 +71,12 @@ TEST_F(ElevatorSimulationTest, Teleop) { m_joystickSim.NotifyNewData(); // advance 75 timesteps - frc::sim::StepTiming(1.5_s); + wpi::sim::StepTiming(1.5_s); EXPECT_NEAR(kSetpoint.value(), m_encoderSim.GetDistance(), 0.05); // advance 25 timesteps to see setpoint is held. - frc::sim::StepTiming(0.5_s); + wpi::sim::StepTiming(0.5_s); EXPECT_NEAR(kSetpoint.value(), m_encoderSim.GetDistance(), 0.05); } @@ -87,7 +87,7 @@ TEST_F(ElevatorSimulationTest, Teleop) { m_joystickSim.NotifyNewData(); // advance 75 timesteps - frc::sim::StepTiming(1.5_s); + wpi::sim::StepTiming(1.5_s); EXPECT_NEAR(0.0, m_encoderSim.GetDistance(), 0.05); } @@ -98,24 +98,24 @@ TEST_F(ElevatorSimulationTest, Teleop) { m_joystickSim.NotifyNewData(); // advance 75 timesteps - frc::sim::StepTiming(1.5_s); + wpi::sim::StepTiming(1.5_s); EXPECT_NEAR(kSetpoint.value(), m_encoderSim.GetDistance(), 0.05); // advance 25 timesteps to see setpoint is held. - frc::sim::StepTiming(0.5_s); + wpi::sim::StepTiming(0.5_s); EXPECT_NEAR(kSetpoint.value(), m_encoderSim.GetDistance(), 0.05); } { // Disable - frc::sim::DriverStationSim::SetAutonomous(false); - frc::sim::DriverStationSim::SetEnabled(false); - frc::sim::DriverStationSim::NotifyNewData(); + wpi::sim::DriverStationSim::SetAutonomous(false); + wpi::sim::DriverStationSim::SetEnabled(false); + wpi::sim::DriverStationSim::NotifyNewData(); // advance 75 timesteps - frc::sim::StepTiming(1.5_s); + wpi::sim::StepTiming(1.5_s); ASSERT_NEAR(0.0, m_motorSim.GetSpeed(), 0.05); ASSERT_NEAR(0.0, m_encoderSim.GetDistance(), 0.05); diff --git a/wpilibcExamples/src/test/cpp/examples/I2CCommunication/cpp/I2CCommunicationTest.cpp b/wpilibcExamples/src/test/cpp/examples/I2CCommunication/cpp/I2CCommunicationTest.cpp index 35c7436e62..27dfaf2972 100644 --- a/wpilibcExamples/src/test/cpp/examples/I2CCommunication/cpp/I2CCommunicationTest.cpp +++ b/wpilibcExamples/src/test/cpp/examples/I2CCommunication/cpp/I2CCommunicationTest.cpp @@ -31,14 +31,14 @@ class I2CCommunicationTest : public testing::TestWithParam { void SetUp() override { gString = std::string(); - frc::sim::PauseTiming(); - frc::sim::DriverStationSim::ResetData(); + wpi::sim::PauseTiming(); + wpi::sim::DriverStationSim::ResetData(); m_port = static_cast(Robot::kPort); m_callback = HALSIM_RegisterI2CWriteCallback(m_port, &callback, nullptr); m_thread = std::thread([&] { m_robot.StartCompetition(); }); - frc::sim::StepTiming(0.0_ms); // Wait for Notifiers + wpi::sim::StepTiming(0.0_ms); // Wait for Notifiers } void TearDown() override { @@ -54,12 +54,12 @@ class AllianceTest : public I2CCommunicationTest {}; TEST_P(AllianceTest, Alliance) { auto alliance = GetParam(); - frc::sim::DriverStationSim::SetAllianceStationId(alliance); - frc::sim::DriverStationSim::NotifyNewData(); + wpi::sim::DriverStationSim::SetAllianceStationId(alliance); + wpi::sim::DriverStationSim::NotifyNewData(); EXPECT_TRUE(HALSIM_GetI2CInitialized(m_port)); - frc::sim::StepTiming(20_ms); + wpi::sim::StepTiming(20_ms); char expected = 'U'; switch (alliance) { @@ -111,12 +111,12 @@ class EnabledTest : public I2CCommunicationTest {}; TEST_P(EnabledTest, Enabled) { auto enabled = GetParam(); - frc::sim::DriverStationSim::SetEnabled(enabled); - frc::sim::DriverStationSim::NotifyNewData(); + wpi::sim::DriverStationSim::SetEnabled(enabled); + wpi::sim::DriverStationSim::NotifyNewData(); EXPECT_TRUE(HALSIM_GetI2CInitialized(m_port)); - frc::sim::StepTiming(20_ms); + wpi::sim::StepTiming(20_ms); char expected = enabled ? 'E' : 'D'; EXPECT_EQ(expected, gString.at(1)); @@ -129,12 +129,12 @@ class AutonomousTest : public I2CCommunicationTest {}; TEST_P(AutonomousTest, Autonomous) { auto autonomous = GetParam(); - frc::sim::DriverStationSim::SetAutonomous(autonomous); - frc::sim::DriverStationSim::NotifyNewData(); + wpi::sim::DriverStationSim::SetAutonomous(autonomous); + wpi::sim::DriverStationSim::NotifyNewData(); EXPECT_TRUE(HALSIM_GetI2CInitialized(m_port)); - frc::sim::StepTiming(20_ms); + wpi::sim::StepTiming(20_ms); char expected = autonomous ? 'A' : 'T'; EXPECT_EQ(expected, gString.at(2)); @@ -147,12 +147,12 @@ class MatchTimeTest : public I2CCommunicationTest {}; TEST_P(MatchTimeTest, Alert) { auto matchTime = GetParam(); - frc::sim::DriverStationSim::SetMatchTime(matchTime); - frc::sim::DriverStationSim::NotifyNewData(); + wpi::sim::DriverStationSim::SetMatchTime(matchTime); + wpi::sim::DriverStationSim::NotifyNewData(); EXPECT_TRUE(HALSIM_GetI2CInitialized(m_port)); - frc::sim::StepTiming(20_ms); + wpi::sim::StepTiming(20_ms); std::string expected = fmt::format("{:03}", matchTime); EXPECT_EQ(expected, gString.substr(3)); diff --git a/wpilibcExamples/src/test/cpp/examples/PotentiometerPID/cpp/PotentiometerPIDTest.cpp b/wpilibcExamples/src/test/cpp/examples/PotentiometerPID/cpp/PotentiometerPIDTest.cpp index 594609795f..fbdb2330c2 100644 --- a/wpilibcExamples/src/test/cpp/examples/PotentiometerPID/cpp/PotentiometerPIDTest.cpp +++ b/wpilibcExamples/src/test/cpp/examples/PotentiometerPID/cpp/PotentiometerPIDTest.cpp @@ -22,16 +22,16 @@ #include "Robot.hpp" class PotentiometerPIDTest : public testing::Test { - frc::DCMotor m_elevatorGearbox = frc::DCMotor::Vex775Pro(4); + wpi::math::DCMotor m_elevatorGearbox = wpi::math::DCMotor::Vex775Pro(4); static constexpr double kElevatorGearing = 10.0; - static constexpr units::meter_t kElevatorDrumRadius = 2.0_in; - static constexpr units::kilogram_t kCarriageMass = 4.0_kg; + static constexpr wpi::units::meter_t kElevatorDrumRadius = 2.0_in; + static constexpr wpi::units::kilogram_t kCarriageMass = 4.0_kg; Robot m_robot; std::optional m_thread; protected: - frc::sim::ElevatorSim m_elevatorSim{m_elevatorGearbox, + wpi::sim::ElevatorSim m_elevatorSim{m_elevatorGearbox, kElevatorGearing, kCarriageMass, kElevatorDrumRadius, @@ -39,16 +39,16 @@ class PotentiometerPIDTest : public testing::Test { Robot::kFullHeight, true, 0.0_m}; - frc::sim::PWMMotorControllerSim m_motorSim{Robot::kMotorChannel}; - frc::sim::AnalogInputSim m_analogSim{Robot::kPotChannel}; - frc::sim::JoystickSim m_joystickSim{Robot::kJoystickChannel}; + wpi::sim::PWMMotorControllerSim m_motorSim{Robot::kMotorChannel}; + wpi::sim::AnalogInputSim m_analogSim{Robot::kPotChannel}; + wpi::sim::JoystickSim m_joystickSim{Robot::kJoystickChannel}; int32_t m_callback; int32_t m_port; public: void SimPeriodicBefore() { m_elevatorSim.SetInputVoltage(m_motorSim.GetSpeed() * - frc::RobotController::GetBatteryVoltage()); + wpi::RobotController::GetBatteryVoltage()); m_elevatorSim.Update(20_ms); /* @@ -57,7 +57,7 @@ class PotentiometerPIDTest : public testing::Test { 3.3v * (meters / range) = v */ m_analogSim.SetVoltage( - (frc::RobotController::GetVoltage3V3() * + (wpi::RobotController::GetVoltage3V3() * (m_elevatorSim.GetPosition().value() / Robot::kFullHeight)) .value()); } @@ -67,8 +67,8 @@ class PotentiometerPIDTest : public testing::Test { } void SetUp() override { - frc::sim::PauseTiming(); - frc::sim::DriverStationSim::ResetData(); + wpi::sim::PauseTiming(); + wpi::sim::DriverStationSim::ResetData(); m_joystickSim.SetButtonsMaximumIndex(12); @@ -76,7 +76,7 @@ class PotentiometerPIDTest : public testing::Test { HALSIM_RegisterSimPeriodicBeforeCallback(CallSimPeriodicBefore, this); m_thread = std::thread([&] { m_robot.StartCompetition(); }); - frc::sim::StepTiming(0.0_ms); // Wait for Notifiers + wpi::sim::StepTiming(0.0_ms); // Wait for Notifiers } void TearDown() override { @@ -91,9 +91,9 @@ class PotentiometerPIDTest : public testing::Test { TEST_F(PotentiometerPIDTest, Teleop) { // teleop init { - frc::sim::DriverStationSim::SetAutonomous(false); - frc::sim::DriverStationSim::SetEnabled(true); - frc::sim::DriverStationSim::NotifyNewData(); + wpi::sim::DriverStationSim::SetAutonomous(false); + wpi::sim::DriverStationSim::SetEnabled(true); + wpi::sim::DriverStationSim::NotifyNewData(); EXPECT_TRUE(m_analogSim.GetInitialized()); } @@ -101,7 +101,7 @@ TEST_F(PotentiometerPIDTest, Teleop) { // first setpoint { // advance 50 timesteps - frc::sim::StepTiming(1_s); + wpi::sim::StepTiming(1_s); EXPECT_NEAR(Robot::kSetpoints[0].value(), m_elevatorSim.GetPosition().value(), 0.1); @@ -114,7 +114,7 @@ TEST_F(PotentiometerPIDTest, Teleop) { m_joystickSim.NotifyNewData(); // advance 50 timesteps - frc::sim::StepTiming(1_s); + wpi::sim::StepTiming(1_s); EXPECT_NEAR(Robot::kSetpoints[1].value(), m_elevatorSim.GetPosition().value(), 0.1); @@ -126,7 +126,7 @@ TEST_F(PotentiometerPIDTest, Teleop) { m_joystickSim.NotifyNewData(); // advance 10 timesteps - frc::sim::StepTiming(0.2_s); + wpi::sim::StepTiming(0.2_s); } // third setpoint @@ -136,7 +136,7 @@ TEST_F(PotentiometerPIDTest, Teleop) { m_joystickSim.NotifyNewData(); // advance 50 timesteps - frc::sim::StepTiming(1_s); + wpi::sim::StepTiming(1_s); EXPECT_NEAR(Robot::kSetpoints[2].value(), m_elevatorSim.GetPosition().value(), 0.1); @@ -148,7 +148,7 @@ TEST_F(PotentiometerPIDTest, Teleop) { m_joystickSim.NotifyNewData(); // advance 10 timesteps - frc::sim::StepTiming(0.2_s); + wpi::sim::StepTiming(0.2_s); } // rollover: first setpoint @@ -158,7 +158,7 @@ TEST_F(PotentiometerPIDTest, Teleop) { m_joystickSim.NotifyNewData(); // advance 60 timesteps - frc::sim::StepTiming(1.2_s); + wpi::sim::StepTiming(1.2_s); EXPECT_NEAR(Robot::kSetpoints[0].value(), m_elevatorSim.GetPosition().value(), 0.1); } diff --git a/wpilibcExamples/src/test/cpp/examples/UnitTest/cpp/subsystems/IntakeTest.cpp b/wpilibcExamples/src/test/cpp/examples/UnitTest/cpp/subsystems/IntakeTest.cpp index c6f541c9e8..73ba07468d 100644 --- a/wpilibcExamples/src/test/cpp/examples/UnitTest/cpp/subsystems/IntakeTest.cpp +++ b/wpilibcExamples/src/test/cpp/examples/UnitTest/cpp/subsystems/IntakeTest.cpp @@ -13,10 +13,10 @@ class IntakeTest : public testing::Test { protected: Intake intake; // create our intake - frc::sim::PWMMotorControllerSim simMotor{ + wpi::sim::PWMMotorControllerSim simMotor{ IntakeConstants::kMotorPort}; // create our simulation PWM - frc::sim::DoubleSolenoidSim simPiston{ - frc::PneumaticsModuleType::CTREPCM, IntakeConstants::kPistonFwdChannel, + wpi::sim::DoubleSolenoidSim simPiston{ + wpi::PneumaticsModuleType::CTREPCM, IntakeConstants::kPistonFwdChannel, IntakeConstants::kPistonRevChannel}; // create our simulation solenoid }; @@ -36,10 +36,10 @@ TEST_F(IntakeTest, WorksWhenOpen) { TEST_F(IntakeTest, Retract) { intake.Retract(); - EXPECT_EQ(frc::DoubleSolenoid::Value::kReverse, simPiston.Get()); + EXPECT_EQ(wpi::DoubleSolenoid::Value::kReverse, simPiston.Get()); } TEST_F(IntakeTest, Deploy) { intake.Deploy(); - EXPECT_EQ(frc::DoubleSolenoid::Value::kForward, simPiston.Get()); + EXPECT_EQ(wpi::DoubleSolenoid::Value::kForward, simPiston.Get()); } diff --git a/wpimath/src/dev/native/cpp/main.cpp b/wpimath/src/dev/native/cpp/main.cpp index 93e9ca7fcc..3c5d56bb18 100644 --- a/wpimath/src/dev/native/cpp/main.cpp +++ b/wpimath/src/dev/native/cpp/main.cpp @@ -7,5 +7,5 @@ #include "wpi/util/print.hpp" int main() { - wpi::print("{}\n", std::numbers::pi); + wpi::util::print("{}\n", std::numbers::pi); } diff --git a/wpimath/src/main/native/cpp/controller/ArmFeedforward.cpp b/wpimath/src/main/native/cpp/controller/ArmFeedforward.cpp index 1e5530cf5d..89f9629cfc 100644 --- a/wpimath/src/main/native/cpp/controller/ArmFeedforward.cpp +++ b/wpimath/src/main/native/cpp/controller/ArmFeedforward.cpp @@ -13,18 +13,18 @@ #include "wpi/math/linalg/EigenCore.hpp" #include "wpi/math/system/NumericalIntegration.hpp" -using namespace frc; +using namespace wpi::math; -units::volt_t ArmFeedforward::Calculate( - units::unit_t currentAngle, units::unit_t currentVelocity, - units::unit_t nextVelocity) const { +wpi::units::volt_t ArmFeedforward::Calculate( + wpi::units::unit_t currentAngle, wpi::units::unit_t currentVelocity, + wpi::units::unit_t nextVelocity) const { using VarMat = slp::VariableMatrix; // Small kₐ values make the solver ill-conditioned - if (kA < units::unit_t{1e-1}) { + if (kA < wpi::units::unit_t{1e-1}) { auto acceleration = (nextVelocity - currentVelocity) / m_dt; - return kS * wpi::sgn(currentVelocity.value()) + kV * currentVelocity + - kA * acceleration + kG * units::math::cos(currentAngle); + return kS * wpi::util::sgn(currentVelocity.value()) + kV * currentVelocity + + kA * acceleration + kG * wpi::units::math::cos(currentAngle); } // Arm dynamics @@ -43,8 +43,8 @@ units::volt_t ArmFeedforward::Calculate( // Initial guess auto acceleration = (nextVelocity - currentVelocity) / m_dt; - u_k.set_value((kS * wpi::sgn(currentVelocity.value()) + kV * currentVelocity + - kA * acceleration + kG * units::math::cos(currentAngle)) + u_k.set_value((kS * wpi::util::sgn(currentVelocity.value()) + kV * currentVelocity + + kA * acceleration + kG * wpi::units::math::cos(currentAngle)) .value()); auto r_k1 = RK4(f, r_k, u_k, m_dt); @@ -107,5 +107,5 @@ units::volt_t ArmFeedforward::Calculate( } } - return units::volt_t{u_k.value()}; + return wpi::units::volt_t{u_k.value()}; } diff --git a/wpimath/src/main/native/cpp/controller/BangBangController.cpp b/wpimath/src/main/native/cpp/controller/BangBangController.cpp index f8d716d3f3..d9a8e001dc 100644 --- a/wpimath/src/main/native/cpp/controller/BangBangController.cpp +++ b/wpimath/src/main/native/cpp/controller/BangBangController.cpp @@ -6,9 +6,9 @@ #include "wpi/util/sendable/SendableBuilder.hpp" -using namespace frc; +using namespace wpi::math; -void BangBangController::InitSendable(wpi::SendableBuilder& builder) { +void BangBangController::InitSendable(wpi::util::SendableBuilder& builder) { builder.SetSmartDashboardType("BangBangController"); builder.AddDoubleProperty( "tolerance", [this] { return GetTolerance(); }, diff --git a/wpimath/src/main/native/cpp/controller/DifferentialDriveAccelerationLimiter.cpp b/wpimath/src/main/native/cpp/controller/DifferentialDriveAccelerationLimiter.cpp index a3610a96bd..c415f433a0 100644 --- a/wpimath/src/main/native/cpp/controller/DifferentialDriveAccelerationLimiter.cpp +++ b/wpimath/src/main/native/cpp/controller/DifferentialDriveAccelerationLimiter.cpp @@ -6,12 +6,12 @@ #include -using namespace frc; +using namespace wpi::math; DifferentialDriveWheelVoltages DifferentialDriveAccelerationLimiter::Calculate( - units::meters_per_second_t leftVelocity, - units::meters_per_second_t rightVelocity, units::volt_t leftVoltage, - units::volt_t rightVoltage) { + wpi::units::meters_per_second_t leftVelocity, + wpi::units::meters_per_second_t rightVelocity, wpi::units::volt_t leftVoltage, + wpi::units::volt_t rightVoltage) { Vectord<2> u{leftVoltage.value(), rightVoltage.value()}; // Find unconstrained wheel accelerations @@ -56,5 +56,5 @@ DifferentialDriveWheelVoltages DifferentialDriveAccelerationLimiter::Calculate( // u = B⁻¹(dx/dt - Ax) u = m_system.B().householderQr().solve(dxdt - m_system.A() * x); - return {units::volt_t{u(0)}, units::volt_t{u(1)}}; + return {wpi::units::volt_t{u(0)}, wpi::units::volt_t{u(1)}}; } diff --git a/wpimath/src/main/native/cpp/controller/DifferentialDriveFeedforward.cpp b/wpimath/src/main/native/cpp/controller/DifferentialDriveFeedforward.cpp index 4c40b36684..2c0a002fb9 100644 --- a/wpimath/src/main/native/cpp/controller/DifferentialDriveFeedforward.cpp +++ b/wpimath/src/main/native/cpp/controller/DifferentialDriveFeedforward.cpp @@ -8,17 +8,17 @@ #include "wpi/math/controller/LinearPlantInversionFeedforward.hpp" -using namespace frc; +using namespace wpi::math; DifferentialDriveWheelVoltages DifferentialDriveFeedforward::Calculate( - units::meters_per_second_t currentLeftVelocity, - units::meters_per_second_t nextLeftVelocity, - units::meters_per_second_t currentRightVelocity, - units::meters_per_second_t nextRightVelocity, units::second_t dt) { - frc::LinearPlantInversionFeedforward<2, 2> feedforward{m_plant, dt}; + wpi::units::meters_per_second_t currentLeftVelocity, + wpi::units::meters_per_second_t nextLeftVelocity, + wpi::units::meters_per_second_t currentRightVelocity, + wpi::units::meters_per_second_t nextRightVelocity, wpi::units::second_t dt) { + wpi::math::LinearPlantInversionFeedforward<2, 2> feedforward{m_plant, dt}; Eigen::Vector2d r{currentLeftVelocity, currentRightVelocity}; Eigen::Vector2d nextR{nextLeftVelocity, nextRightVelocity}; auto u = feedforward.Calculate(r, nextR); - return {units::volt_t{u(0)}, units::volt_t{u(1)}}; + return {wpi::units::volt_t{u(0)}, wpi::units::volt_t{u(1)}}; } diff --git a/wpimath/src/main/native/cpp/controller/LTVDifferentialDriveController.cpp b/wpimath/src/main/native/cpp/controller/LTVDifferentialDriveController.cpp index ae9dce653c..dc65925731 100644 --- a/wpimath/src/main/native/cpp/controller/LTVDifferentialDriveController.cpp +++ b/wpimath/src/main/native/cpp/controller/LTVDifferentialDriveController.cpp @@ -10,13 +10,13 @@ #include "wpi/math/system/Discretization.hpp" #include "wpi/math/util/MathUtil.hpp" -using namespace frc; +using namespace wpi::math; DifferentialDriveWheelVoltages LTVDifferentialDriveController::Calculate( - const Pose2d& currentPose, units::meters_per_second_t leftVelocity, - units::meters_per_second_t rightVelocity, const Pose2d& poseRef, - units::meters_per_second_t leftVelocityRef, - units::meters_per_second_t rightVelocityRef) { + const Pose2d& currentPose, wpi::units::meters_per_second_t leftVelocity, + wpi::units::meters_per_second_t rightVelocity, const Pose2d& poseRef, + wpi::units::meters_per_second_t leftVelocityRef, + wpi::units::meters_per_second_t rightVelocityRef) { // This implements the linear time-varying differential drive controller in // theorem 8.7.4 of https://controls-in-frc.link/ // @@ -26,11 +26,11 @@ DifferentialDriveWheelVoltages LTVDifferentialDriveController::Calculate( // [vₗ] // [vᵣ] - units::meters_per_second_t velocity{(leftVelocity + rightVelocity) / 2.0}; + wpi::units::meters_per_second_t velocity{(leftVelocity + rightVelocity) / 2.0}; // The DARE is ill-conditioned if the velocity is close to zero, so don't // let the system stop. - if (units::math::abs(velocity) < 1e-4_mps) { + if (wpi::units::math::abs(velocity) < 1e-4_mps) { velocity = 1e-4_mps; } @@ -42,7 +42,7 @@ DifferentialDriveWheelVoltages LTVDifferentialDriveController::Calculate( leftVelocity.value(), rightVelocity.value()}; m_error = r - x; - m_error(2) = frc::AngleModulus(units::radian_t{m_error(2)}).value(); + m_error(2) = wpi::math::AngleModulus(wpi::units::radian_t{m_error(2)}).value(); Eigen::Matrix A{ {0.0, 0.0, 0.0, 0.5, 0.5}, @@ -76,6 +76,6 @@ DifferentialDriveWheelVoltages LTVDifferentialDriveController::Calculate( Eigen::Vector2d u = K * inRobotFrame * m_error; - return DifferentialDriveWheelVoltages{units::volt_t{u(0)}, - units::volt_t{u(1)}}; + return DifferentialDriveWheelVoltages{wpi::units::volt_t{u(0)}, + wpi::units::volt_t{u(1)}}; } diff --git a/wpimath/src/main/native/cpp/controller/LTVUnicycleController.cpp b/wpimath/src/main/native/cpp/controller/LTVUnicycleController.cpp index 66045bdf5f..fb84617472 100644 --- a/wpimath/src/main/native/cpp/controller/LTVUnicycleController.cpp +++ b/wpimath/src/main/native/cpp/controller/LTVUnicycleController.cpp @@ -8,12 +8,12 @@ #include "wpi/math/system/Discretization.hpp" #include "wpi/units/math.hpp" -using namespace frc; +using namespace wpi::math; ChassisSpeeds LTVUnicycleController::Calculate( const Pose2d& currentPose, const Pose2d& poseRef, - units::meters_per_second_t linearVelocityRef, - units::radians_per_second_t angularVelocityRef) { + wpi::units::meters_per_second_t linearVelocityRef, + wpi::units::radians_per_second_t angularVelocityRef) { // The change in global pose for a unicycle is defined by the following three // equations. // @@ -53,7 +53,7 @@ ChassisSpeeds LTVUnicycleController::Calculate( // The DARE is ill-conditioned if the velocity is close to zero, so don't // let the system stop. - if (units::math::abs(linearVelocityRef) < 1e-4_mps) { + if (wpi::units::math::abs(linearVelocityRef) < 1e-4_mps) { linearVelocityRef = 1e-4_mps; } @@ -78,7 +78,7 @@ ChassisSpeeds LTVUnicycleController::Calculate( m_poseError.Rotation().Radians().value()}; Eigen::Vector2d u = K * e; - return ChassisSpeeds{linearVelocityRef + units::meters_per_second_t{u(0)}, + return ChassisSpeeds{linearVelocityRef + wpi::units::meters_per_second_t{u(0)}, 0_mps, - angularVelocityRef + units::radians_per_second_t{u(1)}}; + angularVelocityRef + wpi::units::radians_per_second_t{u(1)}}; } diff --git a/wpimath/src/main/native/cpp/controller/LinearQuadraticRegulator.cpp b/wpimath/src/main/native/cpp/controller/LinearQuadraticRegulator.cpp index ce03b7796a..494d5fcf6e 100644 --- a/wpimath/src/main/native/cpp/controller/LinearQuadraticRegulator.cpp +++ b/wpimath/src/main/native/cpp/controller/LinearQuadraticRegulator.cpp @@ -4,7 +4,7 @@ #include "wpi/math/controller/LinearQuadraticRegulator.hpp" -namespace frc { +namespace wpi::math { template class EXPORT_TEMPLATE_DEFINE(WPILIB_DLLEXPORT) LinearQuadraticRegulator<1, 1>; @@ -13,4 +13,4 @@ template class EXPORT_TEMPLATE_DEFINE(WPILIB_DLLEXPORT) template class EXPORT_TEMPLATE_DEFINE(WPILIB_DLLEXPORT) LinearQuadraticRegulator<2, 2>; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/cpp/controller/PIDController.cpp b/wpimath/src/main/native/cpp/controller/PIDController.cpp index 3274afed37..95212bcb84 100644 --- a/wpimath/src/main/native/cpp/controller/PIDController.cpp +++ b/wpimath/src/main/native/cpp/controller/PIDController.cpp @@ -6,9 +6,9 @@ #include "wpi/util/sendable/SendableBuilder.hpp" -using namespace frc; +using namespace wpi::math; -void PIDController::InitSendable(wpi::SendableBuilder& builder) { +void PIDController::InitSendable(wpi::util::SendableBuilder& builder) { builder.SetSmartDashboardType("PIDController"); builder.AddDoubleProperty( "p", [this] { return GetP(); }, [this](double value) { SetP(value); }); diff --git a/wpimath/src/main/native/cpp/controller/ProfiledPIDController.cpp b/wpimath/src/main/native/cpp/controller/ProfiledPIDController.cpp index c7a96b04b3..6709612efd 100644 --- a/wpimath/src/main/native/cpp/controller/ProfiledPIDController.cpp +++ b/wpimath/src/main/native/cpp/controller/ProfiledPIDController.cpp @@ -4,7 +4,7 @@ #include "wpi/math/controller/ProfiledPIDController.hpp" -int frc::detail::IncrementAndGetProfiledPIDControllerInstances() { +int wpi::math::detail::IncrementAndGetProfiledPIDControllerInstances() { static int instances = 0; return ++instances; } diff --git a/wpimath/src/main/native/cpp/controller/proto/ArmFeedforwardProto.cpp b/wpimath/src/main/native/cpp/controller/proto/ArmFeedforwardProto.cpp index 296ffb58a6..6cb9d1a45d 100644 --- a/wpimath/src/main/native/cpp/controller/proto/ArmFeedforwardProto.cpp +++ b/wpimath/src/main/native/cpp/controller/proto/ArmFeedforwardProto.cpp @@ -8,23 +8,23 @@ #include "wpimath/protobuf/controller.npb.h" -std::optional wpi::Protobuf::Unpack( +std::optional wpi::util::Protobuf::Unpack( InputStream& stream) { wpi_proto_ProtobufArmFeedforward msg; if (!stream.Decode(msg)) { return {}; } - return frc::ArmFeedforward{ - units::volt_t{msg.ks}, - units::volt_t{msg.kg}, - units::unit_t{msg.kv}, - units::unit_t{msg.ka}, + return wpi::math::ArmFeedforward{ + wpi::units::volt_t{msg.ks}, + wpi::units::volt_t{msg.kg}, + wpi::units::unit_t{msg.kv}, + wpi::units::unit_t{msg.ka}, }; } -bool wpi::Protobuf::Pack( - OutputStream& stream, const frc::ArmFeedforward& value) { +bool wpi::util::Protobuf::Pack( + OutputStream& stream, const wpi::math::ArmFeedforward& value) { wpi_proto_ProtobufArmFeedforward msg{ .ks = value.GetKs().value(), .kg = value.GetKg().value(), diff --git a/wpimath/src/main/native/cpp/controller/proto/DifferentialDriveFeedforwardProto.cpp b/wpimath/src/main/native/cpp/controller/proto/DifferentialDriveFeedforwardProto.cpp index 63163c8abb..83c014b785 100644 --- a/wpimath/src/main/native/cpp/controller/proto/DifferentialDriveFeedforwardProto.cpp +++ b/wpimath/src/main/native/cpp/controller/proto/DifferentialDriveFeedforwardProto.cpp @@ -6,14 +6,14 @@ #include "wpimath/protobuf/controller.npb.h" -std::optional -wpi::Protobuf::Unpack(InputStream& stream) { +std::optional +wpi::util::Protobuf::Unpack(InputStream& stream) { wpi_proto_ProtobufDifferentialDriveFeedforward msg; if (!stream.Decode(msg)) { return {}; } - return frc::DifferentialDriveFeedforward{ + return wpi::math::DifferentialDriveFeedforward{ decltype(1_V / 1_mps){msg.kv_linear}, decltype(1_V / 1_mps_sq){msg.ka_linear}, decltype(1_V / 1_mps){msg.kv_angular}, @@ -21,8 +21,8 @@ wpi::Protobuf::Unpack(InputStream& stream) { }; } -bool wpi::Protobuf::Pack( - OutputStream& stream, const frc::DifferentialDriveFeedforward& value) { +bool wpi::util::Protobuf::Pack( + OutputStream& stream, const wpi::math::DifferentialDriveFeedforward& value) { wpi_proto_ProtobufDifferentialDriveFeedforward msg{ .kv_linear = value.m_kVLinear.value(), .ka_linear = value.m_kALinear.value(), diff --git a/wpimath/src/main/native/cpp/controller/proto/DifferentialDriveWheelVoltagesProto.cpp b/wpimath/src/main/native/cpp/controller/proto/DifferentialDriveWheelVoltagesProto.cpp index 8cb488fcb0..0ac2bcd1e0 100644 --- a/wpimath/src/main/native/cpp/controller/proto/DifferentialDriveWheelVoltagesProto.cpp +++ b/wpimath/src/main/native/cpp/controller/proto/DifferentialDriveWheelVoltagesProto.cpp @@ -8,21 +8,21 @@ #include "wpimath/protobuf/controller.npb.h" -std::optional wpi::Protobuf< - frc::DifferentialDriveWheelVoltages>::Unpack(InputStream& stream) { +std::optional wpi::util::Protobuf< + wpi::math::DifferentialDriveWheelVoltages>::Unpack(InputStream& stream) { wpi_proto_ProtobufDifferentialDriveWheelVoltages msg; if (!stream.Decode(msg)) { return {}; } - return frc::DifferentialDriveWheelVoltages{ - units::volt_t{msg.left}, - units::volt_t{msg.right}, + return wpi::math::DifferentialDriveWheelVoltages{ + wpi::units::volt_t{msg.left}, + wpi::units::volt_t{msg.right}, }; } -bool wpi::Protobuf::Pack( - OutputStream& stream, const frc::DifferentialDriveWheelVoltages& value) { +bool wpi::util::Protobuf::Pack( + OutputStream& stream, const wpi::math::DifferentialDriveWheelVoltages& value) { wpi_proto_ProtobufDifferentialDriveWheelVoltages msg{ .left = value.left.value(), .right = value.right.value(), diff --git a/wpimath/src/main/native/cpp/controller/proto/ElevatorFeedforwardProto.cpp b/wpimath/src/main/native/cpp/controller/proto/ElevatorFeedforwardProto.cpp index 505929fb7d..74a1919cbe 100644 --- a/wpimath/src/main/native/cpp/controller/proto/ElevatorFeedforwardProto.cpp +++ b/wpimath/src/main/native/cpp/controller/proto/ElevatorFeedforwardProto.cpp @@ -8,23 +8,23 @@ #include "wpimath/protobuf/controller.npb.h" -std::optional -wpi::Protobuf::Unpack(InputStream& stream) { +std::optional +wpi::util::Protobuf::Unpack(InputStream& stream) { wpi_proto_ProtobufElevatorFeedforward msg; if (!stream.Decode(msg)) { return {}; } - return frc::ElevatorFeedforward{ - units::volt_t{msg.ks}, - units::volt_t{msg.kg}, - units::unit_t{msg.kv}, - units::unit_t{msg.ka}, + return wpi::math::ElevatorFeedforward{ + wpi::units::volt_t{msg.ks}, + wpi::units::volt_t{msg.kg}, + wpi::units::unit_t{msg.kv}, + wpi::units::unit_t{msg.ka}, }; } -bool wpi::Protobuf::Pack( - OutputStream& stream, const frc::ElevatorFeedforward& value) { +bool wpi::util::Protobuf::Pack( + OutputStream& stream, const wpi::math::ElevatorFeedforward& value) { wpi_proto_ProtobufElevatorFeedforward msg{ .ks = value.GetKs().value(), .kg = value.GetKg().value(), diff --git a/wpimath/src/main/native/cpp/controller/struct/ArmFeedforwardStruct.cpp b/wpimath/src/main/native/cpp/controller/struct/ArmFeedforwardStruct.cpp index a26abb4818..5d7cbe080f 100644 --- a/wpimath/src/main/native/cpp/controller/struct/ArmFeedforwardStruct.cpp +++ b/wpimath/src/main/native/cpp/controller/struct/ArmFeedforwardStruct.cpp @@ -11,23 +11,23 @@ constexpr size_t kKvOff = kKgOff + 8; constexpr size_t kKaOff = kKvOff + 8; } // namespace -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; -frc::ArmFeedforward StructType::Unpack(std::span data) { - return frc::ArmFeedforward{ - units::volt_t{wpi::UnpackStruct(data)}, - units::volt_t{wpi::UnpackStruct(data)}, - units::unit_t{ - wpi::UnpackStruct(data)}, - units::unit_t{ - wpi::UnpackStruct(data)}, +wpi::math::ArmFeedforward StructType::Unpack(std::span data) { + return wpi::math::ArmFeedforward{ + wpi::units::volt_t{wpi::util::UnpackStruct(data)}, + wpi::units::volt_t{wpi::util::UnpackStruct(data)}, + wpi::units::unit_t{ + wpi::util::UnpackStruct(data)}, + wpi::units::unit_t{ + wpi::util::UnpackStruct(data)}, }; } void StructType::Pack(std::span data, - const frc::ArmFeedforward& value) { - wpi::PackStruct(data, value.GetKs().value()); - wpi::PackStruct(data, value.GetKg().value()); - wpi::PackStruct(data, value.GetKv().value()); - wpi::PackStruct(data, value.GetKa().value()); + const wpi::math::ArmFeedforward& value) { + wpi::util::PackStruct(data, value.GetKs().value()); + wpi::util::PackStruct(data, value.GetKg().value()); + wpi::util::PackStruct(data, value.GetKv().value()); + wpi::util::PackStruct(data, value.GetKa().value()); } diff --git a/wpimath/src/main/native/cpp/controller/struct/DifferentialDriveFeedforwardStruct.cpp b/wpimath/src/main/native/cpp/controller/struct/DifferentialDriveFeedforwardStruct.cpp index 13872eca8b..db25e96ba9 100644 --- a/wpimath/src/main/native/cpp/controller/struct/DifferentialDriveFeedforwardStruct.cpp +++ b/wpimath/src/main/native/cpp/controller/struct/DifferentialDriveFeedforwardStruct.cpp @@ -11,19 +11,19 @@ constexpr size_t kKvAngularOff = kKaLinearOff + 8; constexpr size_t kKaAngularOff = kKvAngularOff + 8; } // namespace -frc::DifferentialDriveFeedforward wpi::Struct< - frc::DifferentialDriveFeedforward>::Unpack(std::span data) { +wpi::math::DifferentialDriveFeedforward wpi::util::Struct< + wpi::math::DifferentialDriveFeedforward>::Unpack(std::span data) { return { - decltype(1_V / 1_mps){wpi::UnpackStruct(data)}, - decltype(1_V / 1_mps_sq){wpi::UnpackStruct(data)}, - decltype(1_V / 1_mps){wpi::UnpackStruct(data)}, - decltype(1_V / 1_mps_sq){wpi::UnpackStruct(data)}}; + decltype(1_V / 1_mps){wpi::util::UnpackStruct(data)}, + decltype(1_V / 1_mps_sq){wpi::util::UnpackStruct(data)}, + decltype(1_V / 1_mps){wpi::util::UnpackStruct(data)}, + decltype(1_V / 1_mps_sq){wpi::util::UnpackStruct(data)}}; } -void wpi::Struct::Pack( - std::span data, const frc::DifferentialDriveFeedforward& value) { - wpi::PackStruct(data, value.m_kVLinear.value()); - wpi::PackStruct(data, value.m_kALinear.value()); - wpi::PackStruct(data, value.m_kVAngular.value()); - wpi::PackStruct(data, value.m_kAAngular.value()); +void wpi::util::Struct::Pack( + std::span data, const wpi::math::DifferentialDriveFeedforward& value) { + wpi::util::PackStruct(data, value.m_kVLinear.value()); + wpi::util::PackStruct(data, value.m_kALinear.value()); + wpi::util::PackStruct(data, value.m_kVAngular.value()); + wpi::util::PackStruct(data, value.m_kAAngular.value()); } diff --git a/wpimath/src/main/native/cpp/controller/struct/DifferentialDriveWheelVoltagesStruct.cpp b/wpimath/src/main/native/cpp/controller/struct/DifferentialDriveWheelVoltagesStruct.cpp index e56a7278ca..364575a77f 100644 --- a/wpimath/src/main/native/cpp/controller/struct/DifferentialDriveWheelVoltagesStruct.cpp +++ b/wpimath/src/main/native/cpp/controller/struct/DifferentialDriveWheelVoltagesStruct.cpp @@ -9,18 +9,18 @@ constexpr size_t kLeftOff = 0; constexpr size_t kRightOff = kLeftOff + 8; } // namespace -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; -frc::DifferentialDriveWheelVoltages StructType::Unpack( +wpi::math::DifferentialDriveWheelVoltages StructType::Unpack( std::span data) { - return frc::DifferentialDriveWheelVoltages{ - units::volt_t{wpi::UnpackStruct(data)}, - units::volt_t{wpi::UnpackStruct(data)}, + return wpi::math::DifferentialDriveWheelVoltages{ + wpi::units::volt_t{wpi::util::UnpackStruct(data)}, + wpi::units::volt_t{wpi::util::UnpackStruct(data)}, }; } void StructType::Pack(std::span data, - const frc::DifferentialDriveWheelVoltages& value) { - wpi::PackStruct(data, value.left.value()); - wpi::PackStruct(data, value.right.value()); + const wpi::math::DifferentialDriveWheelVoltages& value) { + wpi::util::PackStruct(data, value.left.value()); + wpi::util::PackStruct(data, value.right.value()); } diff --git a/wpimath/src/main/native/cpp/controller/struct/ElevatorFeedforwardStruct.cpp b/wpimath/src/main/native/cpp/controller/struct/ElevatorFeedforwardStruct.cpp index ca761b84da..5d39451843 100644 --- a/wpimath/src/main/native/cpp/controller/struct/ElevatorFeedforwardStruct.cpp +++ b/wpimath/src/main/native/cpp/controller/struct/ElevatorFeedforwardStruct.cpp @@ -11,23 +11,23 @@ constexpr size_t kKvOff = kKgOff + 8; constexpr size_t kKaOff = kKvOff + 8; } // namespace -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; -frc::ElevatorFeedforward StructType::Unpack(std::span data) { - return frc::ElevatorFeedforward{ - units::volt_t{wpi::UnpackStruct(data)}, - units::volt_t{wpi::UnpackStruct(data)}, - units::unit_t{ - wpi::UnpackStruct(data)}, - units::unit_t{ - wpi::UnpackStruct(data)}, +wpi::math::ElevatorFeedforward StructType::Unpack(std::span data) { + return wpi::math::ElevatorFeedforward{ + wpi::units::volt_t{wpi::util::UnpackStruct(data)}, + wpi::units::volt_t{wpi::util::UnpackStruct(data)}, + wpi::units::unit_t{ + wpi::util::UnpackStruct(data)}, + wpi::units::unit_t{ + wpi::util::UnpackStruct(data)}, }; } void StructType::Pack(std::span data, - const frc::ElevatorFeedforward& value) { - wpi::PackStruct(data, value.GetKs().value()); - wpi::PackStruct(data, value.GetKg().value()); - wpi::PackStruct(data, value.GetKv().value()); - wpi::PackStruct(data, value.GetKa().value()); + const wpi::math::ElevatorFeedforward& value) { + wpi::util::PackStruct(data, value.GetKs().value()); + wpi::util::PackStruct(data, value.GetKg().value()); + wpi::util::PackStruct(data, value.GetKv().value()); + wpi::util::PackStruct(data, value.GetKa().value()); } diff --git a/wpimath/src/main/native/cpp/estimator/DifferentialDrivePoseEstimator.cpp b/wpimath/src/main/native/cpp/estimator/DifferentialDrivePoseEstimator.cpp index f5f91f43e8..53b1e7e76f 100644 --- a/wpimath/src/main/native/cpp/estimator/DifferentialDrivePoseEstimator.cpp +++ b/wpimath/src/main/native/cpp/estimator/DifferentialDrivePoseEstimator.cpp @@ -6,11 +6,11 @@ #include -using namespace frc; +using namespace wpi::math; DifferentialDrivePoseEstimator::DifferentialDrivePoseEstimator( DifferentialDriveKinematics& kinematics, const Rotation2d& gyroAngle, - units::meter_t leftDistance, units::meter_t rightDistance, + wpi::units::meter_t leftDistance, wpi::units::meter_t rightDistance, const Pose2d& initialPose) : DifferentialDrivePoseEstimator{ kinematics, gyroAngle, leftDistance, rightDistance, @@ -18,9 +18,9 @@ DifferentialDrivePoseEstimator::DifferentialDrivePoseEstimator( DifferentialDrivePoseEstimator::DifferentialDrivePoseEstimator( DifferentialDriveKinematics& kinematics, const Rotation2d& gyroAngle, - units::meter_t leftDistance, units::meter_t rightDistance, - const Pose2d& initialPose, const wpi::array& stateStdDevs, - const wpi::array& visionMeasurementStdDevs) + wpi::units::meter_t leftDistance, wpi::units::meter_t rightDistance, + const Pose2d& initialPose, const wpi::util::array& stateStdDevs, + const wpi::util::array& visionMeasurementStdDevs) : PoseEstimator(kinematics, m_odometryImpl, stateStdDevs, visionMeasurementStdDevs), m_odometryImpl{gyroAngle, leftDistance, rightDistance, initialPose} { diff --git a/wpimath/src/main/native/cpp/estimator/DifferentialDrivePoseEstimator3d.cpp b/wpimath/src/main/native/cpp/estimator/DifferentialDrivePoseEstimator3d.cpp index 526e38fb6e..df353666fa 100644 --- a/wpimath/src/main/native/cpp/estimator/DifferentialDrivePoseEstimator3d.cpp +++ b/wpimath/src/main/native/cpp/estimator/DifferentialDrivePoseEstimator3d.cpp @@ -4,11 +4,11 @@ #include "wpi/math/estimator/DifferentialDrivePoseEstimator3d.hpp" -using namespace frc; +using namespace wpi::math; DifferentialDrivePoseEstimator3d::DifferentialDrivePoseEstimator3d( DifferentialDriveKinematics& kinematics, const Rotation3d& gyroAngle, - units::meter_t leftDistance, units::meter_t rightDistance, + wpi::units::meter_t leftDistance, wpi::units::meter_t rightDistance, const Pose3d& initialPose) : DifferentialDrivePoseEstimator3d{ kinematics, gyroAngle, leftDistance, @@ -17,9 +17,9 @@ DifferentialDrivePoseEstimator3d::DifferentialDrivePoseEstimator3d( DifferentialDrivePoseEstimator3d::DifferentialDrivePoseEstimator3d( DifferentialDriveKinematics& kinematics, const Rotation3d& gyroAngle, - units::meter_t leftDistance, units::meter_t rightDistance, - const Pose3d& initialPose, const wpi::array& stateStdDevs, - const wpi::array& visionMeasurementStdDevs) + wpi::units::meter_t leftDistance, wpi::units::meter_t rightDistance, + const Pose3d& initialPose, const wpi::util::array& stateStdDevs, + const wpi::util::array& visionMeasurementStdDevs) : PoseEstimator3d(kinematics, m_odometryImpl, stateStdDevs, visionMeasurementStdDevs), m_odometryImpl{gyroAngle, leftDistance, rightDistance, initialPose} { diff --git a/wpimath/src/main/native/cpp/estimator/KalmanFilter.cpp b/wpimath/src/main/native/cpp/estimator/KalmanFilter.cpp index fa2f8b5f05..9dac81cd55 100644 --- a/wpimath/src/main/native/cpp/estimator/KalmanFilter.cpp +++ b/wpimath/src/main/native/cpp/estimator/KalmanFilter.cpp @@ -4,9 +4,9 @@ #include "wpi/math/estimator/KalmanFilter.hpp" -namespace frc { +namespace wpi::math { template class EXPORT_TEMPLATE_DEFINE(WPILIB_DLLEXPORT) KalmanFilter<1, 1, 1>; template class EXPORT_TEMPLATE_DEFINE(WPILIB_DLLEXPORT) KalmanFilter<2, 1, 1>; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/cpp/estimator/MecanumDrivePoseEstimator.cpp b/wpimath/src/main/native/cpp/estimator/MecanumDrivePoseEstimator.cpp index 64a51f853d..8fc47e94bd 100644 --- a/wpimath/src/main/native/cpp/estimator/MecanumDrivePoseEstimator.cpp +++ b/wpimath/src/main/native/cpp/estimator/MecanumDrivePoseEstimator.cpp @@ -9,20 +9,20 @@ #include "wpi/math/util/StateSpaceUtil.hpp" #include "wpi/util/timestamp.h" -using namespace frc; +using namespace wpi::math; -frc::MecanumDrivePoseEstimator::MecanumDrivePoseEstimator( +wpi::math::MecanumDrivePoseEstimator::MecanumDrivePoseEstimator( MecanumDriveKinematics& kinematics, const Rotation2d& gyroAngle, const MecanumDriveWheelPositions& wheelPositions, const Pose2d& initialPose) : MecanumDrivePoseEstimator{kinematics, gyroAngle, wheelPositions, initialPose, {0.1, 0.1, 0.1}, {0.45, 0.45, 0.45}} {} -frc::MecanumDrivePoseEstimator::MecanumDrivePoseEstimator( +wpi::math::MecanumDrivePoseEstimator::MecanumDrivePoseEstimator( MecanumDriveKinematics& kinematics, const Rotation2d& gyroAngle, const MecanumDriveWheelPositions& wheelPositions, const Pose2d& initialPose, - const wpi::array& stateStdDevs, - const wpi::array& visionMeasurementStdDevs) + const wpi::util::array& stateStdDevs, + const wpi::util::array& visionMeasurementStdDevs) : PoseEstimator(kinematics, m_odometryImpl, stateStdDevs, visionMeasurementStdDevs), m_odometryImpl(kinematics, gyroAngle, wheelPositions, initialPose) { diff --git a/wpimath/src/main/native/cpp/estimator/MecanumDrivePoseEstimator3d.cpp b/wpimath/src/main/native/cpp/estimator/MecanumDrivePoseEstimator3d.cpp index 3b5a9dafc5..763ceca26b 100644 --- a/wpimath/src/main/native/cpp/estimator/MecanumDrivePoseEstimator3d.cpp +++ b/wpimath/src/main/native/cpp/estimator/MecanumDrivePoseEstimator3d.cpp @@ -9,9 +9,9 @@ #include "wpi/math/util/StateSpaceUtil.hpp" #include "wpi/util/timestamp.h" -using namespace frc; +using namespace wpi::math; -frc::MecanumDrivePoseEstimator3d::MecanumDrivePoseEstimator3d( +wpi::math::MecanumDrivePoseEstimator3d::MecanumDrivePoseEstimator3d( MecanumDriveKinematics& kinematics, const Rotation3d& gyroAngle, const MecanumDriveWheelPositions& wheelPositions, const Pose3d& initialPose) : MecanumDrivePoseEstimator3d{ @@ -19,11 +19,11 @@ frc::MecanumDrivePoseEstimator3d::MecanumDrivePoseEstimator3d( wheelPositions, initialPose, {0.1, 0.1, 0.1, 0.1}, {0.45, 0.45, 0.45, 0.45}} {} -frc::MecanumDrivePoseEstimator3d::MecanumDrivePoseEstimator3d( +wpi::math::MecanumDrivePoseEstimator3d::MecanumDrivePoseEstimator3d( MecanumDriveKinematics& kinematics, const Rotation3d& gyroAngle, const MecanumDriveWheelPositions& wheelPositions, const Pose3d& initialPose, - const wpi::array& stateStdDevs, - const wpi::array& visionMeasurementStdDevs) + const wpi::util::array& stateStdDevs, + const wpi::util::array& visionMeasurementStdDevs) : PoseEstimator3d(kinematics, m_odometryImpl, stateStdDevs, visionMeasurementStdDevs), m_odometryImpl(kinematics, gyroAngle, wheelPositions, initialPose) { diff --git a/wpimath/src/main/native/cpp/estimator/MerweUKF.cpp b/wpimath/src/main/native/cpp/estimator/MerweUKF.cpp index f4876f72a1..1230d1af92 100644 --- a/wpimath/src/main/native/cpp/estimator/MerweUKF.cpp +++ b/wpimath/src/main/native/cpp/estimator/MerweUKF.cpp @@ -4,11 +4,11 @@ #include "wpi/math/estimator/MerweUKF.hpp" -namespace frc { +namespace wpi::math { template class EXPORT_TEMPLATE_DEFINE(WPILIB_DLLEXPORT) UnscentedKalmanFilter<3, 3, 1, MerweScaledSigmaPoints<3>>; template class EXPORT_TEMPLATE_DEFINE(WPILIB_DLLEXPORT) UnscentedKalmanFilter<5, 3, 3, MerweScaledSigmaPoints<5>>; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/cpp/estimator/S3UKF.cpp b/wpimath/src/main/native/cpp/estimator/S3UKF.cpp index 5b6185f343..8966b6de4e 100644 --- a/wpimath/src/main/native/cpp/estimator/S3UKF.cpp +++ b/wpimath/src/main/native/cpp/estimator/S3UKF.cpp @@ -4,11 +4,11 @@ #include "wpi/math/estimator/S3UKF.hpp" -namespace frc { +namespace wpi::math { template class EXPORT_TEMPLATE_DEFINE(WPILIB_DLLEXPORT) UnscentedKalmanFilter<3, 3, 1, S3SigmaPoints<3>>; template class EXPORT_TEMPLATE_DEFINE(WPILIB_DLLEXPORT) UnscentedKalmanFilter<5, 3, 3, S3SigmaPoints<5>>; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/cpp/estimator/SteadyStateKalmanFilter.cpp b/wpimath/src/main/native/cpp/estimator/SteadyStateKalmanFilter.cpp index bcff8c1b5c..8561d0d572 100644 --- a/wpimath/src/main/native/cpp/estimator/SteadyStateKalmanFilter.cpp +++ b/wpimath/src/main/native/cpp/estimator/SteadyStateKalmanFilter.cpp @@ -4,11 +4,11 @@ #include "wpi/math/estimator/SteadyStateKalmanFilter.hpp" -namespace frc { +namespace wpi::math { template class EXPORT_TEMPLATE_DEFINE(WPILIB_DLLEXPORT) SteadyStateKalmanFilter<1, 1, 1>; template class EXPORT_TEMPLATE_DEFINE(WPILIB_DLLEXPORT) SteadyStateKalmanFilter<2, 1, 1>; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/cpp/estimator/SwerveDrivePoseEstimator.cpp b/wpimath/src/main/native/cpp/estimator/SwerveDrivePoseEstimator.cpp index 8d79095272..c7ce436f8b 100644 --- a/wpimath/src/main/native/cpp/estimator/SwerveDrivePoseEstimator.cpp +++ b/wpimath/src/main/native/cpp/estimator/SwerveDrivePoseEstimator.cpp @@ -4,9 +4,9 @@ #include "wpi/math/estimator/SwerveDrivePoseEstimator.hpp" -namespace frc { +namespace wpi::math { template class EXPORT_TEMPLATE_DEFINE(WPILIB_DLLEXPORT) SwerveDrivePoseEstimator<4>; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/cpp/estimator/SwerveDrivePoseEstimator3d.cpp b/wpimath/src/main/native/cpp/estimator/SwerveDrivePoseEstimator3d.cpp index 1e446f824c..575ff93f70 100644 --- a/wpimath/src/main/native/cpp/estimator/SwerveDrivePoseEstimator3d.cpp +++ b/wpimath/src/main/native/cpp/estimator/SwerveDrivePoseEstimator3d.cpp @@ -4,9 +4,9 @@ #include "wpi/math/estimator/SwerveDrivePoseEstimator3d.hpp" -namespace frc { +namespace wpi::math { template class EXPORT_TEMPLATE_DEFINE(WPILIB_DLLEXPORT) SwerveDrivePoseEstimator3d<4>; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/cpp/filter/Debouncer.cpp b/wpimath/src/main/native/cpp/filter/Debouncer.cpp index 3e4f4c9038..afdde6a115 100644 --- a/wpimath/src/main/native/cpp/filter/Debouncer.cpp +++ b/wpimath/src/main/native/cpp/filter/Debouncer.cpp @@ -6,9 +6,9 @@ #include "wpi/math/util/MathShared.hpp" -using namespace frc; +using namespace wpi::math; -Debouncer::Debouncer(units::second_t debounceTime, DebounceType type) +Debouncer::Debouncer(wpi::units::second_t debounceTime, DebounceType type) : m_debounceTime(debounceTime), m_debounceType(type) { m_baseline = m_debounceType == DebounceType::kFalling; ResetTimer(); diff --git a/wpimath/src/main/native/cpp/geometry/Ellipse2d.cpp b/wpimath/src/main/native/cpp/geometry/Ellipse2d.cpp index e3b9f42529..3cd00ac852 100644 --- a/wpimath/src/main/native/cpp/geometry/Ellipse2d.cpp +++ b/wpimath/src/main/native/cpp/geometry/Ellipse2d.cpp @@ -6,7 +6,7 @@ #include -using namespace frc; +using namespace wpi::math; Translation2d Ellipse2d::Nearest(const Translation2d& point) const { // Check if already in ellipse @@ -41,8 +41,8 @@ Translation2d Ellipse2d::Nearest(const Translation2d& point) const { problem.solve(); - rotPoint = frc::Translation2d{units::meter_t{x.value()}, - units::meter_t{y.value()}}; + rotPoint = wpi::math::Translation2d{wpi::units::meter_t{x.value()}, + wpi::units::meter_t{y.value()}}; } // Undo rotation diff --git a/wpimath/src/main/native/cpp/geometry/Pose2d.cpp b/wpimath/src/main/native/cpp/geometry/Pose2d.cpp index 924a6449d6..b3e2449639 100644 --- a/wpimath/src/main/native/cpp/geometry/Pose2d.cpp +++ b/wpimath/src/main/native/cpp/geometry/Pose2d.cpp @@ -6,12 +6,12 @@ #include "wpi/util/json.hpp" -void frc::to_json(wpi::json& json, const Pose2d& pose) { - json = wpi::json{{"translation", pose.Translation()}, +void wpi::math::to_json(wpi::util::json& json, const Pose2d& pose) { + json = wpi::util::json{{"translation", pose.Translation()}, {"rotation", pose.Rotation()}}; } -void frc::from_json(const wpi::json& json, Pose2d& pose) { +void wpi::math::from_json(const wpi::util::json& json, Pose2d& pose) { pose = Pose2d{json.at("translation").get(), json.at("rotation").get()}; } diff --git a/wpimath/src/main/native/cpp/geometry/Pose3d.cpp b/wpimath/src/main/native/cpp/geometry/Pose3d.cpp index 22cfd3b266..6b41b0730c 100644 --- a/wpimath/src/main/native/cpp/geometry/Pose3d.cpp +++ b/wpimath/src/main/native/cpp/geometry/Pose3d.cpp @@ -6,12 +6,12 @@ #include "wpi/util/json.hpp" -void frc::to_json(wpi::json& json, const Pose3d& pose) { - json = wpi::json{{"translation", pose.Translation()}, +void wpi::math::to_json(wpi::util::json& json, const Pose3d& pose) { + json = wpi::util::json{{"translation", pose.Translation()}, {"rotation", pose.Rotation()}}; } -void frc::from_json(const wpi::json& json, Pose3d& pose) { +void wpi::math::from_json(const wpi::util::json& json, Pose3d& pose) { pose = Pose3d{json.at("translation").get(), json.at("rotation").get()}; } diff --git a/wpimath/src/main/native/cpp/geometry/Quaternion.cpp b/wpimath/src/main/native/cpp/geometry/Quaternion.cpp index 91873908aa..e4738dded6 100644 --- a/wpimath/src/main/native/cpp/geometry/Quaternion.cpp +++ b/wpimath/src/main/native/cpp/geometry/Quaternion.cpp @@ -6,14 +6,14 @@ #include "wpi/util/json.hpp" -void frc::to_json(wpi::json& json, const Quaternion& quaternion) { - json = wpi::json{{"W", quaternion.W()}, +void wpi::math::to_json(wpi::util::json& json, const Quaternion& quaternion) { + json = wpi::util::json{{"W", quaternion.W()}, {"X", quaternion.X()}, {"Y", quaternion.Y()}, {"Z", quaternion.Z()}}; } -void frc::from_json(const wpi::json& json, Quaternion& quaternion) { +void wpi::math::from_json(const wpi::util::json& json, Quaternion& quaternion) { quaternion = Quaternion{json.at("W").get(), json.at("X").get(), json.at("Y").get(), json.at("Z").get()}; diff --git a/wpimath/src/main/native/cpp/geometry/Rotation2d.cpp b/wpimath/src/main/native/cpp/geometry/Rotation2d.cpp index b139bd0063..3c3b195def 100644 --- a/wpimath/src/main/native/cpp/geometry/Rotation2d.cpp +++ b/wpimath/src/main/native/cpp/geometry/Rotation2d.cpp @@ -6,10 +6,10 @@ #include "wpi/util/json.hpp" -void frc::to_json(wpi::json& json, const Rotation2d& rotation) { - json = wpi::json{{"radians", rotation.Radians().value()}}; +void wpi::math::to_json(wpi::util::json& json, const Rotation2d& rotation) { + json = wpi::util::json{{"radians", rotation.Radians().value()}}; } -void frc::from_json(const wpi::json& json, Rotation2d& rotation) { - rotation = Rotation2d{units::radian_t{json.at("radians").get()}}; +void wpi::math::from_json(const wpi::util::json& json, Rotation2d& rotation) { + rotation = Rotation2d{wpi::units::radian_t{json.at("radians").get()}}; } diff --git a/wpimath/src/main/native/cpp/geometry/Rotation3d.cpp b/wpimath/src/main/native/cpp/geometry/Rotation3d.cpp index 01ae1c88f3..5b81b54666 100644 --- a/wpimath/src/main/native/cpp/geometry/Rotation3d.cpp +++ b/wpimath/src/main/native/cpp/geometry/Rotation3d.cpp @@ -6,10 +6,10 @@ #include "wpi/util/json.hpp" -void frc::to_json(wpi::json& json, const Rotation3d& rotation) { - json = wpi::json{{"quaternion", rotation.GetQuaternion()}}; +void wpi::math::to_json(wpi::util::json& json, const Rotation3d& rotation) { + json = wpi::util::json{{"quaternion", rotation.GetQuaternion()}}; } -void frc::from_json(const wpi::json& json, Rotation3d& rotation) { +void wpi::math::from_json(const wpi::util::json& json, Rotation3d& rotation) { rotation = Rotation3d{json.at("quaternion").get()}; } diff --git a/wpimath/src/main/native/cpp/geometry/Translation2d.cpp b/wpimath/src/main/native/cpp/geometry/Translation2d.cpp index 93ec5b7418..0a85c360ce 100644 --- a/wpimath/src/main/native/cpp/geometry/Translation2d.cpp +++ b/wpimath/src/main/native/cpp/geometry/Translation2d.cpp @@ -6,12 +6,12 @@ #include "wpi/util/json.hpp" -void frc::to_json(wpi::json& json, const Translation2d& translation) { +void wpi::math::to_json(wpi::util::json& json, const Translation2d& translation) { json = - wpi::json{{"x", translation.X().value()}, {"y", translation.Y().value()}}; + wpi::util::json{{"x", translation.X().value()}, {"y", translation.Y().value()}}; } -void frc::from_json(const wpi::json& json, Translation2d& translation) { - translation = Translation2d{units::meter_t{json.at("x").get()}, - units::meter_t{json.at("y").get()}}; +void wpi::math::from_json(const wpi::util::json& json, Translation2d& translation) { + translation = Translation2d{wpi::units::meter_t{json.at("x").get()}, + wpi::units::meter_t{json.at("y").get()}}; } diff --git a/wpimath/src/main/native/cpp/geometry/Translation3d.cpp b/wpimath/src/main/native/cpp/geometry/Translation3d.cpp index 0216cf1193..df4c81a932 100644 --- a/wpimath/src/main/native/cpp/geometry/Translation3d.cpp +++ b/wpimath/src/main/native/cpp/geometry/Translation3d.cpp @@ -6,14 +6,14 @@ #include "wpi/util/json.hpp" -void frc::to_json(wpi::json& json, const Translation3d& translation) { - json = wpi::json{{"x", translation.X().value()}, +void wpi::math::to_json(wpi::util::json& json, const Translation3d& translation) { + json = wpi::util::json{{"x", translation.X().value()}, {"y", translation.Y().value()}, {"z", translation.Z().value()}}; } -void frc::from_json(const wpi::json& json, Translation3d& translation) { - translation = Translation3d{units::meter_t{json.at("x").get()}, - units::meter_t{json.at("y").get()}, - units::meter_t{json.at("z").get()}}; +void wpi::math::from_json(const wpi::util::json& json, Translation3d& translation) { + translation = Translation3d{wpi::units::meter_t{json.at("x").get()}, + wpi::units::meter_t{json.at("y").get()}, + wpi::units::meter_t{json.at("z").get()}}; } diff --git a/wpimath/src/main/native/cpp/geometry/proto/Ellipse2dProto.cpp b/wpimath/src/main/native/cpp/geometry/proto/Ellipse2dProto.cpp index 2431d4e616..ce4510ec95 100644 --- a/wpimath/src/main/native/cpp/geometry/proto/Ellipse2dProto.cpp +++ b/wpimath/src/main/native/cpp/geometry/proto/Ellipse2dProto.cpp @@ -7,9 +7,9 @@ #include "wpi/util/protobuf/ProtobufCallbacks.hpp" #include "wpimath/protobuf/geometry2d.npb.h" -std::optional wpi::Protobuf::Unpack( +std::optional wpi::util::Protobuf::Unpack( InputStream& stream) { - wpi::UnpackCallback pose; + wpi::util::UnpackCallback pose; wpi_proto_ProtobufEllipse2d msg{ .center = pose.Callback(), .xSemiAxis = 0, @@ -25,16 +25,16 @@ std::optional wpi::Protobuf::Unpack( return {}; } - return frc::Ellipse2d{ + return wpi::math::Ellipse2d{ ipose[0], - units::meter_t{msg.xSemiAxis}, - units::meter_t{msg.ySemiAxis}, + wpi::units::meter_t{msg.xSemiAxis}, + wpi::units::meter_t{msg.ySemiAxis}, }; } -bool wpi::Protobuf::Pack(OutputStream& stream, - const frc::Ellipse2d& value) { - wpi::PackCallback pose{&value.Center()}; +bool wpi::util::Protobuf::Pack(OutputStream& stream, + const wpi::math::Ellipse2d& value) { + wpi::util::PackCallback pose{&value.Center()}; wpi_proto_ProtobufEllipse2d msg{ .center = pose.Callback(), .xSemiAxis = value.XSemiAxis().value(), diff --git a/wpimath/src/main/native/cpp/geometry/proto/Pose2dProto.cpp b/wpimath/src/main/native/cpp/geometry/proto/Pose2dProto.cpp index ab1c9f0ec3..4b0bcf8440 100644 --- a/wpimath/src/main/native/cpp/geometry/proto/Pose2dProto.cpp +++ b/wpimath/src/main/native/cpp/geometry/proto/Pose2dProto.cpp @@ -7,10 +7,10 @@ #include "wpi/util/protobuf/ProtobufCallbacks.hpp" #include "wpimath/protobuf/geometry2d.npb.h" -std::optional wpi::Protobuf::Unpack( +std::optional wpi::util::Protobuf::Unpack( InputStream& stream) { - wpi::UnpackCallback tsln; - wpi::UnpackCallback rot; + wpi::util::UnpackCallback tsln; + wpi::util::UnpackCallback rot; wpi_proto_ProtobufPose2d msg{ .translation = tsln.Callback(), .rotation = rot.Callback(), @@ -26,16 +26,16 @@ std::optional wpi::Protobuf::Unpack( return {}; } - return frc::Pose2d{ + return wpi::math::Pose2d{ itsln[0], irot[0], }; } -bool wpi::Protobuf::Pack(OutputStream& stream, - const frc::Pose2d& value) { - wpi::PackCallback tsln{&value.Translation()}; - wpi::PackCallback rot{&value.Rotation()}; +bool wpi::util::Protobuf::Pack(OutputStream& stream, + const wpi::math::Pose2d& value) { + wpi::util::PackCallback tsln{&value.Translation()}; + wpi::util::PackCallback rot{&value.Rotation()}; wpi_proto_ProtobufPose2d msg{ .translation = tsln.Callback(), .rotation = rot.Callback(), diff --git a/wpimath/src/main/native/cpp/geometry/proto/Pose3dProto.cpp b/wpimath/src/main/native/cpp/geometry/proto/Pose3dProto.cpp index d09bf57281..1c1d61bfe1 100644 --- a/wpimath/src/main/native/cpp/geometry/proto/Pose3dProto.cpp +++ b/wpimath/src/main/native/cpp/geometry/proto/Pose3dProto.cpp @@ -9,10 +9,10 @@ #include "wpi/util/protobuf/ProtobufCallbacks.hpp" #include "wpimath/protobuf/geometry3d.npb.h" -std::optional wpi::Protobuf::Unpack( +std::optional wpi::util::Protobuf::Unpack( InputStream& stream) { - wpi::UnpackCallback tsln; - wpi::UnpackCallback rot; + wpi::util::UnpackCallback tsln; + wpi::util::UnpackCallback rot; wpi_proto_ProtobufPose3d msg{ .translation = tsln.Callback(), .rotation = rot.Callback(), @@ -28,16 +28,16 @@ std::optional wpi::Protobuf::Unpack( return {}; } - return frc::Pose3d{ + return wpi::math::Pose3d{ itsln[0], irot[0], }; } -bool wpi::Protobuf::Pack(OutputStream& stream, - const frc::Pose3d& value) { - wpi::PackCallback tsln{&value.Translation()}; - wpi::PackCallback rot{&value.Rotation()}; +bool wpi::util::Protobuf::Pack(OutputStream& stream, + const wpi::math::Pose3d& value) { + wpi::util::PackCallback tsln{&value.Translation()}; + wpi::util::PackCallback rot{&value.Rotation()}; wpi_proto_ProtobufPose3d msg{ .translation = tsln.Callback(), .rotation = rot.Callback(), diff --git a/wpimath/src/main/native/cpp/geometry/proto/QuaternionProto.cpp b/wpimath/src/main/native/cpp/geometry/proto/QuaternionProto.cpp index 6a1fd9438e..78653e0d3c 100644 --- a/wpimath/src/main/native/cpp/geometry/proto/QuaternionProto.cpp +++ b/wpimath/src/main/native/cpp/geometry/proto/QuaternionProto.cpp @@ -6,14 +6,14 @@ #include "wpimath/protobuf/geometry3d.npb.h" -std::optional wpi::Protobuf::Unpack( +std::optional wpi::util::Protobuf::Unpack( InputStream& stream) { wpi_proto_ProtobufQuaternion msg; if (!stream.Decode(msg)) { return {}; } - return frc::Quaternion{ + return wpi::math::Quaternion{ msg.w, msg.x, msg.y, @@ -21,8 +21,8 @@ std::optional wpi::Protobuf::Unpack( }; } -bool wpi::Protobuf::Pack(OutputStream& stream, - const frc::Quaternion& value) { +bool wpi::util::Protobuf::Pack(OutputStream& stream, + const wpi::math::Quaternion& value) { wpi_proto_ProtobufQuaternion msg{ .w = value.W(), .x = value.X(), diff --git a/wpimath/src/main/native/cpp/geometry/proto/Rectangle2dProto.cpp b/wpimath/src/main/native/cpp/geometry/proto/Rectangle2dProto.cpp index 1f2ecbc776..a79fe89efb 100644 --- a/wpimath/src/main/native/cpp/geometry/proto/Rectangle2dProto.cpp +++ b/wpimath/src/main/native/cpp/geometry/proto/Rectangle2dProto.cpp @@ -7,9 +7,9 @@ #include "wpi/util/protobuf/ProtobufCallbacks.hpp" #include "wpimath/protobuf/geometry2d.npb.h" -std::optional wpi::Protobuf::Unpack( +std::optional wpi::util::Protobuf::Unpack( InputStream& stream) { - wpi::UnpackCallback pose; + wpi::util::UnpackCallback pose; wpi_proto_ProtobufRectangle2d msg{ .center = pose.Callback(), .xWidth = 0, @@ -25,16 +25,16 @@ std::optional wpi::Protobuf::Unpack( return {}; } - return frc::Rectangle2d{ + return wpi::math::Rectangle2d{ ipose[0], - units::meter_t{msg.xWidth}, - units::meter_t{msg.yWidth}, + wpi::units::meter_t{msg.xWidth}, + wpi::units::meter_t{msg.yWidth}, }; } -bool wpi::Protobuf::Pack(OutputStream& stream, - const frc::Rectangle2d& value) { - wpi::PackCallback pose{&value.Center()}; +bool wpi::util::Protobuf::Pack(OutputStream& stream, + const wpi::math::Rectangle2d& value) { + wpi::util::PackCallback pose{&value.Center()}; wpi_proto_ProtobufRectangle2d msg{ .center = pose.Callback(), .xWidth = value.XWidth().value(), diff --git a/wpimath/src/main/native/cpp/geometry/proto/Rotation2dProto.cpp b/wpimath/src/main/native/cpp/geometry/proto/Rotation2dProto.cpp index 1e8d5bbf52..d78fd6acfc 100644 --- a/wpimath/src/main/native/cpp/geometry/proto/Rotation2dProto.cpp +++ b/wpimath/src/main/native/cpp/geometry/proto/Rotation2dProto.cpp @@ -6,20 +6,20 @@ #include "wpimath/protobuf/geometry2d.npb.h" -std::optional wpi::Protobuf::Unpack( +std::optional wpi::util::Protobuf::Unpack( InputStream& stream) { wpi_proto_ProtobufRotation2d msg; if (!stream.Decode(msg)) { return {}; } - return frc::Rotation2d{ - units::radian_t{msg.value}, + return wpi::math::Rotation2d{ + wpi::units::radian_t{msg.value}, }; } -bool wpi::Protobuf::Pack(OutputStream& stream, - const frc::Rotation2d& value) { +bool wpi::util::Protobuf::Pack(OutputStream& stream, + const wpi::math::Rotation2d& value) { wpi_proto_ProtobufRotation2d msg{ .value = value.Radians().value(), }; diff --git a/wpimath/src/main/native/cpp/geometry/proto/Rotation3dProto.cpp b/wpimath/src/main/native/cpp/geometry/proto/Rotation3dProto.cpp index 4a25ceca59..5945069f62 100644 --- a/wpimath/src/main/native/cpp/geometry/proto/Rotation3dProto.cpp +++ b/wpimath/src/main/native/cpp/geometry/proto/Rotation3dProto.cpp @@ -7,9 +7,9 @@ #include "wpi/util/protobuf/ProtobufCallbacks.hpp" #include "wpimath/protobuf/geometry3d.npb.h" -std::optional wpi::Protobuf::Unpack( +std::optional wpi::util::Protobuf::Unpack( InputStream& stream) { - wpi::UnpackCallback quat; + wpi::util::UnpackCallback quat; wpi_proto_ProtobufRotation3d msg{ .q = quat.Callback(), }; @@ -23,14 +23,14 @@ std::optional wpi::Protobuf::Unpack( return {}; } - return frc::Rotation3d{ + return wpi::math::Rotation3d{ iquat[0], }; } -bool wpi::Protobuf::Pack(OutputStream& stream, - const frc::Rotation3d& value) { - wpi::PackCallback quat{&value.GetQuaternion()}; +bool wpi::util::Protobuf::Pack(OutputStream& stream, + const wpi::math::Rotation3d& value) { + wpi::util::PackCallback quat{&value.GetQuaternion()}; wpi_proto_ProtobufRotation3d msg{ .q = quat.Callback(), }; diff --git a/wpimath/src/main/native/cpp/geometry/proto/Transform2dProto.cpp b/wpimath/src/main/native/cpp/geometry/proto/Transform2dProto.cpp index c19a90986a..b8414ef481 100644 --- a/wpimath/src/main/native/cpp/geometry/proto/Transform2dProto.cpp +++ b/wpimath/src/main/native/cpp/geometry/proto/Transform2dProto.cpp @@ -7,10 +7,10 @@ #include "wpi/util/protobuf/ProtobufCallbacks.hpp" #include "wpimath/protobuf/geometry2d.npb.h" -std::optional wpi::Protobuf::Unpack( +std::optional wpi::util::Protobuf::Unpack( InputStream& stream) { - wpi::UnpackCallback tsln; - wpi::UnpackCallback rot; + wpi::util::UnpackCallback tsln; + wpi::util::UnpackCallback rot; wpi_proto_ProtobufTransform2d msg{ .translation = tsln.Callback(), .rotation = rot.Callback(), @@ -26,16 +26,16 @@ std::optional wpi::Protobuf::Unpack( return {}; } - return frc::Transform2d{ + return wpi::math::Transform2d{ itsln[0], irot[0], }; } -bool wpi::Protobuf::Pack(OutputStream& stream, - const frc::Transform2d& value) { - wpi::PackCallback tsln{&value.Translation()}; - wpi::PackCallback rot{&value.Rotation()}; +bool wpi::util::Protobuf::Pack(OutputStream& stream, + const wpi::math::Transform2d& value) { + wpi::util::PackCallback tsln{&value.Translation()}; + wpi::util::PackCallback rot{&value.Rotation()}; wpi_proto_ProtobufTransform2d msg{ .translation = tsln.Callback(), .rotation = rot.Callback(), diff --git a/wpimath/src/main/native/cpp/geometry/proto/Transform3dProto.cpp b/wpimath/src/main/native/cpp/geometry/proto/Transform3dProto.cpp index 2e07e280ce..d2e10da7f2 100644 --- a/wpimath/src/main/native/cpp/geometry/proto/Transform3dProto.cpp +++ b/wpimath/src/main/native/cpp/geometry/proto/Transform3dProto.cpp @@ -7,10 +7,10 @@ #include "wpi/util/protobuf/ProtobufCallbacks.hpp" #include "wpimath/protobuf/geometry3d.npb.h" -std::optional wpi::Protobuf::Unpack( +std::optional wpi::util::Protobuf::Unpack( InputStream& stream) { - wpi::UnpackCallback tsln; - wpi::UnpackCallback rot; + wpi::util::UnpackCallback tsln; + wpi::util::UnpackCallback rot; wpi_proto_ProtobufTransform3d msg{ .translation = tsln.Callback(), .rotation = rot.Callback(), @@ -26,16 +26,16 @@ std::optional wpi::Protobuf::Unpack( return {}; } - return frc::Transform3d{ + return wpi::math::Transform3d{ itsln[0], irot[0], }; } -bool wpi::Protobuf::Pack(OutputStream& stream, - const frc::Transform3d& value) { - wpi::PackCallback tsln{&value.Translation()}; - wpi::PackCallback rot{&value.Rotation()}; +bool wpi::util::Protobuf::Pack(OutputStream& stream, + const wpi::math::Transform3d& value) { + wpi::util::PackCallback tsln{&value.Translation()}; + wpi::util::PackCallback rot{&value.Rotation()}; wpi_proto_ProtobufTransform3d msg{ .translation = tsln.Callback(), .rotation = rot.Callback(), diff --git a/wpimath/src/main/native/cpp/geometry/proto/Translation2dProto.cpp b/wpimath/src/main/native/cpp/geometry/proto/Translation2dProto.cpp index 92a3870801..6d33710dda 100644 --- a/wpimath/src/main/native/cpp/geometry/proto/Translation2dProto.cpp +++ b/wpimath/src/main/native/cpp/geometry/proto/Translation2dProto.cpp @@ -6,21 +6,21 @@ #include "wpimath/protobuf/geometry2d.npb.h" -std::optional wpi::Protobuf::Unpack( +std::optional wpi::util::Protobuf::Unpack( InputStream& stream) { wpi_proto_ProtobufTranslation2d msg; if (!stream.Decode(msg)) { return {}; } - return frc::Translation2d{ - units::meter_t{msg.x}, - units::meter_t{msg.y}, + return wpi::math::Translation2d{ + wpi::units::meter_t{msg.x}, + wpi::units::meter_t{msg.y}, }; } -bool wpi::Protobuf::Pack(OutputStream& stream, - const frc::Translation2d& value) { +bool wpi::util::Protobuf::Pack(OutputStream& stream, + const wpi::math::Translation2d& value) { wpi_proto_ProtobufTranslation2d msg{ .x = value.X().value(), .y = value.Y().value(), diff --git a/wpimath/src/main/native/cpp/geometry/proto/Translation3dProto.cpp b/wpimath/src/main/native/cpp/geometry/proto/Translation3dProto.cpp index b9ab094644..b75d026f86 100644 --- a/wpimath/src/main/native/cpp/geometry/proto/Translation3dProto.cpp +++ b/wpimath/src/main/native/cpp/geometry/proto/Translation3dProto.cpp @@ -6,22 +6,22 @@ #include "wpimath/protobuf/geometry3d.npb.h" -std::optional wpi::Protobuf::Unpack( +std::optional wpi::util::Protobuf::Unpack( InputStream& stream) { wpi_proto_ProtobufTranslation3d msg; if (!stream.Decode(msg)) { return {}; } - return frc::Translation3d{ - units::meter_t{msg.x}, - units::meter_t{msg.y}, - units::meter_t{msg.z}, + return wpi::math::Translation3d{ + wpi::units::meter_t{msg.x}, + wpi::units::meter_t{msg.y}, + wpi::units::meter_t{msg.z}, }; } -bool wpi::Protobuf::Pack(OutputStream& stream, - const frc::Translation3d& value) { +bool wpi::util::Protobuf::Pack(OutputStream& stream, + const wpi::math::Translation3d& value) { wpi_proto_ProtobufTranslation3d msg{ .x = value.X().value(), .y = value.Y().value(), diff --git a/wpimath/src/main/native/cpp/geometry/proto/Twist2dProto.cpp b/wpimath/src/main/native/cpp/geometry/proto/Twist2dProto.cpp index 5359f69f1a..dab29929ad 100644 --- a/wpimath/src/main/native/cpp/geometry/proto/Twist2dProto.cpp +++ b/wpimath/src/main/native/cpp/geometry/proto/Twist2dProto.cpp @@ -6,22 +6,22 @@ #include "wpimath/protobuf/geometry2d.npb.h" -std::optional wpi::Protobuf::Unpack( +std::optional wpi::util::Protobuf::Unpack( InputStream& stream) { wpi_proto_ProtobufTwist2d msg; if (!stream.Decode(msg)) { return {}; } - return frc::Twist2d{ - units::meter_t{msg.dx}, - units::meter_t{msg.dy}, - units::radian_t{msg.dtheta}, + return wpi::math::Twist2d{ + wpi::units::meter_t{msg.dx}, + wpi::units::meter_t{msg.dy}, + wpi::units::radian_t{msg.dtheta}, }; } -bool wpi::Protobuf::Pack(OutputStream& stream, - const frc::Twist2d& value) { +bool wpi::util::Protobuf::Pack(OutputStream& stream, + const wpi::math::Twist2d& value) { wpi_proto_ProtobufTwist2d msg{ .dx = value.dx.value(), .dy = value.dy.value(), diff --git a/wpimath/src/main/native/cpp/geometry/proto/Twist3dProto.cpp b/wpimath/src/main/native/cpp/geometry/proto/Twist3dProto.cpp index ccccb37906..712e6d6f4c 100644 --- a/wpimath/src/main/native/cpp/geometry/proto/Twist3dProto.cpp +++ b/wpimath/src/main/native/cpp/geometry/proto/Twist3dProto.cpp @@ -6,21 +6,21 @@ #include "wpimath/protobuf/geometry3d.npb.h" -std::optional wpi::Protobuf::Unpack( +std::optional wpi::util::Protobuf::Unpack( InputStream& stream) { wpi_proto_ProtobufTwist3d msg; if (!stream.Decode(msg)) { return {}; } - return frc::Twist3d{ - units::meter_t{msg.dx}, units::meter_t{msg.dy}, units::meter_t{msg.dz}, - units::radian_t{msg.rx}, units::radian_t{msg.ry}, units::radian_t{msg.rz}, + return wpi::math::Twist3d{ + wpi::units::meter_t{msg.dx}, wpi::units::meter_t{msg.dy}, wpi::units::meter_t{msg.dz}, + wpi::units::radian_t{msg.rx}, wpi::units::radian_t{msg.ry}, wpi::units::radian_t{msg.rz}, }; } -bool wpi::Protobuf::Pack(OutputStream& stream, - const frc::Twist3d& value) { +bool wpi::util::Protobuf::Pack(OutputStream& stream, + const wpi::math::Twist3d& value) { wpi_proto_ProtobufTwist3d msg{ .dx = value.dx.value(), .dy = value.dy.value(), diff --git a/wpimath/src/main/native/cpp/geometry/struct/Ellipse2dStruct.cpp b/wpimath/src/main/native/cpp/geometry/struct/Ellipse2dStruct.cpp index bcf007c5dc..72367f4644 100644 --- a/wpimath/src/main/native/cpp/geometry/struct/Ellipse2dStruct.cpp +++ b/wpimath/src/main/native/cpp/geometry/struct/Ellipse2dStruct.cpp @@ -6,22 +6,22 @@ namespace { constexpr size_t kCenterOff = 0; -constexpr size_t kXSemiAxisOff = kCenterOff + wpi::GetStructSize(); +constexpr size_t kXSemiAxisOff = kCenterOff + wpi::util::GetStructSize(); constexpr size_t kYSemiAxisOff = kXSemiAxisOff + 8; } // namespace -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; -frc::Ellipse2d StructType::Unpack(std::span data) { - return frc::Ellipse2d{ - wpi::UnpackStruct(data), - units::meter_t{wpi::UnpackStruct(data)}, - units::meter_t{wpi::UnpackStruct(data)}, +wpi::math::Ellipse2d StructType::Unpack(std::span data) { + return wpi::math::Ellipse2d{ + wpi::util::UnpackStruct(data), + wpi::units::meter_t{wpi::util::UnpackStruct(data)}, + wpi::units::meter_t{wpi::util::UnpackStruct(data)}, }; } -void StructType::Pack(std::span data, const frc::Ellipse2d& value) { - wpi::PackStruct(data, value.Center()); - wpi::PackStruct(data, value.XSemiAxis().value()); - wpi::PackStruct(data, value.YSemiAxis().value()); +void StructType::Pack(std::span data, const wpi::math::Ellipse2d& value) { + wpi::util::PackStruct(data, value.Center()); + wpi::util::PackStruct(data, value.XSemiAxis().value()); + wpi::util::PackStruct(data, value.YSemiAxis().value()); } diff --git a/wpimath/src/main/native/cpp/geometry/struct/Pose2dStruct.cpp b/wpimath/src/main/native/cpp/geometry/struct/Pose2dStruct.cpp index 77d42c4637..d2c1efe1c3 100644 --- a/wpimath/src/main/native/cpp/geometry/struct/Pose2dStruct.cpp +++ b/wpimath/src/main/native/cpp/geometry/struct/Pose2dStruct.cpp @@ -7,19 +7,19 @@ namespace { constexpr size_t kTranslationOff = 0; constexpr size_t kRotationOff = - kTranslationOff + wpi::GetStructSize(); + kTranslationOff + wpi::util::GetStructSize(); } // namespace -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; -frc::Pose2d StructType::Unpack(std::span data) { - return frc::Pose2d{ - wpi::UnpackStruct(data), - wpi::UnpackStruct(data), +wpi::math::Pose2d StructType::Unpack(std::span data) { + return wpi::math::Pose2d{ + wpi::util::UnpackStruct(data), + wpi::util::UnpackStruct(data), }; } -void StructType::Pack(std::span data, const frc::Pose2d& value) { - wpi::PackStruct(data, value.Translation()); - wpi::PackStruct(data, value.Rotation()); +void StructType::Pack(std::span data, const wpi::math::Pose2d& value) { + wpi::util::PackStruct(data, value.Translation()); + wpi::util::PackStruct(data, value.Rotation()); } diff --git a/wpimath/src/main/native/cpp/geometry/struct/Pose3dStruct.cpp b/wpimath/src/main/native/cpp/geometry/struct/Pose3dStruct.cpp index 44ac5b04ae..9c5705aeca 100644 --- a/wpimath/src/main/native/cpp/geometry/struct/Pose3dStruct.cpp +++ b/wpimath/src/main/native/cpp/geometry/struct/Pose3dStruct.cpp @@ -7,19 +7,19 @@ namespace { constexpr size_t kTranslationOff = 0; constexpr size_t kRotationOff = - kTranslationOff + wpi::GetStructSize(); + kTranslationOff + wpi::util::GetStructSize(); } // namespace -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; -frc::Pose3d StructType::Unpack(std::span data) { - return frc::Pose3d{ - wpi::UnpackStruct(data), - wpi::UnpackStruct(data), +wpi::math::Pose3d StructType::Unpack(std::span data) { + return wpi::math::Pose3d{ + wpi::util::UnpackStruct(data), + wpi::util::UnpackStruct(data), }; } -void StructType::Pack(std::span data, const frc::Pose3d& value) { - wpi::PackStruct(data, value.Translation()); - wpi::PackStruct(data, value.Rotation()); +void StructType::Pack(std::span data, const wpi::math::Pose3d& value) { + wpi::util::PackStruct(data, value.Translation()); + wpi::util::PackStruct(data, value.Rotation()); } diff --git a/wpimath/src/main/native/cpp/geometry/struct/QuaternionStruct.cpp b/wpimath/src/main/native/cpp/geometry/struct/QuaternionStruct.cpp index 381aa5c14f..5fd797a7f9 100644 --- a/wpimath/src/main/native/cpp/geometry/struct/QuaternionStruct.cpp +++ b/wpimath/src/main/native/cpp/geometry/struct/QuaternionStruct.cpp @@ -11,20 +11,20 @@ constexpr size_t kYOff = kXOff + 8; constexpr size_t kZOff = kYOff + 8; } // namespace -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; -frc::Quaternion StructType::Unpack(std::span data) { - return frc::Quaternion{ - wpi::UnpackStruct(data), - wpi::UnpackStruct(data), - wpi::UnpackStruct(data), - wpi::UnpackStruct(data), +wpi::math::Quaternion StructType::Unpack(std::span data) { + return wpi::math::Quaternion{ + wpi::util::UnpackStruct(data), + wpi::util::UnpackStruct(data), + wpi::util::UnpackStruct(data), + wpi::util::UnpackStruct(data), }; } -void StructType::Pack(std::span data, const frc::Quaternion& value) { - wpi::PackStruct(data, value.W()); - wpi::PackStruct(data, value.X()); - wpi::PackStruct(data, value.Y()); - wpi::PackStruct(data, value.Z()); +void StructType::Pack(std::span data, const wpi::math::Quaternion& value) { + wpi::util::PackStruct(data, value.W()); + wpi::util::PackStruct(data, value.X()); + wpi::util::PackStruct(data, value.Y()); + wpi::util::PackStruct(data, value.Z()); } diff --git a/wpimath/src/main/native/cpp/geometry/struct/Rectangle2dStruct.cpp b/wpimath/src/main/native/cpp/geometry/struct/Rectangle2dStruct.cpp index 2005c37a04..77716b8257 100644 --- a/wpimath/src/main/native/cpp/geometry/struct/Rectangle2dStruct.cpp +++ b/wpimath/src/main/native/cpp/geometry/struct/Rectangle2dStruct.cpp @@ -6,22 +6,22 @@ namespace { constexpr size_t kCenterOff = 0; -constexpr size_t kXWidthOff = kCenterOff + wpi::GetStructSize(); +constexpr size_t kXWidthOff = kCenterOff + wpi::util::GetStructSize(); constexpr size_t kYWidthOff = kXWidthOff + 8; } // namespace -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; -frc::Rectangle2d StructType::Unpack(std::span data) { - return frc::Rectangle2d{ - wpi::UnpackStruct(data), - units::meter_t{wpi::UnpackStruct(data)}, - units::meter_t{wpi::UnpackStruct(data)}, +wpi::math::Rectangle2d StructType::Unpack(std::span data) { + return wpi::math::Rectangle2d{ + wpi::util::UnpackStruct(data), + wpi::units::meter_t{wpi::util::UnpackStruct(data)}, + wpi::units::meter_t{wpi::util::UnpackStruct(data)}, }; } -void StructType::Pack(std::span data, const frc::Rectangle2d& value) { - wpi::PackStruct(data, value.Center()); - wpi::PackStruct(data, value.XWidth().value()); - wpi::PackStruct(data, value.YWidth().value()); +void StructType::Pack(std::span data, const wpi::math::Rectangle2d& value) { + wpi::util::PackStruct(data, value.Center()); + wpi::util::PackStruct(data, value.XWidth().value()); + wpi::util::PackStruct(data, value.YWidth().value()); } diff --git a/wpimath/src/main/native/cpp/geometry/struct/Rotation2dStruct.cpp b/wpimath/src/main/native/cpp/geometry/struct/Rotation2dStruct.cpp index 184aa9ed0a..be887ef65a 100644 --- a/wpimath/src/main/native/cpp/geometry/struct/Rotation2dStruct.cpp +++ b/wpimath/src/main/native/cpp/geometry/struct/Rotation2dStruct.cpp @@ -8,14 +8,14 @@ namespace { constexpr size_t kValueOff = 0; } // namespace -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; -frc::Rotation2d StructType::Unpack(std::span data) { - return frc::Rotation2d{ - units::radian_t{wpi::UnpackStruct(data)}, +wpi::math::Rotation2d StructType::Unpack(std::span data) { + return wpi::math::Rotation2d{ + wpi::units::radian_t{wpi::util::UnpackStruct(data)}, }; } -void StructType::Pack(std::span data, const frc::Rotation2d& value) { - wpi::PackStruct(data, value.Radians().value()); +void StructType::Pack(std::span data, const wpi::math::Rotation2d& value) { + wpi::util::PackStruct(data, value.Radians().value()); } diff --git a/wpimath/src/main/native/cpp/geometry/struct/Rotation3dStruct.cpp b/wpimath/src/main/native/cpp/geometry/struct/Rotation3dStruct.cpp index b8807953b3..0354d074a3 100644 --- a/wpimath/src/main/native/cpp/geometry/struct/Rotation3dStruct.cpp +++ b/wpimath/src/main/native/cpp/geometry/struct/Rotation3dStruct.cpp @@ -8,14 +8,14 @@ namespace { constexpr size_t kQOff = 0; } // namespace -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; -frc::Rotation3d StructType::Unpack(std::span data) { - return frc::Rotation3d{ - wpi::UnpackStruct(data), +wpi::math::Rotation3d StructType::Unpack(std::span data) { + return wpi::math::Rotation3d{ + wpi::util::UnpackStruct(data), }; } -void StructType::Pack(std::span data, const frc::Rotation3d& value) { - wpi::PackStruct(data, value.GetQuaternion()); +void StructType::Pack(std::span data, const wpi::math::Rotation3d& value) { + wpi::util::PackStruct(data, value.GetQuaternion()); } diff --git a/wpimath/src/main/native/cpp/geometry/struct/Transform2dStruct.cpp b/wpimath/src/main/native/cpp/geometry/struct/Transform2dStruct.cpp index 33678a8754..83eb0f87af 100644 --- a/wpimath/src/main/native/cpp/geometry/struct/Transform2dStruct.cpp +++ b/wpimath/src/main/native/cpp/geometry/struct/Transform2dStruct.cpp @@ -7,19 +7,19 @@ namespace { constexpr size_t kTranslationOff = 0; constexpr size_t kRotationOff = - kTranslationOff + wpi::GetStructSize(); + kTranslationOff + wpi::util::GetStructSize(); } // namespace -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; -frc::Transform2d StructType::Unpack(std::span data) { - return frc::Transform2d{ - wpi::UnpackStruct(data), - wpi::UnpackStruct(data), +wpi::math::Transform2d StructType::Unpack(std::span data) { + return wpi::math::Transform2d{ + wpi::util::UnpackStruct(data), + wpi::util::UnpackStruct(data), }; } -void StructType::Pack(std::span data, const frc::Transform2d& value) { - wpi::PackStruct(data, value.Translation()); - wpi::PackStruct(data, value.Rotation()); +void StructType::Pack(std::span data, const wpi::math::Transform2d& value) { + wpi::util::PackStruct(data, value.Translation()); + wpi::util::PackStruct(data, value.Rotation()); } diff --git a/wpimath/src/main/native/cpp/geometry/struct/Transform3dStruct.cpp b/wpimath/src/main/native/cpp/geometry/struct/Transform3dStruct.cpp index e986e001ee..7cccc7f523 100644 --- a/wpimath/src/main/native/cpp/geometry/struct/Transform3dStruct.cpp +++ b/wpimath/src/main/native/cpp/geometry/struct/Transform3dStruct.cpp @@ -7,19 +7,19 @@ namespace { constexpr size_t kTranslationOff = 0; constexpr size_t kRotationOff = - kTranslationOff + wpi::GetStructSize(); + kTranslationOff + wpi::util::GetStructSize(); } // namespace -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; -frc::Transform3d StructType::Unpack(std::span data) { - return frc::Transform3d{ - wpi::UnpackStruct(data), - wpi::UnpackStruct(data), +wpi::math::Transform3d StructType::Unpack(std::span data) { + return wpi::math::Transform3d{ + wpi::util::UnpackStruct(data), + wpi::util::UnpackStruct(data), }; } -void StructType::Pack(std::span data, const frc::Transform3d& value) { - wpi::PackStruct(data, value.Translation()); - wpi::PackStruct(data, value.Rotation()); +void StructType::Pack(std::span data, const wpi::math::Transform3d& value) { + wpi::util::PackStruct(data, value.Translation()); + wpi::util::PackStruct(data, value.Rotation()); } diff --git a/wpimath/src/main/native/cpp/geometry/struct/Translation2dStruct.cpp b/wpimath/src/main/native/cpp/geometry/struct/Translation2dStruct.cpp index 22028c5362..37dae99369 100644 --- a/wpimath/src/main/native/cpp/geometry/struct/Translation2dStruct.cpp +++ b/wpimath/src/main/native/cpp/geometry/struct/Translation2dStruct.cpp @@ -9,17 +9,17 @@ constexpr size_t kXOff = 0; constexpr size_t kYOff = kXOff + 8; } // namespace -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; -frc::Translation2d StructType::Unpack(std::span data) { - return frc::Translation2d{ - units::meter_t{wpi::UnpackStruct(data)}, - units::meter_t{wpi::UnpackStruct(data)}, +wpi::math::Translation2d StructType::Unpack(std::span data) { + return wpi::math::Translation2d{ + wpi::units::meter_t{wpi::util::UnpackStruct(data)}, + wpi::units::meter_t{wpi::util::UnpackStruct(data)}, }; } void StructType::Pack(std::span data, - const frc::Translation2d& value) { - wpi::PackStruct(data, value.X().value()); - wpi::PackStruct(data, value.Y().value()); + const wpi::math::Translation2d& value) { + wpi::util::PackStruct(data, value.X().value()); + wpi::util::PackStruct(data, value.Y().value()); } diff --git a/wpimath/src/main/native/cpp/geometry/struct/Translation3dStruct.cpp b/wpimath/src/main/native/cpp/geometry/struct/Translation3dStruct.cpp index 50ea05dbc9..ce0360016d 100644 --- a/wpimath/src/main/native/cpp/geometry/struct/Translation3dStruct.cpp +++ b/wpimath/src/main/native/cpp/geometry/struct/Translation3dStruct.cpp @@ -10,19 +10,19 @@ constexpr size_t kYOff = kXOff + 8; constexpr size_t kZOff = kYOff + 8; } // namespace -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; -frc::Translation3d StructType::Unpack(std::span data) { - return frc::Translation3d{ - units::meter_t{wpi::UnpackStruct(data)}, - units::meter_t{wpi::UnpackStruct(data)}, - units::meter_t{wpi::UnpackStruct(data)}, +wpi::math::Translation3d StructType::Unpack(std::span data) { + return wpi::math::Translation3d{ + wpi::units::meter_t{wpi::util::UnpackStruct(data)}, + wpi::units::meter_t{wpi::util::UnpackStruct(data)}, + wpi::units::meter_t{wpi::util::UnpackStruct(data)}, }; } void StructType::Pack(std::span data, - const frc::Translation3d& value) { - wpi::PackStruct(data, value.X().value()); - wpi::PackStruct(data, value.Y().value()); - wpi::PackStruct(data, value.Z().value()); + const wpi::math::Translation3d& value) { + wpi::util::PackStruct(data, value.X().value()); + wpi::util::PackStruct(data, value.Y().value()); + wpi::util::PackStruct(data, value.Z().value()); } diff --git a/wpimath/src/main/native/cpp/geometry/struct/Twist2dStruct.cpp b/wpimath/src/main/native/cpp/geometry/struct/Twist2dStruct.cpp index 97d0d5c19d..e0ccd248cd 100644 --- a/wpimath/src/main/native/cpp/geometry/struct/Twist2dStruct.cpp +++ b/wpimath/src/main/native/cpp/geometry/struct/Twist2dStruct.cpp @@ -10,18 +10,18 @@ constexpr size_t kDyOff = kDxOff + 8; constexpr size_t kDthetaOff = kDyOff + 8; } // namespace -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; -frc::Twist2d StructType::Unpack(std::span data) { - return frc::Twist2d{ - units::meter_t{wpi::UnpackStruct(data)}, - units::meter_t{wpi::UnpackStruct(data)}, - units::radian_t{wpi::UnpackStruct(data)}, +wpi::math::Twist2d StructType::Unpack(std::span data) { + return wpi::math::Twist2d{ + wpi::units::meter_t{wpi::util::UnpackStruct(data)}, + wpi::units::meter_t{wpi::util::UnpackStruct(data)}, + wpi::units::radian_t{wpi::util::UnpackStruct(data)}, }; } -void StructType::Pack(std::span data, const frc::Twist2d& value) { - wpi::PackStruct(data, value.dx.value()); - wpi::PackStruct(data, value.dy.value()); - wpi::PackStruct(data, value.dtheta.value()); +void StructType::Pack(std::span data, const wpi::math::Twist2d& value) { + wpi::util::PackStruct(data, value.dx.value()); + wpi::util::PackStruct(data, value.dy.value()); + wpi::util::PackStruct(data, value.dtheta.value()); } diff --git a/wpimath/src/main/native/cpp/geometry/struct/Twist3dStruct.cpp b/wpimath/src/main/native/cpp/geometry/struct/Twist3dStruct.cpp index 6fc3d2a94e..a213952716 100644 --- a/wpimath/src/main/native/cpp/geometry/struct/Twist3dStruct.cpp +++ b/wpimath/src/main/native/cpp/geometry/struct/Twist3dStruct.cpp @@ -13,24 +13,24 @@ constexpr size_t kRyOff = kRxOff + 8; constexpr size_t kRzOff = kRyOff + 8; } // namespace -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; -frc::Twist3d StructType::Unpack(std::span data) { - return frc::Twist3d{ - units::meter_t{wpi::UnpackStruct(data)}, - units::meter_t{wpi::UnpackStruct(data)}, - units::meter_t{wpi::UnpackStruct(data)}, - units::radian_t{wpi::UnpackStruct(data)}, - units::radian_t{wpi::UnpackStruct(data)}, - units::radian_t{wpi::UnpackStruct(data)}, +wpi::math::Twist3d StructType::Unpack(std::span data) { + return wpi::math::Twist3d{ + wpi::units::meter_t{wpi::util::UnpackStruct(data)}, + wpi::units::meter_t{wpi::util::UnpackStruct(data)}, + wpi::units::meter_t{wpi::util::UnpackStruct(data)}, + wpi::units::radian_t{wpi::util::UnpackStruct(data)}, + wpi::units::radian_t{wpi::util::UnpackStruct(data)}, + wpi::units::radian_t{wpi::util::UnpackStruct(data)}, }; } -void StructType::Pack(std::span data, const frc::Twist3d& value) { - wpi::PackStruct(data, value.dx.value()); - wpi::PackStruct(data, value.dy.value()); - wpi::PackStruct(data, value.dz.value()); - wpi::PackStruct(data, value.rx.value()); - wpi::PackStruct(data, value.ry.value()); - wpi::PackStruct(data, value.rz.value()); +void StructType::Pack(std::span data, const wpi::math::Twist3d& value) { + wpi::util::PackStruct(data, value.dx.value()); + wpi::util::PackStruct(data, value.dy.value()); + wpi::util::PackStruct(data, value.dz.value()); + wpi::util::PackStruct(data, value.rx.value()); + wpi::util::PackStruct(data, value.ry.value()); + wpi::util::PackStruct(data, value.rz.value()); } diff --git a/wpimath/src/main/native/cpp/jni/ArmFeedforwardJNI.cpp b/wpimath/src/main/native/cpp/jni/ArmFeedforwardJNI.cpp index 67d1b6c498..1b280b8966 100644 --- a/wpimath/src/main/native/cpp/jni/ArmFeedforwardJNI.cpp +++ b/wpimath/src/main/native/cpp/jni/ArmFeedforwardJNI.cpp @@ -8,7 +8,7 @@ #include "wpi/math/controller/ArmFeedforward.hpp" #include "wpi/util/jni_util.hpp" -using namespace wpi::java; +using namespace wpi::util::java; extern "C" { @@ -23,13 +23,13 @@ Java_org_wpilib_math_jni_ArmFeedforwardJNI_calculate jdouble currentAngle, jdouble currentVelocity, jdouble nextVelocity, jdouble dt) { - return frc::ArmFeedforward{units::volt_t{ks}, units::volt_t{kg}, - units::unit_t{kv}, - units::unit_t{ka}, - units::second_t{dt}} - .Calculate(units::radian_t{currentAngle}, - units::radians_per_second_t{currentVelocity}, - units::radians_per_second_t{nextVelocity}) + return wpi::math::ArmFeedforward{wpi::units::volt_t{ks}, wpi::units::volt_t{kg}, + wpi::units::unit_t{kv}, + wpi::units::unit_t{ka}, + wpi::units::second_t{dt}} + .Calculate(wpi::units::radian_t{currentAngle}, + wpi::units::radians_per_second_t{currentVelocity}, + wpi::units::radians_per_second_t{nextVelocity}) .value(); } diff --git a/wpimath/src/main/native/cpp/jni/DAREJNI.cpp b/wpimath/src/main/native/cpp/jni/DAREJNI.cpp index a0e96e0beb..7afb1b560e 100644 --- a/wpimath/src/main/native/cpp/jni/DAREJNI.cpp +++ b/wpimath/src/main/native/cpp/jni/DAREJNI.cpp @@ -13,7 +13,7 @@ #include "wpi/math/linalg/DARE.hpp" #include "wpi/util/jni_util.hpp" -using namespace wpi::java; +using namespace wpi::util::java; extern "C" { @@ -46,7 +46,7 @@ Java_org_wpilib_math_jni_DAREJNI_dareNoPrecondABQR Rmat{nativeR.data(), inputs, inputs}; auto result = - frc::DARE(Amat, Bmat, Qmat, Rmat, false) + wpi::math::DARE(Amat, Bmat, Qmat, Rmat, false) .value(); env->SetDoubleArrayRegion(S, 0, states * states, result.data()); @@ -84,7 +84,7 @@ Java_org_wpilib_math_jni_DAREJNI_dareNoPrecondABQRN Eigen::RowMajor>> Nmat{nativeN.data(), states, inputs}; - auto result = frc::DARE(Amat, Bmat, Qmat, + auto result = wpi::math::DARE(Amat, Bmat, Qmat, Rmat, Nmat, false) .value(); @@ -120,21 +120,21 @@ Java_org_wpilib_math_jni_DAREJNI_dareABQR Rmat{nativeR.data(), inputs, inputs}; if (auto result = - frc::DARE(Amat, Bmat, Qmat, Rmat)) { + wpi::math::DARE(Amat, Bmat, Qmat, Rmat)) { env->SetDoubleArrayRegion(S, 0, states * states, result.value().data()); // K = (BᵀSB + R)⁻¹BᵀSA - } else if (result.error() == frc::DAREError::QNotSymmetric || - result.error() == frc::DAREError::QNotPositiveSemidefinite) { + } else if (result.error() == wpi::math::DAREError::QNotSymmetric || + result.error() == wpi::math::DAREError::QNotPositiveSemidefinite) { illegalArgEx.Throw( env, fmt::format("{}\n\nQ =\n{}\n", to_string(result.error()), Qmat)); - } else if (result.error() == frc::DAREError::RNotSymmetric || - result.error() == frc::DAREError::RNotPositiveDefinite) { + } else if (result.error() == wpi::math::DAREError::RNotSymmetric || + result.error() == wpi::math::DAREError::RNotPositiveDefinite) { illegalArgEx.Throw( env, fmt::format("{}\n\nR =\n{}\n", to_string(result.error()), Rmat)); - } else if (result.error() == frc::DAREError::ABNotStabilizable) { + } else if (result.error() == wpi::math::DAREError::ABNotStabilizable) { illegalArgEx.Throw(env, fmt::format("{}\n\nA =\n{}\nB =\n{}\n", to_string(result.error()), Amat, Bmat)); - } else if (result.error() == frc::DAREError::ACNotDetectable) { + } else if (result.error() == wpi::math::DAREError::ACNotDetectable) { illegalArgEx.Throw(env, fmt::format("{}\n\nA =\n{}\nQ =\n{}\n", to_string(result.error()), Amat, Qmat)); } @@ -172,23 +172,23 @@ Java_org_wpilib_math_jni_DAREJNI_dareABQRN Eigen::RowMajor>> Nmat{nativeN.data(), states, inputs}; - if (auto result = frc::DARE(Amat, Bmat, Qmat, + if (auto result = wpi::math::DARE(Amat, Bmat, Qmat, Rmat, Nmat)) { env->SetDoubleArrayRegion(S, 0, states * states, result.value().data()); - } else if (result.error() == frc::DAREError::QNotSymmetric || - result.error() == frc::DAREError::QNotPositiveSemidefinite) { + } else if (result.error() == wpi::math::DAREError::QNotSymmetric || + result.error() == wpi::math::DAREError::QNotPositiveSemidefinite) { illegalArgEx.Throw( env, fmt::format("{}\n\nQ =\n{}\n", to_string(result.error()), Qmat)); - } else if (result.error() == frc::DAREError::RNotSymmetric || - result.error() == frc::DAREError::RNotPositiveDefinite) { + } else if (result.error() == wpi::math::DAREError::RNotSymmetric || + result.error() == wpi::math::DAREError::RNotPositiveDefinite) { illegalArgEx.Throw( env, fmt::format("{}\n\nR =\n{}\n", to_string(result.error()), Rmat)); - } else if (result.error() == frc::DAREError::ABNotStabilizable) { + } else if (result.error() == wpi::math::DAREError::ABNotStabilizable) { illegalArgEx.Throw( env, fmt::format("{}\n\nA =\n{}\nB =\n{}\n", to_string(result.error()), Amat - Bmat * Rmat.llt().solve(Nmat.transpose()), Bmat)); - } else if (result.error() == frc::DAREError::ACNotDetectable) { + } else if (result.error() == wpi::math::DAREError::ACNotDetectable) { auto R_llt = Rmat.llt(); illegalArgEx.Throw( env, fmt::format("{}\n\nA =\n{}\nQ =\n{}\n", to_string(result.error()), diff --git a/wpimath/src/main/native/cpp/jni/EigenJNI.cpp b/wpimath/src/main/native/cpp/jni/EigenJNI.cpp index 2c810e3e1b..a16b7e31ba 100644 --- a/wpimath/src/main/native/cpp/jni/EigenJNI.cpp +++ b/wpimath/src/main/native/cpp/jni/EigenJNI.cpp @@ -12,7 +12,7 @@ #include "org_wpilib_math_jni_EigenJNI.h" #include "wpi/util/jni_util.hpp" -using namespace wpi::java; +using namespace wpi::util::java; extern "C" { diff --git a/wpimath/src/main/native/cpp/jni/Ellipse2dJNI.cpp b/wpimath/src/main/native/cpp/jni/Ellipse2dJNI.cpp index a91e44fd44..28d3877b2f 100644 --- a/wpimath/src/main/native/cpp/jni/Ellipse2dJNI.cpp +++ b/wpimath/src/main/native/cpp/jni/Ellipse2dJNI.cpp @@ -9,7 +9,7 @@ #include "wpi/util/array.hpp" #include "wpi/util/jni_util.hpp" -using namespace wpi::java; +using namespace wpi::util::java; extern "C" { @@ -25,13 +25,13 @@ Java_org_wpilib_math_jni_Ellipse2dJNI_nearest jdoubleArray nearestPoint) { auto point = - frc::Ellipse2d{ - frc::Pose2d{units::meter_t{centerX}, units::meter_t{centerY}, - units::radian_t{centerHeading}}, - units::meter_t{xSemiAxis}, units::meter_t{ySemiAxis}} - .Nearest({units::meter_t{pointX}, units::meter_t{pointY}}); + wpi::math::Ellipse2d{ + wpi::math::Pose2d{wpi::units::meter_t{centerX}, wpi::units::meter_t{centerY}, + wpi::units::radian_t{centerHeading}}, + wpi::units::meter_t{xSemiAxis}, wpi::units::meter_t{ySemiAxis}} + .Nearest({wpi::units::meter_t{pointX}, wpi::units::meter_t{pointY}}); - wpi::array buf{point.X().value(), point.Y().value()}; + wpi::util::array buf{point.X().value(), point.Y().value()}; env->SetDoubleArrayRegion(nearestPoint, 0, 2, buf.data()); } diff --git a/wpimath/src/main/native/cpp/jni/Exceptions.cpp b/wpimath/src/main/native/cpp/jni/Exceptions.cpp index 0bd0311661..37f52b36e6 100644 --- a/wpimath/src/main/native/cpp/jni/Exceptions.cpp +++ b/wpimath/src/main/native/cpp/jni/Exceptions.cpp @@ -6,7 +6,7 @@ #include -using namespace wpi::java; +using namespace wpi::util::java; // // Globals and load/unload diff --git a/wpimath/src/main/native/cpp/jni/Exceptions.hpp b/wpimath/src/main/native/cpp/jni/Exceptions.hpp index 476e896c06..b0ba37d3e9 100644 --- a/wpimath/src/main/native/cpp/jni/Exceptions.hpp +++ b/wpimath/src/main/native/cpp/jni/Exceptions.hpp @@ -6,6 +6,6 @@ #include "wpi/util/jni_util.hpp" -extern wpi::java::JException illegalArgEx; -extern wpi::java::JException ioEx; -extern wpi::java::JException trajectorySerializationEx; +extern wpi::util::java::JException illegalArgEx; +extern wpi::util::java::JException ioEx; +extern wpi::util::java::JException trajectorySerializationEx; diff --git a/wpimath/src/main/native/cpp/jni/StateSpaceUtilJNI.cpp b/wpimath/src/main/native/cpp/jni/StateSpaceUtilJNI.cpp index 03539452f2..86176f1f60 100644 --- a/wpimath/src/main/native/cpp/jni/StateSpaceUtilJNI.cpp +++ b/wpimath/src/main/native/cpp/jni/StateSpaceUtilJNI.cpp @@ -10,7 +10,7 @@ #include "wpi/math/util/StateSpaceUtil.hpp" #include "wpi/util/jni_util.hpp" -using namespace wpi::java; +using namespace wpi::util::java; extern "C" { @@ -36,7 +36,7 @@ Java_org_wpilib_math_jni_StateSpaceUtilJNI_isStabilizable B{nativeB.data(), states, inputs}; bool isStabilizable = - frc::IsStabilizable(A, B); + wpi::math::IsStabilizable(A, B); return isStabilizable; } diff --git a/wpimath/src/main/native/cpp/jni/Transform3dJNI.cpp b/wpimath/src/main/native/cpp/jni/Transform3dJNI.cpp index 369e722aa7..1e20916e30 100644 --- a/wpimath/src/main/native/cpp/jni/Transform3dJNI.cpp +++ b/wpimath/src/main/native/cpp/jni/Transform3dJNI.cpp @@ -13,7 +13,7 @@ #include "wpi/units/length.hpp" #include "wpi/util/jni_util.hpp" -using namespace wpi::java; +using namespace wpi::util::java; extern "C" { @@ -27,11 +27,11 @@ Java_org_wpilib_math_jni_Transform3dJNI_log (JNIEnv* env, jclass, jdouble relX, jdouble relY, jdouble relZ, jdouble relQw, jdouble relQx, jdouble relQy, jdouble relQz) { - frc::Transform3d transform3d{ - units::meter_t{relX}, units::meter_t{relY}, units::meter_t{relZ}, - frc::Rotation3d{frc::Quaternion{relQw, relQx, relQy, relQz}}}; + wpi::math::Transform3d transform3d{ + wpi::units::meter_t{relX}, wpi::units::meter_t{relY}, wpi::units::meter_t{relZ}, + wpi::math::Rotation3d{wpi::math::Quaternion{relQw, relQx, relQy, relQz}}}; - frc::Twist3d result = transform3d.Log(); + wpi::math::Twist3d result = transform3d.Log(); return MakeJDoubleArray( env, {{result.dx.value(), result.dy.value(), result.dz.value(), diff --git a/wpimath/src/main/native/cpp/jni/Twist3dJNI.cpp b/wpimath/src/main/native/cpp/jni/Twist3dJNI.cpp index e9de7cbcfb..7c82ea72aa 100644 --- a/wpimath/src/main/native/cpp/jni/Twist3dJNI.cpp +++ b/wpimath/src/main/native/cpp/jni/Twist3dJNI.cpp @@ -11,7 +11,7 @@ #include "wpi/units/length.hpp" #include "wpi/util/jni_util.hpp" -using namespace wpi::java; +using namespace wpi::util::java; extern "C" { @@ -25,11 +25,11 @@ Java_org_wpilib_math_jni_Twist3dJNI_exp (JNIEnv* env, jclass, jdouble twistDx, jdouble twistDy, jdouble twistDz, jdouble twistRx, jdouble twistRy, jdouble twistRz) { - frc::Twist3d twist{units::meter_t{twistDx}, units::meter_t{twistDy}, - units::meter_t{twistDz}, units::radian_t{twistRx}, - units::radian_t{twistRy}, units::radian_t{twistRz}}; + wpi::math::Twist3d twist{wpi::units::meter_t{twistDx}, wpi::units::meter_t{twistDy}, + wpi::units::meter_t{twistDz}, wpi::units::radian_t{twistRx}, + wpi::units::radian_t{twistRy}, wpi::units::radian_t{twistRz}}; - frc::Transform3d result = twist.Exp(); + wpi::math::Transform3d result = twist.Exp(); const auto& resultQuaternion = result.Rotation().GetQuaternion(); return MakeJDoubleArray( diff --git a/wpimath/src/main/native/cpp/kinematics/DifferentialDriveOdometry.cpp b/wpimath/src/main/native/cpp/kinematics/DifferentialDriveOdometry.cpp index 030e178fbd..bdc6c2aacf 100644 --- a/wpimath/src/main/native/cpp/kinematics/DifferentialDriveOdometry.cpp +++ b/wpimath/src/main/native/cpp/kinematics/DifferentialDriveOdometry.cpp @@ -6,11 +6,11 @@ #include "wpi/math/util/MathShared.hpp" -using namespace frc; +using namespace wpi::math; DifferentialDriveOdometry::DifferentialDriveOdometry( - const Rotation2d& gyroAngle, units::meter_t leftDistance, - units::meter_t rightDistance, const Pose2d& initialPose) + const Rotation2d& gyroAngle, wpi::units::meter_t leftDistance, + wpi::units::meter_t rightDistance, const Pose2d& initialPose) : Odometry(m_kinematicsImpl, gyroAngle, {leftDistance, rightDistance}, initialPose) { wpi::math::MathSharedStore::ReportUsage("DifferentialDriveOdometry", ""); diff --git a/wpimath/src/main/native/cpp/kinematics/DifferentialDriveOdometry3d.cpp b/wpimath/src/main/native/cpp/kinematics/DifferentialDriveOdometry3d.cpp index 3d923ed1e3..b6e0bf034e 100644 --- a/wpimath/src/main/native/cpp/kinematics/DifferentialDriveOdometry3d.cpp +++ b/wpimath/src/main/native/cpp/kinematics/DifferentialDriveOdometry3d.cpp @@ -6,11 +6,11 @@ #include "wpi/math/util/MathShared.hpp" -using namespace frc; +using namespace wpi::math; DifferentialDriveOdometry3d::DifferentialDriveOdometry3d( - const Rotation3d& gyroAngle, units::meter_t leftDistance, - units::meter_t rightDistance, const Pose3d& initialPose) + const Rotation3d& gyroAngle, wpi::units::meter_t leftDistance, + wpi::units::meter_t rightDistance, const Pose3d& initialPose) : Odometry3d(m_kinematicsImpl, gyroAngle, {leftDistance, rightDistance}, initialPose) { wpi::math::MathSharedStore::ReportUsage("DifferentialDriveOdometry3d", ""); diff --git a/wpimath/src/main/native/cpp/kinematics/MecanumDriveKinematics.cpp b/wpimath/src/main/native/cpp/kinematics/MecanumDriveKinematics.cpp index 99d18b4f93..04a9818ff7 100644 --- a/wpimath/src/main/native/cpp/kinematics/MecanumDriveKinematics.cpp +++ b/wpimath/src/main/native/cpp/kinematics/MecanumDriveKinematics.cpp @@ -4,7 +4,7 @@ #include "wpi/math/kinematics/MecanumDriveKinematics.hpp" -using namespace frc; +using namespace wpi::math; MecanumDriveWheelSpeeds MecanumDriveKinematics::ToWheelSpeeds( const ChassisSpeeds& chassisSpeeds, @@ -28,10 +28,10 @@ MecanumDriveWheelSpeeds MecanumDriveKinematics::ToWheelSpeeds( Eigen::Vector4d wheelsVector = m_inverseKinematics * chassisSpeedsVector; MecanumDriveWheelSpeeds wheelSpeeds; - wheelSpeeds.frontLeft = units::meters_per_second_t{wheelsVector(0)}; - wheelSpeeds.frontRight = units::meters_per_second_t{wheelsVector(1)}; - wheelSpeeds.rearLeft = units::meters_per_second_t{wheelsVector(2)}; - wheelSpeeds.rearRight = units::meters_per_second_t{wheelsVector(3)}; + wheelSpeeds.frontLeft = wpi::units::meters_per_second_t{wheelsVector(0)}; + wheelSpeeds.frontRight = wpi::units::meters_per_second_t{wheelsVector(1)}; + wheelSpeeds.rearLeft = wpi::units::meters_per_second_t{wheelsVector(2)}; + wheelSpeeds.rearRight = wpi::units::meters_per_second_t{wheelsVector(3)}; return wheelSpeeds; } @@ -44,9 +44,9 @@ ChassisSpeeds MecanumDriveKinematics::ToChassisSpeeds( Eigen::Vector3d chassisSpeedsVector = m_forwardKinematics.solve(wheelSpeedsVector); - return {units::meters_per_second_t{chassisSpeedsVector(0)}, // NOLINT - units::meters_per_second_t{chassisSpeedsVector(1)}, - units::radians_per_second_t{chassisSpeedsVector(2)}}; + return {wpi::units::meters_per_second_t{chassisSpeedsVector(0)}, // NOLINT + wpi::units::meters_per_second_t{chassisSpeedsVector(1)}, + wpi::units::radians_per_second_t{chassisSpeedsVector(2)}}; } Twist2d MecanumDriveKinematics::ToTwist2d( @@ -60,8 +60,8 @@ Twist2d MecanumDriveKinematics::ToTwist2d( Eigen::Vector3d twistVector = m_forwardKinematics.solve(wheelDeltasVector); - return {units::meter_t{twistVector(0)}, units::meter_t{twistVector(1)}, - units::radian_t{twistVector(2)}}; + return {wpi::units::meter_t{twistVector(0)}, wpi::units::meter_t{twistVector(1)}, + wpi::units::radian_t{twistVector(2)}}; } Twist2d MecanumDriveKinematics::ToTwist2d( @@ -72,8 +72,8 @@ Twist2d MecanumDriveKinematics::ToTwist2d( Eigen::Vector3d twistVector = m_forwardKinematics.solve(wheelDeltasVector); - return {units::meter_t{twistVector(0)}, units::meter_t{twistVector(1)}, - units::radian_t{twistVector(2)}}; + return {wpi::units::meter_t{twistVector(0)}, wpi::units::meter_t{twistVector(1)}, + wpi::units::radian_t{twistVector(2)}}; } void MecanumDriveKinematics::SetInverseKinematics(Translation2d fl, diff --git a/wpimath/src/main/native/cpp/kinematics/MecanumDriveOdometry.cpp b/wpimath/src/main/native/cpp/kinematics/MecanumDriveOdometry.cpp index 7022f852a8..f7df5d3a2e 100644 --- a/wpimath/src/main/native/cpp/kinematics/MecanumDriveOdometry.cpp +++ b/wpimath/src/main/native/cpp/kinematics/MecanumDriveOdometry.cpp @@ -6,7 +6,7 @@ #include "wpi/math/util/MathShared.hpp" -using namespace frc; +using namespace wpi::math; MecanumDriveOdometry::MecanumDriveOdometry( MecanumDriveKinematics kinematics, const Rotation2d& gyroAngle, diff --git a/wpimath/src/main/native/cpp/kinematics/MecanumDriveOdometry3d.cpp b/wpimath/src/main/native/cpp/kinematics/MecanumDriveOdometry3d.cpp index 3c83651e85..bd2fac79ab 100644 --- a/wpimath/src/main/native/cpp/kinematics/MecanumDriveOdometry3d.cpp +++ b/wpimath/src/main/native/cpp/kinematics/MecanumDriveOdometry3d.cpp @@ -6,7 +6,7 @@ #include "wpi/math/util/MathShared.hpp" -using namespace frc; +using namespace wpi::math; MecanumDriveOdometry3d::MecanumDriveOdometry3d( MecanumDriveKinematics kinematics, const Rotation3d& gyroAngle, diff --git a/wpimath/src/main/native/cpp/kinematics/SwerveDriveKinematics.cpp b/wpimath/src/main/native/cpp/kinematics/SwerveDriveKinematics.cpp index 46e8257161..7904440ece 100644 --- a/wpimath/src/main/native/cpp/kinematics/SwerveDriveKinematics.cpp +++ b/wpimath/src/main/native/cpp/kinematics/SwerveDriveKinematics.cpp @@ -4,9 +4,9 @@ #include "wpi/math/kinematics/SwerveDriveKinematics.hpp" -namespace frc { +namespace wpi::math { template class EXPORT_TEMPLATE_DEFINE(WPILIB_DLLEXPORT) SwerveDriveKinematics<4>; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/cpp/kinematics/SwerveDriveOdometry.cpp b/wpimath/src/main/native/cpp/kinematics/SwerveDriveOdometry.cpp index eb33a07f15..02abc4125a 100644 --- a/wpimath/src/main/native/cpp/kinematics/SwerveDriveOdometry.cpp +++ b/wpimath/src/main/native/cpp/kinematics/SwerveDriveOdometry.cpp @@ -4,8 +4,8 @@ #include "wpi/math/kinematics/SwerveDriveOdometry.hpp" -namespace frc { +namespace wpi::math { template class EXPORT_TEMPLATE_DEFINE(WPILIB_DLLEXPORT) SwerveDriveOdometry<4>; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/cpp/kinematics/SwerveDriveOdometry3d.cpp b/wpimath/src/main/native/cpp/kinematics/SwerveDriveOdometry3d.cpp index e1c9a81067..d8be23d2f5 100644 --- a/wpimath/src/main/native/cpp/kinematics/SwerveDriveOdometry3d.cpp +++ b/wpimath/src/main/native/cpp/kinematics/SwerveDriveOdometry3d.cpp @@ -4,9 +4,9 @@ #include "wpi/math/kinematics/SwerveDriveOdometry3d.hpp" -namespace frc { +namespace wpi::math { template class EXPORT_TEMPLATE_DEFINE(WPILIB_DLLEXPORT) SwerveDriveOdometry3d<4>; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/cpp/kinematics/proto/ChassisSpeedsProto.cpp b/wpimath/src/main/native/cpp/kinematics/proto/ChassisSpeedsProto.cpp index ae3badb0e5..168714e475 100644 --- a/wpimath/src/main/native/cpp/kinematics/proto/ChassisSpeedsProto.cpp +++ b/wpimath/src/main/native/cpp/kinematics/proto/ChassisSpeedsProto.cpp @@ -6,22 +6,22 @@ #include "wpimath/protobuf/kinematics.npb.h" -std::optional wpi::Protobuf::Unpack( +std::optional wpi::util::Protobuf::Unpack( InputStream& stream) { wpi_proto_ProtobufChassisSpeeds msg; if (!stream.Decode(msg)) { return {}; } - return frc::ChassisSpeeds{ - units::meters_per_second_t{msg.vx}, - units::meters_per_second_t{msg.vy}, - units::radians_per_second_t{msg.omega}, + return wpi::math::ChassisSpeeds{ + wpi::units::meters_per_second_t{msg.vx}, + wpi::units::meters_per_second_t{msg.vy}, + wpi::units::radians_per_second_t{msg.omega}, }; } -bool wpi::Protobuf::Pack(OutputStream& stream, - const frc::ChassisSpeeds& value) { +bool wpi::util::Protobuf::Pack(OutputStream& stream, + const wpi::math::ChassisSpeeds& value) { wpi_proto_ProtobufChassisSpeeds msg{ .vx = value.vx.value(), .vy = value.vy.value(), diff --git a/wpimath/src/main/native/cpp/kinematics/proto/DifferentialDriveKinematicsProto.cpp b/wpimath/src/main/native/cpp/kinematics/proto/DifferentialDriveKinematicsProto.cpp index 630947cf90..a47296d7d4 100644 --- a/wpimath/src/main/native/cpp/kinematics/proto/DifferentialDriveKinematicsProto.cpp +++ b/wpimath/src/main/native/cpp/kinematics/proto/DifferentialDriveKinematicsProto.cpp @@ -6,20 +6,20 @@ #include "wpimath/protobuf/kinematics.npb.h" -std::optional -wpi::Protobuf::Unpack(InputStream& stream) { +std::optional +wpi::util::Protobuf::Unpack(InputStream& stream) { wpi_proto_ProtobufDifferentialDriveKinematics msg; if (!stream.Decode(msg)) { return {}; } - return frc::DifferentialDriveKinematics{ - units::meter_t{msg.trackwidth}, + return wpi::math::DifferentialDriveKinematics{ + wpi::units::meter_t{msg.trackwidth}, }; } -bool wpi::Protobuf::Pack( - OutputStream& stream, const frc::DifferentialDriveKinematics& value) { +bool wpi::util::Protobuf::Pack( + OutputStream& stream, const wpi::math::DifferentialDriveKinematics& value) { wpi_proto_ProtobufDifferentialDriveKinematics msg{ .trackwidth = value.trackwidth.value(), }; diff --git a/wpimath/src/main/native/cpp/kinematics/proto/DifferentialDriveWheelPositionsProto.cpp b/wpimath/src/main/native/cpp/kinematics/proto/DifferentialDriveWheelPositionsProto.cpp index e42537295e..ff6ec6a9f2 100644 --- a/wpimath/src/main/native/cpp/kinematics/proto/DifferentialDriveWheelPositionsProto.cpp +++ b/wpimath/src/main/native/cpp/kinematics/proto/DifferentialDriveWheelPositionsProto.cpp @@ -6,21 +6,21 @@ #include "wpimath/protobuf/kinematics.npb.h" -std::optional wpi::Protobuf< - frc::DifferentialDriveWheelPositions>::Unpack(InputStream& stream) { +std::optional wpi::util::Protobuf< + wpi::math::DifferentialDriveWheelPositions>::Unpack(InputStream& stream) { wpi_proto_ProtobufDifferentialDriveWheelPositions msg; if (!stream.Decode(msg)) { return {}; } - return frc::DifferentialDriveWheelPositions{ - units::meter_t{msg.left}, - units::meter_t{msg.right}, + return wpi::math::DifferentialDriveWheelPositions{ + wpi::units::meter_t{msg.left}, + wpi::units::meter_t{msg.right}, }; } -bool wpi::Protobuf::Pack( - OutputStream& stream, const frc::DifferentialDriveWheelPositions& value) { +bool wpi::util::Protobuf::Pack( + OutputStream& stream, const wpi::math::DifferentialDriveWheelPositions& value) { wpi_proto_ProtobufDifferentialDriveWheelPositions msg{ .left = value.left.value(), .right = value.right.value(), diff --git a/wpimath/src/main/native/cpp/kinematics/proto/DifferentialDriveWheelSpeedsProto.cpp b/wpimath/src/main/native/cpp/kinematics/proto/DifferentialDriveWheelSpeedsProto.cpp index df85399e41..5a2b555d45 100644 --- a/wpimath/src/main/native/cpp/kinematics/proto/DifferentialDriveWheelSpeedsProto.cpp +++ b/wpimath/src/main/native/cpp/kinematics/proto/DifferentialDriveWheelSpeedsProto.cpp @@ -6,21 +6,21 @@ #include "wpimath/protobuf/kinematics.npb.h" -std::optional -wpi::Protobuf::Unpack(InputStream& stream) { +std::optional +wpi::util::Protobuf::Unpack(InputStream& stream) { wpi_proto_ProtobufDifferentialDriveWheelSpeeds msg; if (!stream.Decode(msg)) { return {}; } - return frc::DifferentialDriveWheelSpeeds{ - units::meters_per_second_t{msg.left}, - units::meters_per_second_t{msg.right}, + return wpi::math::DifferentialDriveWheelSpeeds{ + wpi::units::meters_per_second_t{msg.left}, + wpi::units::meters_per_second_t{msg.right}, }; } -bool wpi::Protobuf::Pack( - OutputStream& stream, const frc::DifferentialDriveWheelSpeeds& value) { +bool wpi::util::Protobuf::Pack( + OutputStream& stream, const wpi::math::DifferentialDriveWheelSpeeds& value) { wpi_proto_ProtobufDifferentialDriveWheelSpeeds msg{ .left = value.left.value(), .right = value.right.value(), diff --git a/wpimath/src/main/native/cpp/kinematics/proto/MecanumDriveKinematicsProto.cpp b/wpimath/src/main/native/cpp/kinematics/proto/MecanumDriveKinematicsProto.cpp index abeca52516..be9dcd7fa0 100644 --- a/wpimath/src/main/native/cpp/kinematics/proto/MecanumDriveKinematicsProto.cpp +++ b/wpimath/src/main/native/cpp/kinematics/proto/MecanumDriveKinematicsProto.cpp @@ -7,12 +7,12 @@ #include "wpi/util/protobuf/ProtobufCallbacks.hpp" #include "wpimath/protobuf/kinematics.npb.h" -std::optional -wpi::Protobuf::Unpack(InputStream& stream) { - wpi::UnpackCallback frontLeft; - wpi::UnpackCallback frontRight; - wpi::UnpackCallback rearLeft; - wpi::UnpackCallback rearRight; +std::optional +wpi::util::Protobuf::Unpack(InputStream& stream) { + wpi::util::UnpackCallback frontLeft; + wpi::util::UnpackCallback frontRight; + wpi::util::UnpackCallback rearLeft; + wpi::util::UnpackCallback rearRight; wpi_proto_ProtobufMecanumDriveKinematics msg{ .front_left = frontLeft.Callback(), .front_right = frontRight.Callback(), @@ -33,7 +33,7 @@ wpi::Protobuf::Unpack(InputStream& stream) { return {}; } - return frc::MecanumDriveKinematics{ + return wpi::math::MecanumDriveKinematics{ ifrontLeft[0], ifrontRight[0], irearLeft[0], @@ -41,12 +41,12 @@ wpi::Protobuf::Unpack(InputStream& stream) { }; } -bool wpi::Protobuf::Pack( - OutputStream& stream, const frc::MecanumDriveKinematics& value) { - wpi::PackCallback frontLeft{&value.GetFrontLeft()}; - wpi::PackCallback frontRight{&value.GetFrontRight()}; - wpi::PackCallback rearLeft{&value.GetRearLeft()}; - wpi::PackCallback rearRight{&value.GetRearRight()}; +bool wpi::util::Protobuf::Pack( + OutputStream& stream, const wpi::math::MecanumDriveKinematics& value) { + wpi::util::PackCallback frontLeft{&value.GetFrontLeft()}; + wpi::util::PackCallback frontRight{&value.GetFrontRight()}; + wpi::util::PackCallback rearLeft{&value.GetRearLeft()}; + wpi::util::PackCallback rearRight{&value.GetRearRight()}; wpi_proto_ProtobufMecanumDriveKinematics msg{ .front_left = frontLeft.Callback(), .front_right = frontRight.Callback(), diff --git a/wpimath/src/main/native/cpp/kinematics/proto/MecanumDriveWheelPositionsProto.cpp b/wpimath/src/main/native/cpp/kinematics/proto/MecanumDriveWheelPositionsProto.cpp index d0b487c697..e08446f2e3 100644 --- a/wpimath/src/main/native/cpp/kinematics/proto/MecanumDriveWheelPositionsProto.cpp +++ b/wpimath/src/main/native/cpp/kinematics/proto/MecanumDriveWheelPositionsProto.cpp @@ -6,23 +6,23 @@ #include "wpimath/protobuf/kinematics.npb.h" -std::optional -wpi::Protobuf::Unpack(InputStream& stream) { +std::optional +wpi::util::Protobuf::Unpack(InputStream& stream) { wpi_proto_ProtobufMecanumDriveWheelPositions msg; if (!stream.Decode(msg)) { return {}; } - return frc::MecanumDriveWheelPositions{ - units::meter_t{msg.front_left}, - units::meter_t{msg.front_right}, - units::meter_t{msg.rear_left}, - units::meter_t{msg.rear_right}, + return wpi::math::MecanumDriveWheelPositions{ + wpi::units::meter_t{msg.front_left}, + wpi::units::meter_t{msg.front_right}, + wpi::units::meter_t{msg.rear_left}, + wpi::units::meter_t{msg.rear_right}, }; } -bool wpi::Protobuf::Pack( - OutputStream& stream, const frc::MecanumDriveWheelPositions& value) { +bool wpi::util::Protobuf::Pack( + OutputStream& stream, const wpi::math::MecanumDriveWheelPositions& value) { wpi_proto_ProtobufMecanumDriveWheelPositions msg{ .front_left = value.frontLeft.value(), .front_right = value.frontRight.value(), diff --git a/wpimath/src/main/native/cpp/kinematics/proto/MecanumDriveWheelSpeedsProto.cpp b/wpimath/src/main/native/cpp/kinematics/proto/MecanumDriveWheelSpeedsProto.cpp index 9e9fdb4f55..cd74d84bc1 100644 --- a/wpimath/src/main/native/cpp/kinematics/proto/MecanumDriveWheelSpeedsProto.cpp +++ b/wpimath/src/main/native/cpp/kinematics/proto/MecanumDriveWheelSpeedsProto.cpp @@ -6,23 +6,23 @@ #include "wpimath/protobuf/kinematics.npb.h" -std::optional -wpi::Protobuf::Unpack(InputStream& stream) { +std::optional +wpi::util::Protobuf::Unpack(InputStream& stream) { wpi_proto_ProtobufMecanumDriveWheelSpeeds msg; if (!stream.Decode(msg)) { return {}; } - return frc::MecanumDriveWheelSpeeds{ - units::meters_per_second_t{msg.front_left}, - units::meters_per_second_t{msg.front_right}, - units::meters_per_second_t{msg.rear_left}, - units::meters_per_second_t{msg.rear_right}, + return wpi::math::MecanumDriveWheelSpeeds{ + wpi::units::meters_per_second_t{msg.front_left}, + wpi::units::meters_per_second_t{msg.front_right}, + wpi::units::meters_per_second_t{msg.rear_left}, + wpi::units::meters_per_second_t{msg.rear_right}, }; } -bool wpi::Protobuf::Pack( - OutputStream& stream, const frc::MecanumDriveWheelSpeeds& value) { +bool wpi::util::Protobuf::Pack( + OutputStream& stream, const wpi::math::MecanumDriveWheelSpeeds& value) { wpi_proto_ProtobufMecanumDriveWheelSpeeds msg{ .front_left = value.frontLeft.value(), .front_right = value.frontRight.value(), diff --git a/wpimath/src/main/native/cpp/kinematics/proto/SwerveModulePositionProto.cpp b/wpimath/src/main/native/cpp/kinematics/proto/SwerveModulePositionProto.cpp index cba4492cd7..05aae69ef2 100644 --- a/wpimath/src/main/native/cpp/kinematics/proto/SwerveModulePositionProto.cpp +++ b/wpimath/src/main/native/cpp/kinematics/proto/SwerveModulePositionProto.cpp @@ -7,9 +7,9 @@ #include "wpi/util/protobuf/ProtobufCallbacks.hpp" #include "wpimath/protobuf/kinematics.npb.h" -std::optional -wpi::Protobuf::Unpack(InputStream& stream) { - wpi::UnpackCallback angle; +std::optional +wpi::util::Protobuf::Unpack(InputStream& stream) { + wpi::util::UnpackCallback angle; wpi_proto_ProtobufSwerveModulePosition msg{ .distance = 0, .angle = angle.Callback(), @@ -24,15 +24,15 @@ wpi::Protobuf::Unpack(InputStream& stream) { return {}; } - return frc::SwerveModulePosition{ - units::meter_t{msg.distance}, + return wpi::math::SwerveModulePosition{ + wpi::units::meter_t{msg.distance}, iangle[0], }; } -bool wpi::Protobuf::Pack( - OutputStream& stream, const frc::SwerveModulePosition& value) { - wpi::PackCallback angle{&value.angle}; +bool wpi::util::Protobuf::Pack( + OutputStream& stream, const wpi::math::SwerveModulePosition& value) { + wpi::util::PackCallback angle{&value.angle}; wpi_proto_ProtobufSwerveModulePosition msg{ .distance = value.distance.value(), .angle = angle.Callback(), diff --git a/wpimath/src/main/native/cpp/kinematics/proto/SwerveModuleStateProto.cpp b/wpimath/src/main/native/cpp/kinematics/proto/SwerveModuleStateProto.cpp index 31de39e996..c320ee6efc 100644 --- a/wpimath/src/main/native/cpp/kinematics/proto/SwerveModuleStateProto.cpp +++ b/wpimath/src/main/native/cpp/kinematics/proto/SwerveModuleStateProto.cpp @@ -7,9 +7,9 @@ #include "wpi/util/protobuf/ProtobufCallbacks.hpp" #include "wpimath/protobuf/kinematics.npb.h" -std::optional -wpi::Protobuf::Unpack(InputStream& stream) { - wpi::UnpackCallback angle; +std::optional +wpi::util::Protobuf::Unpack(InputStream& stream) { + wpi::util::UnpackCallback angle; wpi_proto_ProtobufSwerveModuleState msg{ .speed = 0, .angle = angle.Callback(), @@ -24,15 +24,15 @@ wpi::Protobuf::Unpack(InputStream& stream) { return {}; } - return frc::SwerveModuleState{ - units::meters_per_second_t{msg.speed}, + return wpi::math::SwerveModuleState{ + wpi::units::meters_per_second_t{msg.speed}, iangle[0], }; } -bool wpi::Protobuf::Pack( - OutputStream& stream, const frc::SwerveModuleState& value) { - wpi::PackCallback angle{&value.angle}; +bool wpi::util::Protobuf::Pack( + OutputStream& stream, const wpi::math::SwerveModuleState& value) { + wpi::util::PackCallback angle{&value.angle}; wpi_proto_ProtobufSwerveModuleState msg{ .speed = value.speed.value(), .angle = angle.Callback(), diff --git a/wpimath/src/main/native/cpp/kinematics/struct/ChassisSpeedsStruct.cpp b/wpimath/src/main/native/cpp/kinematics/struct/ChassisSpeedsStruct.cpp index 46160e6674..1a1b97ea0c 100644 --- a/wpimath/src/main/native/cpp/kinematics/struct/ChassisSpeedsStruct.cpp +++ b/wpimath/src/main/native/cpp/kinematics/struct/ChassisSpeedsStruct.cpp @@ -10,19 +10,19 @@ constexpr size_t kVyOff = kVxOff + 8; constexpr size_t kOmegaOff = kVyOff + 8; } // namespace -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; -frc::ChassisSpeeds StructType::Unpack(std::span data) { - return frc::ChassisSpeeds{ - units::meters_per_second_t{wpi::UnpackStruct(data)}, - units::meters_per_second_t{wpi::UnpackStruct(data)}, - units::radians_per_second_t{wpi::UnpackStruct(data)}, +wpi::math::ChassisSpeeds StructType::Unpack(std::span data) { + return wpi::math::ChassisSpeeds{ + wpi::units::meters_per_second_t{wpi::util::UnpackStruct(data)}, + wpi::units::meters_per_second_t{wpi::util::UnpackStruct(data)}, + wpi::units::radians_per_second_t{wpi::util::UnpackStruct(data)}, }; } void StructType::Pack(std::span data, - const frc::ChassisSpeeds& value) { - wpi::PackStruct(data, value.vx.value()); - wpi::PackStruct(data, value.vy.value()); - wpi::PackStruct(data, value.omega.value()); + const wpi::math::ChassisSpeeds& value) { + wpi::util::PackStruct(data, value.vx.value()); + wpi::util::PackStruct(data, value.vy.value()); + wpi::util::PackStruct(data, value.omega.value()); } diff --git a/wpimath/src/main/native/cpp/kinematics/struct/DifferentialDriveKinematicsStruct.cpp b/wpimath/src/main/native/cpp/kinematics/struct/DifferentialDriveKinematicsStruct.cpp index 570157ad36..f2bdeb8410 100644 --- a/wpimath/src/main/native/cpp/kinematics/struct/DifferentialDriveKinematicsStruct.cpp +++ b/wpimath/src/main/native/cpp/kinematics/struct/DifferentialDriveKinematicsStruct.cpp @@ -8,16 +8,16 @@ namespace { constexpr size_t kTrackwidthOff = 0; } // namespace -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; -frc::DifferentialDriveKinematics StructType::Unpack( +wpi::math::DifferentialDriveKinematics StructType::Unpack( std::span data) { - return frc::DifferentialDriveKinematics{ - units::meter_t{wpi::UnpackStruct(data)}, + return wpi::math::DifferentialDriveKinematics{ + wpi::units::meter_t{wpi::util::UnpackStruct(data)}, }; } void StructType::Pack(std::span data, - const frc::DifferentialDriveKinematics& value) { - wpi::PackStruct(data, value.trackwidth.value()); + const wpi::math::DifferentialDriveKinematics& value) { + wpi::util::PackStruct(data, value.trackwidth.value()); } diff --git a/wpimath/src/main/native/cpp/kinematics/struct/DifferentialDriveWheelPositionsStruct.cpp b/wpimath/src/main/native/cpp/kinematics/struct/DifferentialDriveWheelPositionsStruct.cpp index 44807070a4..563df5a03d 100644 --- a/wpimath/src/main/native/cpp/kinematics/struct/DifferentialDriveWheelPositionsStruct.cpp +++ b/wpimath/src/main/native/cpp/kinematics/struct/DifferentialDriveWheelPositionsStruct.cpp @@ -9,18 +9,18 @@ constexpr size_t kLeftOff = 0; constexpr size_t kRightOff = kLeftOff + 8; } // namespace -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; -frc::DifferentialDriveWheelPositions StructType::Unpack( +wpi::math::DifferentialDriveWheelPositions StructType::Unpack( std::span data) { - return frc::DifferentialDriveWheelPositions{ - units::meter_t{wpi::UnpackStruct(data)}, - units::meter_t{wpi::UnpackStruct(data)}, + return wpi::math::DifferentialDriveWheelPositions{ + wpi::units::meter_t{wpi::util::UnpackStruct(data)}, + wpi::units::meter_t{wpi::util::UnpackStruct(data)}, }; } void StructType::Pack(std::span data, - const frc::DifferentialDriveWheelPositions& value) { - wpi::PackStruct(data, value.left.value()); - wpi::PackStruct(data, value.right.value()); + const wpi::math::DifferentialDriveWheelPositions& value) { + wpi::util::PackStruct(data, value.left.value()); + wpi::util::PackStruct(data, value.right.value()); } diff --git a/wpimath/src/main/native/cpp/kinematics/struct/DifferentialDriveWheelSpeedsStruct.cpp b/wpimath/src/main/native/cpp/kinematics/struct/DifferentialDriveWheelSpeedsStruct.cpp index a870c6c0e0..3d193bd6c8 100644 --- a/wpimath/src/main/native/cpp/kinematics/struct/DifferentialDriveWheelSpeedsStruct.cpp +++ b/wpimath/src/main/native/cpp/kinematics/struct/DifferentialDriveWheelSpeedsStruct.cpp @@ -9,18 +9,18 @@ constexpr size_t kLeftOff = 0; constexpr size_t kRightOff = kLeftOff + 8; } // namespace -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; -frc::DifferentialDriveWheelSpeeds StructType::Unpack( +wpi::math::DifferentialDriveWheelSpeeds StructType::Unpack( std::span data) { - return frc::DifferentialDriveWheelSpeeds{ - units::meters_per_second_t{wpi::UnpackStruct(data)}, - units::meters_per_second_t{wpi::UnpackStruct(data)}, + return wpi::math::DifferentialDriveWheelSpeeds{ + wpi::units::meters_per_second_t{wpi::util::UnpackStruct(data)}, + wpi::units::meters_per_second_t{wpi::util::UnpackStruct(data)}, }; } void StructType::Pack(std::span data, - const frc::DifferentialDriveWheelSpeeds& value) { - wpi::PackStruct(data, value.left.value()); - wpi::PackStruct(data, value.right.value()); + const wpi::math::DifferentialDriveWheelSpeeds& value) { + wpi::util::PackStruct(data, value.left.value()); + wpi::util::PackStruct(data, value.right.value()); } diff --git a/wpimath/src/main/native/cpp/kinematics/struct/MecanumDriveKinematicsStruct.cpp b/wpimath/src/main/native/cpp/kinematics/struct/MecanumDriveKinematicsStruct.cpp index 925af4ff3b..da1f6b987e 100644 --- a/wpimath/src/main/native/cpp/kinematics/struct/MecanumDriveKinematicsStruct.cpp +++ b/wpimath/src/main/native/cpp/kinematics/struct/MecanumDriveKinematicsStruct.cpp @@ -7,28 +7,28 @@ namespace { constexpr size_t kFrontLeftOff = 0; constexpr size_t kFrontRightOff = - kFrontLeftOff + wpi::GetStructSize(); + kFrontLeftOff + wpi::util::GetStructSize(); constexpr size_t kRearLeftOff = - kFrontRightOff + wpi::GetStructSize(); + kFrontRightOff + wpi::util::GetStructSize(); constexpr size_t kRearRightOff = - kRearLeftOff + wpi::GetStructSize(); + kRearLeftOff + wpi::util::GetStructSize(); } // namespace -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; -frc::MecanumDriveKinematics StructType::Unpack(std::span data) { - return frc::MecanumDriveKinematics{ - wpi::UnpackStruct(data), - wpi::UnpackStruct(data), - wpi::UnpackStruct(data), - wpi::UnpackStruct(data), +wpi::math::MecanumDriveKinematics StructType::Unpack(std::span data) { + return wpi::math::MecanumDriveKinematics{ + wpi::util::UnpackStruct(data), + wpi::util::UnpackStruct(data), + wpi::util::UnpackStruct(data), + wpi::util::UnpackStruct(data), }; } void StructType::Pack(std::span data, - const frc::MecanumDriveKinematics& value) { - wpi::PackStruct(data, value.GetFrontLeft()); - wpi::PackStruct(data, value.GetFrontRight()); - wpi::PackStruct(data, value.GetRearLeft()); - wpi::PackStruct(data, value.GetRearRight()); + const wpi::math::MecanumDriveKinematics& value) { + wpi::util::PackStruct(data, value.GetFrontLeft()); + wpi::util::PackStruct(data, value.GetFrontRight()); + wpi::util::PackStruct(data, value.GetRearLeft()); + wpi::util::PackStruct(data, value.GetRearRight()); } diff --git a/wpimath/src/main/native/cpp/kinematics/struct/MecanumDriveWheelPositionsStruct.cpp b/wpimath/src/main/native/cpp/kinematics/struct/MecanumDriveWheelPositionsStruct.cpp index 04b2bcf954..7c7c004fe7 100644 --- a/wpimath/src/main/native/cpp/kinematics/struct/MecanumDriveWheelPositionsStruct.cpp +++ b/wpimath/src/main/native/cpp/kinematics/struct/MecanumDriveWheelPositionsStruct.cpp @@ -11,22 +11,22 @@ constexpr size_t kRearLeftOff = kFrontRightOff + 8; constexpr size_t kRearRightOff = kRearLeftOff + 8; } // namespace -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; -frc::MecanumDriveWheelPositions StructType::Unpack( +wpi::math::MecanumDriveWheelPositions StructType::Unpack( std::span data) { - return frc::MecanumDriveWheelPositions{ - units::meter_t{wpi::UnpackStruct(data)}, - units::meter_t{wpi::UnpackStruct(data)}, - units::meter_t{wpi::UnpackStruct(data)}, - units::meter_t{wpi::UnpackStruct(data)}, + return wpi::math::MecanumDriveWheelPositions{ + wpi::units::meter_t{wpi::util::UnpackStruct(data)}, + wpi::units::meter_t{wpi::util::UnpackStruct(data)}, + wpi::units::meter_t{wpi::util::UnpackStruct(data)}, + wpi::units::meter_t{wpi::util::UnpackStruct(data)}, }; } void StructType::Pack(std::span data, - const frc::MecanumDriveWheelPositions& value) { - wpi::PackStruct(data, value.frontLeft.value()); - wpi::PackStruct(data, value.frontRight.value()); - wpi::PackStruct(data, value.rearLeft.value()); - wpi::PackStruct(data, value.rearRight.value()); + const wpi::math::MecanumDriveWheelPositions& value) { + wpi::util::PackStruct(data, value.frontLeft.value()); + wpi::util::PackStruct(data, value.frontRight.value()); + wpi::util::PackStruct(data, value.rearLeft.value()); + wpi::util::PackStruct(data, value.rearRight.value()); } diff --git a/wpimath/src/main/native/cpp/kinematics/struct/MecanumDriveWheelSpeedsStruct.cpp b/wpimath/src/main/native/cpp/kinematics/struct/MecanumDriveWheelSpeedsStruct.cpp index 48622e333b..1f4cd6ae6e 100644 --- a/wpimath/src/main/native/cpp/kinematics/struct/MecanumDriveWheelSpeedsStruct.cpp +++ b/wpimath/src/main/native/cpp/kinematics/struct/MecanumDriveWheelSpeedsStruct.cpp @@ -11,24 +11,24 @@ constexpr size_t kRearLeftOff = kFrontRightOff + 8; constexpr size_t kRearRightOff = kRearLeftOff + 8; } // namespace -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; -frc::MecanumDriveWheelSpeeds StructType::Unpack(std::span data) { - return frc::MecanumDriveWheelSpeeds{ - units::meters_per_second_t{ - wpi::UnpackStruct(data)}, - units::meters_per_second_t{ - wpi::UnpackStruct(data)}, - units::meters_per_second_t{wpi::UnpackStruct(data)}, - units::meters_per_second_t{ - wpi::UnpackStruct(data)}, +wpi::math::MecanumDriveWheelSpeeds StructType::Unpack(std::span data) { + return wpi::math::MecanumDriveWheelSpeeds{ + wpi::units::meters_per_second_t{ + wpi::util::UnpackStruct(data)}, + wpi::units::meters_per_second_t{ + wpi::util::UnpackStruct(data)}, + wpi::units::meters_per_second_t{wpi::util::UnpackStruct(data)}, + wpi::units::meters_per_second_t{ + wpi::util::UnpackStruct(data)}, }; } void StructType::Pack(std::span data, - const frc::MecanumDriveWheelSpeeds& value) { - wpi::PackStruct(data, value.frontLeft.value()); - wpi::PackStruct(data, value.frontRight.value()); - wpi::PackStruct(data, value.rearLeft.value()); - wpi::PackStruct(data, value.rearRight.value()); + const wpi::math::MecanumDriveWheelSpeeds& value) { + wpi::util::PackStruct(data, value.frontLeft.value()); + wpi::util::PackStruct(data, value.frontRight.value()); + wpi::util::PackStruct(data, value.rearLeft.value()); + wpi::util::PackStruct(data, value.rearRight.value()); } diff --git a/wpimath/src/main/native/cpp/kinematics/struct/SwerveModulePositionStruct.cpp b/wpimath/src/main/native/cpp/kinematics/struct/SwerveModulePositionStruct.cpp index 52a69e1d1b..22ed63d958 100644 --- a/wpimath/src/main/native/cpp/kinematics/struct/SwerveModulePositionStruct.cpp +++ b/wpimath/src/main/native/cpp/kinematics/struct/SwerveModulePositionStruct.cpp @@ -9,17 +9,17 @@ constexpr size_t kDistanceOff = 0; constexpr size_t kAngleOff = kDistanceOff + 8; } // namespace -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; -frc::SwerveModulePosition StructType::Unpack(std::span data) { - return frc::SwerveModulePosition{ - units::meter_t{wpi::UnpackStruct(data)}, - wpi::UnpackStruct(data), +wpi::math::SwerveModulePosition StructType::Unpack(std::span data) { + return wpi::math::SwerveModulePosition{ + wpi::units::meter_t{wpi::util::UnpackStruct(data)}, + wpi::util::UnpackStruct(data), }; } void StructType::Pack(std::span data, - const frc::SwerveModulePosition& value) { - wpi::PackStruct(data, value.distance.value()); - wpi::PackStruct(data, value.angle); + const wpi::math::SwerveModulePosition& value) { + wpi::util::PackStruct(data, value.distance.value()); + wpi::util::PackStruct(data, value.angle); } diff --git a/wpimath/src/main/native/cpp/kinematics/struct/SwerveModuleStateStruct.cpp b/wpimath/src/main/native/cpp/kinematics/struct/SwerveModuleStateStruct.cpp index ca64f4315a..26c7a6c008 100644 --- a/wpimath/src/main/native/cpp/kinematics/struct/SwerveModuleStateStruct.cpp +++ b/wpimath/src/main/native/cpp/kinematics/struct/SwerveModuleStateStruct.cpp @@ -9,17 +9,17 @@ constexpr size_t kSpeedOff = 0; constexpr size_t kAngleOff = kSpeedOff + 8; } // namespace -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; -frc::SwerveModuleState StructType::Unpack(std::span data) { - return frc::SwerveModuleState{ - units::meters_per_second_t{wpi::UnpackStruct(data)}, - wpi::UnpackStruct(data), +wpi::math::SwerveModuleState StructType::Unpack(std::span data) { + return wpi::math::SwerveModuleState{ + wpi::units::meters_per_second_t{wpi::util::UnpackStruct(data)}, + wpi::util::UnpackStruct(data), }; } void StructType::Pack(std::span data, - const frc::SwerveModuleState& value) { - wpi::PackStruct(data, value.speed.value()); - wpi::PackStruct(data, value.angle); + const wpi::math::SwerveModuleState& value) { + wpi::util::PackStruct(data, value.speed.value()); + wpi::util::PackStruct(data, value.angle); } diff --git a/wpimath/src/main/native/cpp/spline/proto/CubicHermiteSplineProto.cpp b/wpimath/src/main/native/cpp/spline/proto/CubicHermiteSplineProto.cpp index 8e62cb1dbf..48882b9365 100644 --- a/wpimath/src/main/native/cpp/spline/proto/CubicHermiteSplineProto.cpp +++ b/wpimath/src/main/native/cpp/spline/proto/CubicHermiteSplineProto.cpp @@ -7,12 +7,12 @@ #include "wpi/util/protobuf/ProtobufCallbacks.hpp" #include "wpimath/protobuf/spline.npb.h" -std::optional -wpi::Protobuf::Unpack(InputStream& stream) { - wpi::WpiArrayUnpackCallback xInitial; - wpi::WpiArrayUnpackCallback xFinal; - wpi::WpiArrayUnpackCallback yInitial; - wpi::WpiArrayUnpackCallback yFinal; +std::optional +wpi::util::Protobuf::Unpack(InputStream& stream) { + wpi::util::WpiArrayUnpackCallback xInitial; + wpi::util::WpiArrayUnpackCallback xFinal; + wpi::util::WpiArrayUnpackCallback yInitial; + wpi::util::WpiArrayUnpackCallback yFinal; wpi_proto_ProtobufCubicHermiteSpline msg{ .x_initial = xInitial.Callback(), .x_final = xFinal.Callback(), @@ -28,7 +28,7 @@ wpi::Protobuf::Unpack(InputStream& stream) { return {}; } - return frc::CubicHermiteSpline{ + return wpi::math::CubicHermiteSpline{ xInitial.Array(), xFinal.Array(), yInitial.Array(), @@ -36,12 +36,12 @@ wpi::Protobuf::Unpack(InputStream& stream) { }; } -bool wpi::Protobuf::Pack( - OutputStream& stream, const frc::CubicHermiteSpline& value) { - wpi::PackCallback xInitial{value.GetInitialControlVector().x}; - wpi::PackCallback xFinal{value.GetFinalControlVector().x}; - wpi::PackCallback yInitial{value.GetInitialControlVector().y}; - wpi::PackCallback yFinal{value.GetFinalControlVector().y}; +bool wpi::util::Protobuf::Pack( + OutputStream& stream, const wpi::math::CubicHermiteSpline& value) { + wpi::util::PackCallback xInitial{value.GetInitialControlVector().x}; + wpi::util::PackCallback xFinal{value.GetFinalControlVector().x}; + wpi::util::PackCallback yInitial{value.GetInitialControlVector().y}; + wpi::util::PackCallback yFinal{value.GetFinalControlVector().y}; wpi_proto_ProtobufCubicHermiteSpline msg{ .x_initial = xInitial.Callback(), .x_final = xFinal.Callback(), diff --git a/wpimath/src/main/native/cpp/spline/proto/QuinticHermiteSplineProto.cpp b/wpimath/src/main/native/cpp/spline/proto/QuinticHermiteSplineProto.cpp index 5112cd555f..8f4fead901 100644 --- a/wpimath/src/main/native/cpp/spline/proto/QuinticHermiteSplineProto.cpp +++ b/wpimath/src/main/native/cpp/spline/proto/QuinticHermiteSplineProto.cpp @@ -7,12 +7,12 @@ #include "wpi/util/protobuf/ProtobufCallbacks.hpp" #include "wpimath/protobuf/spline.npb.h" -std::optional -wpi::Protobuf::Unpack(InputStream& stream) { - wpi::WpiArrayUnpackCallback xInitial; - wpi::WpiArrayUnpackCallback xFinal; - wpi::WpiArrayUnpackCallback yInitial; - wpi::WpiArrayUnpackCallback yFinal; +std::optional +wpi::util::Protobuf::Unpack(InputStream& stream) { + wpi::util::WpiArrayUnpackCallback xInitial; + wpi::util::WpiArrayUnpackCallback xFinal; + wpi::util::WpiArrayUnpackCallback yInitial; + wpi::util::WpiArrayUnpackCallback yFinal; wpi_proto_ProtobufQuinticHermiteSpline msg{ .x_initial = xInitial.Callback(), .x_final = xFinal.Callback(), @@ -28,7 +28,7 @@ wpi::Protobuf::Unpack(InputStream& stream) { return {}; } - return frc::QuinticHermiteSpline{ + return wpi::math::QuinticHermiteSpline{ xInitial.Array(), xFinal.Array(), yInitial.Array(), @@ -36,12 +36,12 @@ wpi::Protobuf::Unpack(InputStream& stream) { }; } -bool wpi::Protobuf::Pack( - OutputStream& stream, const frc::QuinticHermiteSpline& value) { - wpi::PackCallback xInitial{value.GetInitialControlVector().x}; - wpi::PackCallback xFinal{value.GetFinalControlVector().x}; - wpi::PackCallback yInitial{value.GetInitialControlVector().y}; - wpi::PackCallback yFinal{value.GetFinalControlVector().y}; +bool wpi::util::Protobuf::Pack( + OutputStream& stream, const wpi::math::QuinticHermiteSpline& value) { + wpi::util::PackCallback xInitial{value.GetInitialControlVector().x}; + wpi::util::PackCallback xFinal{value.GetFinalControlVector().x}; + wpi::util::PackCallback yInitial{value.GetInitialControlVector().y}; + wpi::util::PackCallback yFinal{value.GetFinalControlVector().y}; wpi_proto_ProtobufQuinticHermiteSpline msg{ .x_initial = xInitial.Callback(), .x_final = xFinal.Callback(), diff --git a/wpimath/src/main/native/cpp/spline/struct/CubicHermiteSplineStruct.cpp b/wpimath/src/main/native/cpp/spline/struct/CubicHermiteSplineStruct.cpp index fb4817cac5..58674b45cb 100644 --- a/wpimath/src/main/native/cpp/spline/struct/CubicHermiteSplineStruct.cpp +++ b/wpimath/src/main/native/cpp/spline/struct/CubicHermiteSplineStruct.cpp @@ -11,21 +11,21 @@ constexpr size_t kYInitialOff = kXFinalOff + 2 * 8; constexpr size_t kYFinalOff = kYInitialOff + 2 * 8; } // namespace -frc::CubicHermiteSpline wpi::Struct::Unpack( +wpi::math::CubicHermiteSpline wpi::util::Struct::Unpack( std::span data) { - return frc::CubicHermiteSpline{ - wpi::UnpackStructArray(data), - wpi::UnpackStructArray(data), - wpi::UnpackStructArray(data), - wpi::UnpackStructArray(data)}; + return wpi::math::CubicHermiteSpline{ + wpi::util::UnpackStructArray(data), + wpi::util::UnpackStructArray(data), + wpi::util::UnpackStructArray(data), + wpi::util::UnpackStructArray(data)}; } -void wpi::Struct::Pack( - std::span data, const frc::CubicHermiteSpline& value) { - wpi::PackStructArray(data, +void wpi::util::Struct::Pack( + std::span data, const wpi::math::CubicHermiteSpline& value) { + wpi::util::PackStructArray(data, value.GetInitialControlVector().x); - wpi::PackStructArray(data, value.GetFinalControlVector().x); - wpi::PackStructArray(data, + wpi::util::PackStructArray(data, value.GetFinalControlVector().x); + wpi::util::PackStructArray(data, value.GetInitialControlVector().y); - wpi::PackStructArray(data, value.GetFinalControlVector().y); + wpi::util::PackStructArray(data, value.GetFinalControlVector().y); } diff --git a/wpimath/src/main/native/cpp/spline/struct/QuinticHermiteSplineStruct.cpp b/wpimath/src/main/native/cpp/spline/struct/QuinticHermiteSplineStruct.cpp index e03be9f2e6..057b2dad89 100644 --- a/wpimath/src/main/native/cpp/spline/struct/QuinticHermiteSplineStruct.cpp +++ b/wpimath/src/main/native/cpp/spline/struct/QuinticHermiteSplineStruct.cpp @@ -11,21 +11,21 @@ constexpr size_t kYInitialOff = kXFinalOff + 3 * 8; constexpr size_t kYFinalOff = kYInitialOff + 3 * 8; } // namespace -frc::QuinticHermiteSpline wpi::Struct::Unpack( +wpi::math::QuinticHermiteSpline wpi::util::Struct::Unpack( std::span data) { - return frc::QuinticHermiteSpline{ - wpi::UnpackStructArray(data), - wpi::UnpackStructArray(data), - wpi::UnpackStructArray(data), - wpi::UnpackStructArray(data)}; + return wpi::math::QuinticHermiteSpline{ + wpi::util::UnpackStructArray(data), + wpi::util::UnpackStructArray(data), + wpi::util::UnpackStructArray(data), + wpi::util::UnpackStructArray(data)}; } -void wpi::Struct::Pack( - std::span data, const frc::QuinticHermiteSpline& value) { - wpi::PackStructArray(data, +void wpi::util::Struct::Pack( + std::span data, const wpi::math::QuinticHermiteSpline& value) { + wpi::util::PackStructArray(data, value.GetInitialControlVector().x); - wpi::PackStructArray(data, value.GetFinalControlVector().x); - wpi::PackStructArray(data, + wpi::util::PackStructArray(data, value.GetFinalControlVector().x); + wpi::util::PackStructArray(data, value.GetInitialControlVector().y); - wpi::PackStructArray(data, value.GetFinalControlVector().y); + wpi::util::PackStructArray(data, value.GetFinalControlVector().y); } diff --git a/wpimath/src/main/native/cpp/system/LinearSystemLoop.cpp b/wpimath/src/main/native/cpp/system/LinearSystemLoop.cpp index 213b00f5a8..10fd30bf01 100644 --- a/wpimath/src/main/native/cpp/system/LinearSystemLoop.cpp +++ b/wpimath/src/main/native/cpp/system/LinearSystemLoop.cpp @@ -4,11 +4,11 @@ #include "wpi/math/system/LinearSystemLoop.hpp" -namespace frc { +namespace wpi::math { template class EXPORT_TEMPLATE_DEFINE(WPILIB_DLLEXPORT) LinearSystemLoop<1, 1, 1>; template class EXPORT_TEMPLATE_DEFINE(WPILIB_DLLEXPORT) LinearSystemLoop<2, 1, 1>; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/cpp/system/plant/proto/DCMotorProto.cpp b/wpimath/src/main/native/cpp/system/plant/proto/DCMotorProto.cpp index de5bd5596e..6637c6a467 100644 --- a/wpimath/src/main/native/cpp/system/plant/proto/DCMotorProto.cpp +++ b/wpimath/src/main/native/cpp/system/plant/proto/DCMotorProto.cpp @@ -8,24 +8,24 @@ #include "wpimath/protobuf/plant.npb.h" -std::optional wpi::Protobuf::Unpack( +std::optional wpi::util::Protobuf::Unpack( InputStream& stream) { wpi_proto_ProtobufDCMotor msg; if (!stream.Decode(msg)) { return {}; } - return frc::DCMotor{ - units::volt_t{msg.nominal_voltage}, - units::newton_meter_t{msg.stall_torque}, - units::ampere_t{msg.stall_current}, - units::ampere_t{msg.free_current}, - units::radians_per_second_t{msg.free_speed}, + return wpi::math::DCMotor{ + wpi::units::volt_t{msg.nominal_voltage}, + wpi::units::newton_meter_t{msg.stall_torque}, + wpi::units::ampere_t{msg.stall_current}, + wpi::units::ampere_t{msg.free_current}, + wpi::units::radians_per_second_t{msg.free_speed}, }; } -bool wpi::Protobuf::Pack(OutputStream& stream, - const frc::DCMotor& value) { +bool wpi::util::Protobuf::Pack(OutputStream& stream, + const wpi::math::DCMotor& value) { wpi_proto_ProtobufDCMotor msg{ .nominal_voltage = value.nominalVoltage.value(), .stall_torque = value.stallTorque.value(), diff --git a/wpimath/src/main/native/cpp/system/plant/struct/DCMotorStruct.cpp b/wpimath/src/main/native/cpp/system/plant/struct/DCMotorStruct.cpp index 8ba75c7bfa..8cccad71b2 100644 --- a/wpimath/src/main/native/cpp/system/plant/struct/DCMotorStruct.cpp +++ b/wpimath/src/main/native/cpp/system/plant/struct/DCMotorStruct.cpp @@ -12,23 +12,23 @@ constexpr size_t kFreeCurrentOff = kStallCurrentOff + 8; constexpr size_t kFreeSpeedOff = kFreeCurrentOff + 8; } // namespace -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; -frc::DCMotor StructType::Unpack(std::span data) { - return frc::DCMotor{ - units::volt_t{wpi::UnpackStruct(data)}, - units::newton_meter_t{wpi::UnpackStruct(data)}, - units::ampere_t{wpi::UnpackStruct(data)}, - units::ampere_t{wpi::UnpackStruct(data)}, - units::radians_per_second_t{ - wpi::UnpackStruct(data)}, +wpi::math::DCMotor StructType::Unpack(std::span data) { + return wpi::math::DCMotor{ + wpi::units::volt_t{wpi::util::UnpackStruct(data)}, + wpi::units::newton_meter_t{wpi::util::UnpackStruct(data)}, + wpi::units::ampere_t{wpi::util::UnpackStruct(data)}, + wpi::units::ampere_t{wpi::util::UnpackStruct(data)}, + wpi::units::radians_per_second_t{ + wpi::util::UnpackStruct(data)}, }; } -void StructType::Pack(std::span data, const frc::DCMotor& value) { - wpi::PackStruct(data, value.nominalVoltage.value()); - wpi::PackStruct(data, value.stallTorque.value()); - wpi::PackStruct(data, value.stallCurrent.value()); - wpi::PackStruct(data, value.freeCurrent.value()); - wpi::PackStruct(data, value.freeSpeed.value()); +void StructType::Pack(std::span data, const wpi::math::DCMotor& value) { + wpi::util::PackStruct(data, value.nominalVoltage.value()); + wpi::util::PackStruct(data, value.stallTorque.value()); + wpi::util::PackStruct(data, value.stallCurrent.value()); + wpi::util::PackStruct(data, value.freeCurrent.value()); + wpi::util::PackStruct(data, value.freeSpeed.value()); } diff --git a/wpimath/src/main/native/cpp/trajectory/Trajectory.cpp b/wpimath/src/main/native/cpp/trajectory/Trajectory.cpp index 6d84b81bb2..4b38834c2d 100644 --- a/wpimath/src/main/native/cpp/trajectory/Trajectory.cpp +++ b/wpimath/src/main/native/cpp/trajectory/Trajectory.cpp @@ -6,22 +6,22 @@ #include "wpi/util/json.hpp" -using namespace frc; +using namespace wpi::math; -void frc::to_json(wpi::json& json, const Trajectory::State& state) { - json = wpi::json{{"time", state.t.value()}, +void wpi::math::to_json(wpi::util::json& json, const Trajectory::State& state) { + json = wpi::util::json{{"time", state.t.value()}, {"velocity", state.velocity.value()}, {"acceleration", state.acceleration.value()}, {"pose", state.pose}, {"curvature", state.curvature.value()}}; } -void frc::from_json(const wpi::json& json, Trajectory::State& state) { +void wpi::math::from_json(const wpi::util::json& json, Trajectory::State& state) { state.pose = json.at("pose").get(); - state.t = units::second_t{json.at("time").get()}; + state.t = wpi::units::second_t{json.at("time").get()}; state.velocity = - units::meters_per_second_t{json.at("velocity").get()}; + wpi::units::meters_per_second_t{json.at("velocity").get()}; state.acceleration = - units::meters_per_second_squared_t{json.at("acceleration").get()}; - state.curvature = units::curvature_t{json.at("curvature").get()}; + wpi::units::meters_per_second_squared_t{json.at("acceleration").get()}; + state.curvature = wpi::units::curvature_t{json.at("curvature").get()}; } diff --git a/wpimath/src/main/native/cpp/trajectory/TrajectoryGenerator.cpp b/wpimath/src/main/native/cpp/trajectory/TrajectoryGenerator.cpp index 678fec2789..31ef5aa8a0 100644 --- a/wpimath/src/main/native/cpp/trajectory/TrajectoryGenerator.cpp +++ b/wpimath/src/main/native/cpp/trajectory/TrajectoryGenerator.cpp @@ -12,7 +12,7 @@ #include "wpi/math/trajectory/TrajectoryParameterizer.hpp" #include "wpi/util/print.hpp" -using namespace frc; +using namespace wpi::math; const Trajectory TrajectoryGenerator::kDoNothingTrajectory( std::vector{Trajectory::State()}); @@ -22,7 +22,7 @@ void TrajectoryGenerator::ReportError(const char* error) { if (s_errorFunc) { s_errorFunc(error); } else { - wpi::print(stderr, "TrajectoryGenerator error: {}\n", error); + wpi::util::print(stderr, "TrajectoryGenerator error: {}\n", error); } } @@ -41,7 +41,7 @@ Trajectory TrajectoryGenerator::GenerateTrajectory( end.y[1] *= -1; } - std::vector points; + std::vector points; try { points = SplinePointsFromSplines(SplineHelper::CubicSplinesFromControlVectors( @@ -86,7 +86,7 @@ Trajectory TrajectoryGenerator::GenerateTrajectory( } } - std::vector points; + std::vector points; try { points = SplinePointsFromSplines( SplineHelper::QuinticSplinesFromControlVectors(controlVectors)); diff --git a/wpimath/src/main/native/cpp/trajectory/TrajectoryParameterizer.cpp b/wpimath/src/main/native/cpp/trajectory/TrajectoryParameterizer.cpp index 5d981aeba8..6a275ab325 100644 --- a/wpimath/src/main/native/cpp/trajectory/TrajectoryParameterizer.cpp +++ b/wpimath/src/main/native/cpp/trajectory/TrajectoryParameterizer.cpp @@ -34,15 +34,15 @@ #include "wpi/units/math.hpp" -using namespace frc; +using namespace wpi::math; Trajectory TrajectoryParameterizer::TimeParameterizeTrajectory( const std::vector& points, const std::vector>& constraints, - units::meters_per_second_t startVelocity, - units::meters_per_second_t endVelocity, - units::meters_per_second_t maxVelocity, - units::meters_per_second_squared_t maxAcceleration, bool reversed) { + wpi::units::meters_per_second_t startVelocity, + wpi::units::meters_per_second_t endVelocity, + wpi::units::meters_per_second_t maxVelocity, + wpi::units::meters_per_second_squared_t maxAcceleration, bool reversed) { std::vector constrainedStates(points.size()); ConstrainedState predecessor{points.front(), 0_m, startVelocity, @@ -56,7 +56,7 @@ Trajectory TrajectoryParameterizer::TimeParameterizeTrajectory( constrainedState.pose = points[i]; // Begin constraining based on predecessor - units::meter_t ds = constrainedState.pose.first.Translation().Distance( + wpi::units::meter_t ds = constrainedState.pose.first.Translation().Distance( predecessor.pose.first.Translation()); constrainedState.distance = ds + predecessor.distance; @@ -66,9 +66,9 @@ Trajectory TrajectoryParameterizer::TimeParameterizeTrajectory( // Enforce global max velocity and max reachable velocity by global // acceleration limit. v_f = √(v_i² + 2ad). - constrainedState.maxVelocity = units::math::min( + constrainedState.maxVelocity = wpi::units::math::min( maxVelocity, - units::math::sqrt(predecessor.maxVelocity * predecessor.maxVelocity + + wpi::units::math::sqrt(predecessor.maxVelocity * predecessor.maxVelocity + predecessor.maxAcceleration * ds * 2.0)); constrainedState.minAcceleration = -maxAcceleration; @@ -77,7 +77,7 @@ Trajectory TrajectoryParameterizer::TimeParameterizeTrajectory( // At this point, the constrained state is fully constructed apart from // all the custom-defined user constraints. for (const auto& constraint : constraints) { - constrainedState.maxVelocity = units::math::min( + constrainedState.maxVelocity = wpi::units::math::min( constrainedState.maxVelocity, constraint->MaxVelocity(constrainedState.pose.first, constrainedState.pose.second, @@ -94,7 +94,7 @@ Trajectory TrajectoryParameterizer::TimeParameterizeTrajectory( // If the actual acceleration for this state is higher than the max // acceleration that we applied, then we need to reduce the max // acceleration of the predecessor and try again. - units::meters_per_second_squared_t actualAcceleration = + wpi::units::meters_per_second_squared_t actualAcceleration = (constrainedState.maxVelocity * constrainedState.maxVelocity - predecessor.maxVelocity * predecessor.maxVelocity) / (ds * 2.0); @@ -123,14 +123,14 @@ Trajectory TrajectoryParameterizer::TimeParameterizeTrajectory( // Backward pass for (int i = points.size() - 1; i >= 0; i--) { auto& constrainedState = constrainedStates[i]; - units::meter_t ds = + wpi::units::meter_t ds = constrainedState.distance - successor.distance; // negative while (true) { // Enforce max velocity limit (reverse) // v_f = √(v_i² + 2ad), where v_i = successor. - units::meters_per_second_t newMaxVelocity = - units::math::sqrt(successor.maxVelocity * successor.maxVelocity + + wpi::units::meters_per_second_t newMaxVelocity = + wpi::units::math::sqrt(successor.maxVelocity * successor.maxVelocity + successor.minAcceleration * ds * 2.0); // No more limits to impose! This state can be finalized. @@ -150,7 +150,7 @@ Trajectory TrajectoryParameterizer::TimeParameterizeTrajectory( // If the actual acceleration for this state is lower than the min // acceleration, then we need to lower the min acceleration of the // successor and try again. - units::meters_per_second_squared_t actualAcceleration = + wpi::units::meters_per_second_squared_t actualAcceleration = (constrainedState.maxVelocity * constrainedState.maxVelocity - successor.maxVelocity * successor.maxVelocity) / (ds * 2.0); @@ -168,30 +168,30 @@ Trajectory TrajectoryParameterizer::TimeParameterizeTrajectory( // trajectory states. std::vector states(points.size()); - units::second_t t = 0_s; - units::meter_t s = 0_m; - units::meters_per_second_t v = 0_mps; + wpi::units::second_t t = 0_s; + wpi::units::meter_t s = 0_m; + wpi::units::meters_per_second_t v = 0_mps; for (unsigned int i = 0; i < constrainedStates.size(); i++) { auto state = constrainedStates[i]; // Calculate the change in position between the current state and the // previous state. - units::meter_t ds = state.distance - s; + wpi::units::meter_t ds = state.distance - s; // Calculate the acceleration between the current state and the previous // state. - units::meters_per_second_squared_t accel = + wpi::units::meters_per_second_squared_t accel = (state.maxVelocity * state.maxVelocity - v * v) / (ds * 2); // Calculate dt. - units::second_t dt = 0_s; + wpi::units::second_t dt = 0_s; if (i > 0) { states.at(i - 1).acceleration = reversed ? -accel : accel; - if (units::math::abs(accel) > 1E-6_mps_sq) { + if (wpi::units::math::abs(accel) > 1E-6_mps_sq) { // v_f = v_0 + at dt = (state.maxVelocity - v) / accel; - } else if (units::math::abs(v) > 1E-6_mps) { + } else if (wpi::units::math::abs(v) > 1E-6_mps) { // delta_x = vt dt = ds / v; } else { @@ -230,11 +230,11 @@ void TrajectoryParameterizer::EnforceAccelerationLimits( "back one-by-one."); } - state->minAcceleration = units::math::max( + state->minAcceleration = wpi::units::math::max( state->minAcceleration, reverse ? -minMaxAccel.maxAcceleration : minMaxAccel.minAcceleration); - state->maxAcceleration = units::math::min( + state->maxAcceleration = wpi::units::math::min( state->maxAcceleration, reverse ? -minMaxAccel.minAcceleration : minMaxAccel.maxAcceleration); } diff --git a/wpimath/src/main/native/cpp/trajectory/proto/TrajectoryProto.cpp b/wpimath/src/main/native/cpp/trajectory/proto/TrajectoryProto.cpp index 3853a3f12d..5e0c478a48 100644 --- a/wpimath/src/main/native/cpp/trajectory/proto/TrajectoryProto.cpp +++ b/wpimath/src/main/native/cpp/trajectory/proto/TrajectoryProto.cpp @@ -9,9 +9,9 @@ #include "wpi/util/protobuf/ProtobufCallbacks.hpp" #include "wpimath/protobuf/trajectory.npb.h" -std::optional wpi::Protobuf::Unpack( +std::optional wpi::util::Protobuf::Unpack( InputStream& stream) { - wpi::StdVectorUnpackCallback states; + wpi::util::StdVectorUnpackCallback states; wpi_proto_ProtobufTrajectory msg{ .states = states.Callback(), }; @@ -19,12 +19,12 @@ std::optional wpi::Protobuf::Unpack( return {}; } - return frc::Trajectory{states.Vec()}; + return wpi::math::Trajectory{states.Vec()}; } -bool wpi::Protobuf::Pack(OutputStream& stream, - const frc::Trajectory& value) { - wpi::PackCallback states{value.States()}; +bool wpi::util::Protobuf::Pack(OutputStream& stream, + const wpi::math::Trajectory& value) { + wpi::util::PackCallback states{value.States()}; wpi_proto_ProtobufTrajectory msg{ .states = states.Callback(), }; diff --git a/wpimath/src/main/native/cpp/trajectory/proto/TrajectoryStateProto.cpp b/wpimath/src/main/native/cpp/trajectory/proto/TrajectoryStateProto.cpp index 6a1f1ed80d..708914e57b 100644 --- a/wpimath/src/main/native/cpp/trajectory/proto/TrajectoryStateProto.cpp +++ b/wpimath/src/main/native/cpp/trajectory/proto/TrajectoryStateProto.cpp @@ -9,9 +9,9 @@ #include "wpi/util/protobuf/ProtobufCallbacks.hpp" #include "wpimath/protobuf/trajectory.npb.h" -std::optional -wpi::Protobuf::Unpack(InputStream& stream) { - wpi::UnpackCallback pose; +std::optional +wpi::util::Protobuf::Unpack(InputStream& stream) { + wpi::util::UnpackCallback pose; wpi_proto_ProtobufTrajectoryState msg; msg.pose = pose.Callback(); @@ -25,18 +25,18 @@ wpi::Protobuf::Unpack(InputStream& stream) { return {}; } - return frc::Trajectory::State{ - units::second_t{msg.time}, - units::meters_per_second_t{msg.velocity}, - units::meters_per_second_squared_t{msg.acceleration}, + return wpi::math::Trajectory::State{ + wpi::units::second_t{msg.time}, + wpi::units::meters_per_second_t{msg.velocity}, + wpi::units::meters_per_second_squared_t{msg.acceleration}, std::move(ipose[0]), - units::curvature_t{msg.curvature}, + wpi::units::curvature_t{msg.curvature}, }; } -bool wpi::Protobuf::Pack( - OutputStream& stream, const frc::Trajectory::State& value) { - wpi::PackCallback pose{&value.pose}; +bool wpi::util::Protobuf::Pack( + OutputStream& stream, const wpi::math::Trajectory::State& value) { + wpi::util::PackCallback pose{&value.pose}; wpi_proto_ProtobufTrajectoryState msg{ .time = value.t.value(), .velocity = value.velocity.value(), diff --git a/wpimath/src/main/native/cpp/util/MathShared.cpp b/wpimath/src/main/native/cpp/util/MathShared.cpp index 5738f063f3..d93afcdd2e 100644 --- a/wpimath/src/main/native/cpp/util/MathShared.cpp +++ b/wpimath/src/main/native/cpp/util/MathShared.cpp @@ -20,14 +20,14 @@ class DefaultMathShared : public MathShared { void ReportWarningV(fmt::string_view format, fmt::format_args args) override { } void ReportUsage(std::string_view resource, std::string_view data) override {} - units::second_t GetTimestamp() override { - return units::second_t{wpi::Now() * 1.0e-6}; + wpi::units::second_t GetTimestamp() override { + return wpi::units::second_t{wpi::util::Now() * 1.0e-6}; } }; } // namespace static std::unique_ptr mathShared; -static wpi::mutex setLock; +static wpi::util::mutex setLock; MathShared& MathSharedStore::GetMathShared() { std::scoped_lock lock(setLock); diff --git a/wpimath/src/main/native/cpp/util/StateSpaceUtil.cpp b/wpimath/src/main/native/cpp/util/StateSpaceUtil.cpp index 8c7233c1d0..52eb462dbc 100644 --- a/wpimath/src/main/native/cpp/util/StateSpaceUtil.cpp +++ b/wpimath/src/main/native/cpp/util/StateSpaceUtil.cpp @@ -6,7 +6,7 @@ #include -namespace frc { +namespace wpi::math { template bool IsStabilizable<1, 1>(const Matrixd<1, 1>& A, const Matrixd<1, 1>& B); @@ -68,4 +68,4 @@ Eigen::MatrixXd MakeCovMatrix(const std::span stdDevs) { return result; } -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/controller/ArmFeedforward.hpp b/wpimath/src/main/native/include/wpi/math/controller/ArmFeedforward.hpp index 22cff97d97..44f9004a2c 100644 --- a/wpimath/src/main/native/include/wpi/math/controller/ArmFeedforward.hpp +++ b/wpimath/src/main/native/include/wpi/math/controller/ArmFeedforward.hpp @@ -14,22 +14,22 @@ #include "wpi/util/MathExtras.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::math { /** * A helper class that computes feedforward outputs for a simple arm (modeled as * a motor acting against the force of gravity on a beam suspended at an angle). */ class WPILIB_DLLEXPORT ArmFeedforward { public: - using Angle = units::radians; - using Velocity = units::radians_per_second; - using Acceleration = units::compound_unit>; + using Angle = wpi::units::radians; + using Velocity = wpi::units::radians_per_second; + using Acceleration = wpi::units::compound_unit>; using kv_unit = - units::compound_unit>; + wpi::units::compound_unit>; using ka_unit = - units::compound_unit>; + wpi::units::compound_unit>; /** * Creates a new ArmFeedforward with the specified gains. @@ -44,20 +44,20 @@ class WPILIB_DLLEXPORT ArmFeedforward { * @throws IllegalArgumentException for period ≤ zero. */ constexpr ArmFeedforward( - units::volt_t kS, units::volt_t kG, units::unit_t kV, - units::unit_t kA = units::unit_t(0), - units::second_t dt = 20_ms) + wpi::units::volt_t kS, wpi::units::volt_t kG, wpi::units::unit_t kV, + wpi::units::unit_t kA = wpi::units::unit_t(0), + wpi::units::second_t dt = 20_ms) : kS(kS), kG(kG), kV(kV), kA(kA), m_dt(dt) { if (kV.value() < 0) { wpi::math::MathSharedStore::ReportError( "kV must be a non-negative number, got {}!", kV.value()); - this->kV = units::unit_t{0}; + this->kV = wpi::units::unit_t{0}; wpi::math::MathSharedStore::ReportWarning("kV defaulted to 0."); } if (kA.value() < 0) { wpi::math::MathSharedStore::ReportError( "kA must be a non-negative number, got {}!", kA.value()); - this->kA = units::unit_t{0}; + this->kA = wpi::units::unit_t{0}; wpi::math::MathSharedStore::ReportWarning("kA defaulted to 0;"); } if (dt <= 0_ms) { @@ -82,10 +82,10 @@ class WPILIB_DLLEXPORT ArmFeedforward { * @return The computed feedforward, in volts. */ [[deprecated("Use the current/next velocity overload instead.")]] - constexpr units::volt_t Calculate( - units::unit_t angle, units::unit_t velocity, - units::unit_t acceleration) const { - return kS * wpi::sgn(velocity) + kG * units::math::cos(angle) + + constexpr wpi::units::volt_t Calculate( + wpi::units::unit_t angle, wpi::units::unit_t velocity, + wpi::units::unit_t acceleration) const { + return kS * wpi::util::sgn(velocity) + kG * wpi::units::math::cos(angle) + kV * velocity + kA * acceleration; } @@ -103,10 +103,10 @@ class WPILIB_DLLEXPORT ArmFeedforward { * @return The computed feedforward in volts. */ [[deprecated("Use the current/next velocity overload instead.")]] - units::volt_t Calculate(units::unit_t currentAngle, - units::unit_t currentVelocity, - units::unit_t nextVelocity, - units::second_t dt) const { + wpi::units::volt_t Calculate(wpi::units::unit_t currentAngle, + wpi::units::unit_t currentVelocity, + wpi::units::unit_t nextVelocity, + wpi::units::second_t dt) const { return Calculate(currentAngle, currentVelocity, nextVelocity); } @@ -121,11 +121,11 @@ class WPILIB_DLLEXPORT ArmFeedforward { * @param currentVelocity The current velocity. * @return The computed feedforward in volts. */ - constexpr units::volt_t Calculate( - units::unit_t currentAngle, - units::unit_t currentVelocity) const { - return kS * wpi::sgn(currentVelocity) + - kG * units::math::cos(currentAngle) + kV * currentVelocity; + constexpr wpi::units::volt_t Calculate( + wpi::units::unit_t currentAngle, + wpi::units::unit_t currentVelocity) const { + return kS * wpi::util::sgn(currentVelocity) + + kG * wpi::units::math::cos(currentAngle) + kV * currentVelocity; } /** @@ -140,9 +140,9 @@ class WPILIB_DLLEXPORT ArmFeedforward { * @param nextVelocity The next velocity. * @return The computed feedforward in volts. */ - units::volt_t Calculate(units::unit_t currentAngle, - units::unit_t currentVelocity, - units::unit_t nextVelocity) const; + wpi::units::volt_t Calculate(wpi::units::unit_t currentAngle, + wpi::units::unit_t currentVelocity, + wpi::units::unit_t nextVelocity) const; // Rearranging the main equation from the calculate() method yields the // formulas for the methods below: @@ -163,11 +163,11 @@ class WPILIB_DLLEXPORT ArmFeedforward { * @param acceleration The acceleration of the arm. * @return The maximum possible velocity at the given acceleration and angle. */ - constexpr units::unit_t MaxAchievableVelocity( - units::volt_t maxVoltage, units::unit_t angle, - units::unit_t acceleration) { + constexpr wpi::units::unit_t MaxAchievableVelocity( + wpi::units::volt_t maxVoltage, wpi::units::unit_t angle, + wpi::units::unit_t acceleration) { // Assume max velocity is positive - return (maxVoltage - kS - kG * units::math::cos(angle) - + return (maxVoltage - kS - kG * wpi::units::math::cos(angle) - kA * acceleration) / kV; } @@ -188,11 +188,11 @@ class WPILIB_DLLEXPORT ArmFeedforward { * @param acceleration The acceleration of the arm. * @return The minimum possible velocity at the given acceleration and angle. */ - constexpr units::unit_t MinAchievableVelocity( - units::volt_t maxVoltage, units::unit_t angle, - units::unit_t acceleration) { + constexpr wpi::units::unit_t MinAchievableVelocity( + wpi::units::volt_t maxVoltage, wpi::units::unit_t angle, + wpi::units::unit_t acceleration) { // Assume min velocity is negative, ks flips sign - return (-maxVoltage + kS - kG * units::math::cos(angle) - + return (-maxVoltage + kS - kG * wpi::units::math::cos(angle) - kA * acceleration) / kV; } @@ -213,11 +213,11 @@ class WPILIB_DLLEXPORT ArmFeedforward { * @param velocity The velocity of the arm. * @return The maximum possible acceleration at the given velocity and angle. */ - constexpr units::unit_t MaxAchievableAcceleration( - units::volt_t maxVoltage, units::unit_t angle, - units::unit_t velocity) { - return (maxVoltage - kS * wpi::sgn(velocity) - - kG * units::math::cos(angle) - kV * velocity) / + constexpr wpi::units::unit_t MaxAchievableAcceleration( + wpi::units::volt_t maxVoltage, wpi::units::unit_t angle, + wpi::units::unit_t velocity) { + return (maxVoltage - kS * wpi::util::sgn(velocity) - + kG * wpi::units::math::cos(angle) - kV * velocity) / kA; } @@ -237,9 +237,9 @@ class WPILIB_DLLEXPORT ArmFeedforward { * @param velocity The velocity of the arm. * @return The minimum possible acceleration at the given velocity and angle. */ - constexpr units::unit_t MinAchievableAcceleration( - units::volt_t maxVoltage, units::unit_t angle, - units::unit_t velocity) { + constexpr wpi::units::unit_t MinAchievableAcceleration( + wpi::units::volt_t maxVoltage, wpi::units::unit_t angle, + wpi::units::unit_t velocity) { return MaxAchievableAcceleration(-maxVoltage, angle, velocity); } @@ -248,74 +248,74 @@ class WPILIB_DLLEXPORT ArmFeedforward { * * @param kS The static gain. */ - constexpr void SetKs(units::volt_t kS) { this->kS = kS; } + constexpr void SetKs(wpi::units::volt_t kS) { this->kS = kS; } /** * Sets the gravity gain. * * @param kG The gravity gain. */ - constexpr void SetKg(units::volt_t kG) { this->kG = kG; } + constexpr void SetKg(wpi::units::volt_t kG) { this->kG = kG; } /** * Sets the velocity gain. * * @param kV The velocity gain. */ - constexpr void SetKv(units::unit_t kV) { this->kV = kV; } + constexpr void SetKv(wpi::units::unit_t kV) { this->kV = kV; } /** * Sets the acceleration gain. * * @param kA The acceleration gain. */ - constexpr void SetKa(units::unit_t kA) { this->kA = kA; } + constexpr void SetKa(wpi::units::unit_t kA) { this->kA = kA; } /** * Returns the static gain. * * @return The static gain. */ - constexpr units::volt_t GetKs() const { return kS; } + constexpr wpi::units::volt_t GetKs() const { return kS; } /** * Returns the gravity gain. * * @return The gravity gain. */ - constexpr units::volt_t GetKg() const { return kG; } + constexpr wpi::units::volt_t GetKg() const { return kG; } /** * Returns the velocity gain. * * @return The velocity gain. */ - constexpr units::unit_t GetKv() const { return kV; } + constexpr wpi::units::unit_t GetKv() const { return kV; } /** * Returns the acceleration gain. * * @return The acceleration gain. */ - constexpr units::unit_t GetKa() const { return kA; } + constexpr wpi::units::unit_t GetKa() const { return kA; } private: /// The static gain, in volts. - units::volt_t kS; + wpi::units::volt_t kS; /// The gravity gain, in volts. - units::volt_t kG; + wpi::units::volt_t kG; /// The velocity gain, in V/(rad/s)volt seconds per radian. - units::unit_t kV; + wpi::units::unit_t kV; /// The acceleration gain, in V/(rad/s²). - units::unit_t kA; + wpi::units::unit_t kA; /** The period. */ - units::second_t m_dt; + wpi::units::second_t m_dt; }; -} // namespace frc +} // namespace wpi::math #include "wpi/math/controller/proto/ArmFeedforwardProto.hpp" #include "wpi/math/controller/struct/ArmFeedforwardStruct.hpp" diff --git a/wpimath/src/main/native/include/wpi/math/controller/BangBangController.hpp b/wpimath/src/main/native/include/wpi/math/controller/BangBangController.hpp index e5098b820b..d467dfcedc 100644 --- a/wpimath/src/main/native/include/wpi/math/controller/BangBangController.hpp +++ b/wpimath/src/main/native/include/wpi/math/controller/BangBangController.hpp @@ -13,7 +13,7 @@ #include "wpi/util/sendable/Sendable.hpp" #include "wpi/util/sendable/SendableHelper.hpp" -namespace frc { +namespace wpi::math { /** * Implements a bang-bang controller, which outputs either 0 or 1 depending on @@ -29,8 +29,8 @@ namespace frc { * control them with a bang-bang controller. */ class WPILIB_DLLEXPORT BangBangController - : public wpi::Sendable, - public wpi::SendableHelper { + : public wpi::util::Sendable, + public wpi::util::SendableHelper { public: /** * Creates a new bang-bang controller. @@ -128,7 +128,7 @@ class WPILIB_DLLEXPORT BangBangController return Calculate(measurement, m_setpoint); } - void InitSendable(wpi::SendableBuilder& builder) override; + void InitSendable(wpi::util::SendableBuilder& builder) override; private: double m_tolerance; @@ -140,4 +140,4 @@ class WPILIB_DLLEXPORT BangBangController inline static int instances = 0; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/controller/ControlAffinePlantInversionFeedforward.hpp b/wpimath/src/main/native/include/wpi/math/controller/ControlAffinePlantInversionFeedforward.hpp index a4594c86fe..8315dab993 100644 --- a/wpimath/src/main/native/include/wpi/math/controller/ControlAffinePlantInversionFeedforward.hpp +++ b/wpimath/src/main/native/include/wpi/math/controller/ControlAffinePlantInversionFeedforward.hpp @@ -13,7 +13,7 @@ #include "wpi/math/system/NumericalJacobian.hpp" #include "wpi/units/time.hpp" -namespace frc { +namespace wpi::math { /** * Constructs a control-affine plant inversion model-based feedforward from @@ -55,7 +55,7 @@ class ControlAffinePlantInversionFeedforward { */ ControlAffinePlantInversionFeedforward( std::function f, - units::second_t dt) + wpi::units::second_t dt) : m_dt(dt), m_f(f) { m_B = NumericalJacobianU(f, StateVector::Zero(), InputVector::Zero()); @@ -74,7 +74,7 @@ class ControlAffinePlantInversionFeedforward { */ ControlAffinePlantInversionFeedforward( std::function f, - const Matrixd& B, units::second_t dt) + const Matrixd& B, wpi::units::second_t dt) : m_B(B), m_dt(dt) { m_f = [=](const StateVector& x, const InputVector& u) -> StateVector { return f(x); @@ -178,7 +178,7 @@ class ControlAffinePlantInversionFeedforward { private: Matrixd m_B; - units::second_t m_dt; + wpi::units::second_t m_dt; /** * The model dynamics. @@ -192,4 +192,4 @@ class ControlAffinePlantInversionFeedforward { InputVector m_uff; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/controller/DifferentialDriveAccelerationLimiter.hpp b/wpimath/src/main/native/include/wpi/math/controller/DifferentialDriveAccelerationLimiter.hpp index 699012d719..251e7fe9ff 100644 --- a/wpimath/src/main/native/include/wpi/math/controller/DifferentialDriveAccelerationLimiter.hpp +++ b/wpimath/src/main/native/include/wpi/math/controller/DifferentialDriveAccelerationLimiter.hpp @@ -17,7 +17,7 @@ #include "wpi/units/voltage.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::math { /** * Filters the provided voltages to limit a differential drive's linear and @@ -38,9 +38,9 @@ class WPILIB_DLLEXPORT DifferentialDriveAccelerationLimiter { * @param maxAngularAccel The maximum angular acceleration. */ DifferentialDriveAccelerationLimiter( - LinearSystem<2, 2, 2> system, units::meter_t trackwidth, - units::meters_per_second_squared_t maxLinearAccel, - units::radians_per_second_squared_t maxAngularAccel) + LinearSystem<2, 2, 2> system, wpi::units::meter_t trackwidth, + wpi::units::meters_per_second_squared_t maxLinearAccel, + wpi::units::radians_per_second_squared_t maxAngularAccel) : DifferentialDriveAccelerationLimiter(system, trackwidth, -maxLinearAccel, maxLinearAccel, maxAngularAccel) {} @@ -58,10 +58,10 @@ class WPILIB_DLLEXPORT DifferentialDriveAccelerationLimiter { * than maximum linear acceleration */ DifferentialDriveAccelerationLimiter( - LinearSystem<2, 2, 2> system, units::meter_t trackwidth, - units::meters_per_second_squared_t minLinearAccel, - units::meters_per_second_squared_t maxLinearAccel, - units::radians_per_second_squared_t maxAngularAccel) + LinearSystem<2, 2, 2> system, wpi::units::meter_t trackwidth, + wpi::units::meters_per_second_squared_t minLinearAccel, + wpi::units::meters_per_second_squared_t maxLinearAccel, + wpi::units::radians_per_second_squared_t maxAngularAccel) : m_system{std::move(system)}, m_trackwidth{trackwidth}, m_minLinearAccel{minLinearAccel}, @@ -83,16 +83,16 @@ class WPILIB_DLLEXPORT DifferentialDriveAccelerationLimiter { * @return The constrained wheel voltages. */ DifferentialDriveWheelVoltages Calculate( - units::meters_per_second_t leftVelocity, - units::meters_per_second_t rightVelocity, units::volt_t leftVoltage, - units::volt_t rightVoltage); + wpi::units::meters_per_second_t leftVelocity, + wpi::units::meters_per_second_t rightVelocity, wpi::units::volt_t leftVoltage, + wpi::units::volt_t rightVoltage); private: LinearSystem<2, 2, 2> m_system; - units::meter_t m_trackwidth; - units::meters_per_second_squared_t m_minLinearAccel; - units::meters_per_second_squared_t m_maxLinearAccel; - units::radians_per_second_squared_t m_maxAngularAccel; + wpi::units::meter_t m_trackwidth; + wpi::units::meters_per_second_squared_t m_minLinearAccel; + wpi::units::meters_per_second_squared_t m_maxLinearAccel; + wpi::units::radians_per_second_squared_t m_maxAngularAccel; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/controller/DifferentialDriveFeedforward.hpp b/wpimath/src/main/native/include/wpi/math/controller/DifferentialDriveFeedforward.hpp index d5a9b3a626..0bc5f982f7 100644 --- a/wpimath/src/main/native/include/wpi/math/controller/DifferentialDriveFeedforward.hpp +++ b/wpimath/src/main/native/include/wpi/math/controller/DifferentialDriveFeedforward.hpp @@ -16,13 +16,13 @@ #include "wpi/units/voltage.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::math { /** * A helper class which computes the feedforward outputs for a differential * drive drivetrain. */ class WPILIB_DLLEXPORT DifferentialDriveFeedforward { - frc::LinearSystem<2, 2, 2> m_plant; + wpi::math::LinearSystem<2, 2, 2> m_plant; public: /** @@ -41,7 +41,7 @@ class WPILIB_DLLEXPORT DifferentialDriveFeedforward { constexpr DifferentialDriveFeedforward( decltype(1_V / 1_mps) kVLinear, decltype(1_V / 1_mps_sq) kALinear, decltype(1_V / 1_rad_per_s) kVAngular, - decltype(1_V / 1_rad_per_s_sq) kAAngular, units::meter_t trackwidth) + decltype(1_V / 1_rad_per_s_sq) kAAngular, wpi::units::meter_t trackwidth) // See LinearSystemId::IdentifyDrivetrainSystem(decltype(1_V / 1_mps), // decltype(1_V / 1_mps_sq), decltype(1_V / 1_rad_per_s), decltype(1_V / // 1_rad_per_s_sq)) @@ -64,7 +64,7 @@ class WPILIB_DLLEXPORT DifferentialDriveFeedforward { decltype(1_V / 1_mps_sq) kALinear, decltype(1_V / 1_mps) kVAngular, decltype(1_V / 1_mps_sq) kAAngular) - : m_plant{frc::LinearSystemId::IdentifyDrivetrainSystem( + : m_plant{wpi::math::LinearSystemId::IdentifyDrivetrainSystem( kVLinear, kALinear, kVAngular, kAAngular)}, m_kVLinear{kVLinear}, m_kALinear{kALinear}, @@ -86,17 +86,17 @@ class WPILIB_DLLEXPORT DifferentialDriveFeedforward { * @param dt Discretization timestep. */ DifferentialDriveWheelVoltages Calculate( - units::meters_per_second_t currentLeftVelocity, - units::meters_per_second_t nextLeftVelocity, - units::meters_per_second_t currentRightVelocity, - units::meters_per_second_t nextRightVelocity, units::second_t dt); + wpi::units::meters_per_second_t currentLeftVelocity, + wpi::units::meters_per_second_t nextLeftVelocity, + wpi::units::meters_per_second_t currentRightVelocity, + wpi::units::meters_per_second_t nextRightVelocity, wpi::units::second_t dt); decltype(1_V / 1_mps) m_kVLinear; decltype(1_V / 1_mps_sq) m_kALinear; decltype(1_V / 1_mps) m_kVAngular; decltype(1_V / 1_mps_sq) m_kAAngular; }; -} // namespace frc +} // namespace wpi::math #include "wpi/math/controller/proto/DifferentialDriveFeedforwardProto.hpp" #include "wpi/math/controller/struct/DifferentialDriveFeedforwardStruct.hpp" diff --git a/wpimath/src/main/native/include/wpi/math/controller/DifferentialDriveWheelVoltages.hpp b/wpimath/src/main/native/include/wpi/math/controller/DifferentialDriveWheelVoltages.hpp index 34aa01970c..dfc4fed664 100644 --- a/wpimath/src/main/native/include/wpi/math/controller/DifferentialDriveWheelVoltages.hpp +++ b/wpimath/src/main/native/include/wpi/math/controller/DifferentialDriveWheelVoltages.hpp @@ -6,20 +6,20 @@ #include "wpi/units/voltage.hpp" -namespace frc { +namespace wpi::math { /** * Motor voltages for a differential drive. */ struct DifferentialDriveWheelVoltages { /// Left wheel voltage. - units::volt_t left = 0_V; + wpi::units::volt_t left = 0_V; /// Right wheel voltage. - units::volt_t right = 0_V; + wpi::units::volt_t right = 0_V; }; -} // namespace frc +} // namespace wpi::math #include "wpi/math/controller/proto/DifferentialDriveWheelVoltagesProto.hpp" #include "wpi/math/controller/struct/DifferentialDriveWheelVoltagesStruct.hpp" diff --git a/wpimath/src/main/native/include/wpi/math/controller/ElevatorFeedforward.hpp b/wpimath/src/main/native/include/wpi/math/controller/ElevatorFeedforward.hpp index fcffd91206..947a92dfa6 100644 --- a/wpimath/src/main/native/include/wpi/math/controller/ElevatorFeedforward.hpp +++ b/wpimath/src/main/native/include/wpi/math/controller/ElevatorFeedforward.hpp @@ -13,21 +13,21 @@ #include "wpi/units/voltage.hpp" #include "wpi/util/MathExtras.hpp" -namespace frc { +namespace wpi::math { /** * A helper class that computes feedforward outputs for a simple elevator * (modeled as a motor acting against the force of gravity). */ class ElevatorFeedforward { public: - using Distance = units::meters; + using Distance = wpi::units::meters; using Velocity = - units::compound_unit>; + wpi::units::compound_unit>; using Acceleration = - units::compound_unit>; - using kv_unit = units::compound_unit>; + wpi::units::compound_unit>; + using kv_unit = wpi::units::compound_unit>; using ka_unit = - units::compound_unit>; + wpi::units::compound_unit>; /** * Creates a new ElevatorFeedforward with the specified gains. @@ -42,20 +42,20 @@ class ElevatorFeedforward { * @throws IllegalArgumentException for period ≤ zero. */ constexpr ElevatorFeedforward( - units::volt_t kS, units::volt_t kG, units::unit_t kV, - units::unit_t kA = units::unit_t(0), - units::second_t dt = 20_ms) + wpi::units::volt_t kS, wpi::units::volt_t kG, wpi::units::unit_t kV, + wpi::units::unit_t kA = wpi::units::unit_t(0), + wpi::units::second_t dt = 20_ms) : kS(kS), kG(kG), kV(kV), kA(kA), m_dt(dt) { if (kV.value() < 0) { wpi::math::MathSharedStore::ReportError( "kV must be a non-negative number, got {}!", kV.value()); - this->kV = units::unit_t{0}; + this->kV = wpi::units::unit_t{0}; wpi::math::MathSharedStore::ReportWarning("kV defaulted to 0."); } if (kA.value() < 0) { wpi::math::MathSharedStore::ReportError( "kA must be a non-negative number, got {}!", kA.value()); - this->kA = units::unit_t{0}; + this->kA = wpi::units::unit_t{0}; wpi::math::MathSharedStore::ReportWarning("kA defaulted to 0;"); } if (dt <= 0_ms) { @@ -76,10 +76,10 @@ class ElevatorFeedforward { * @deprecated Use the current/next velocity overload instead. */ [[deprecated("Use the current/next velocity overload instead.")]] - constexpr units::volt_t Calculate( - units::unit_t velocity, - units::unit_t acceleration) const { - return kS * wpi::sgn(velocity) + kG + kV * velocity + kA * acceleration; + constexpr wpi::units::volt_t Calculate( + wpi::units::unit_t velocity, + wpi::units::unit_t acceleration) const { + return kS * wpi::util::sgn(velocity) + kG + kV * velocity + kA * acceleration; } /** @@ -92,9 +92,9 @@ class ElevatorFeedforward { * @return The computed feedforward, in volts. */ [[deprecated("Use the current/next velocity overload instead.")]] - units::volt_t Calculate(units::unit_t currentVelocity, - units::unit_t nextVelocity, - units::second_t dt) const { + wpi::units::volt_t Calculate(wpi::units::unit_t currentVelocity, + wpi::units::unit_t nextVelocity, + wpi::units::second_t dt) const { // See wpimath/algorithms.md#Elevator_feedforward for derivation auto plant = LinearSystemId::IdentifyVelocitySystem(kV, kA); LinearPlantInversionFeedforward<1, 1> feedforward{plant, dt}; @@ -102,8 +102,8 @@ class ElevatorFeedforward { Vectord<1> r{{currentVelocity.value()}}; Vectord<1> nextR{{nextVelocity.value()}}; - return kG + kS * wpi::sgn(currentVelocity.value()) + - units::volt_t{feedforward.Calculate(r, nextR)(0)}; + return kG + kS * wpi::util::sgn(currentVelocity.value()) + + wpi::units::volt_t{feedforward.Calculate(r, nextR)(0)}; } /** @@ -113,8 +113,8 @@ class ElevatorFeedforward { * @param currentVelocity The velocity setpoint. * @return The computed feedforward, in volts. */ - constexpr units::volt_t Calculate( - units::unit_t currentVelocity) const { + constexpr wpi::units::volt_t Calculate( + wpi::units::unit_t currentVelocity) const { return Calculate(currentVelocity, currentVelocity); } @@ -128,19 +128,19 @@ class ElevatorFeedforward { * @param nextVelocity The next velocity setpoint. * @return The computed feedforward, in volts. */ - constexpr units::volt_t Calculate( - units::unit_t currentVelocity, - units::unit_t nextVelocity) const { + constexpr wpi::units::volt_t Calculate( + wpi::units::unit_t currentVelocity, + wpi::units::unit_t nextVelocity) const { // See wpimath/algorithms.md#Elevator_feedforward for derivation if (kA < decltype(kA)(1e-9)) { - return kS * wpi::sgn(nextVelocity) + kG + kV * nextVelocity; + return kS * wpi::util::sgn(nextVelocity) + kG + kV * nextVelocity; } else { double A = -kV.value() / kA.value(); double B = 1.0 / kA.value(); double A_d = gcem::exp(A * m_dt.value()); double B_d = A > -1e-9 ? B * m_dt.value() : 1.0 / A * (A_d - 1.0) * B; - return kG + kS * wpi::sgn(currentVelocity) + - units::volt_t{ + return kG + kS * wpi::util::sgn(currentVelocity) + + wpi::units::volt_t{ 1.0 / B_d * (nextVelocity.value() - A_d * currentVelocity.value())}; } @@ -160,8 +160,8 @@ class ElevatorFeedforward { * @param acceleration The acceleration of the elevator. * @return The maximum possible velocity at the given acceleration. */ - constexpr units::unit_t MaxAchievableVelocity( - units::volt_t maxVoltage, units::unit_t acceleration) { + constexpr wpi::units::unit_t MaxAchievableVelocity( + wpi::units::volt_t maxVoltage, wpi::units::unit_t acceleration) { // Assume max velocity is positive return (maxVoltage - kS - kG - kA * acceleration) / kV; } @@ -177,8 +177,8 @@ class ElevatorFeedforward { * @param acceleration The acceleration of the elevator. * @return The minimum possible velocity at the given acceleration. */ - constexpr units::unit_t MinAchievableVelocity( - units::volt_t maxVoltage, units::unit_t acceleration) { + constexpr wpi::units::unit_t MinAchievableVelocity( + wpi::units::volt_t maxVoltage, wpi::units::unit_t acceleration) { // Assume min velocity is negative, ks flips sign return (-maxVoltage + kS - kG - kA * acceleration) / kV; } @@ -194,9 +194,9 @@ class ElevatorFeedforward { * @param velocity The velocity of the elevator. * @return The maximum possible acceleration at the given velocity. */ - constexpr units::unit_t MaxAchievableAcceleration( - units::volt_t maxVoltage, units::unit_t velocity) { - return (maxVoltage - kS * wpi::sgn(velocity) - kG - kV * velocity) / kA; + constexpr wpi::units::unit_t MaxAchievableAcceleration( + wpi::units::volt_t maxVoltage, wpi::units::unit_t velocity) { + return (maxVoltage - kS * wpi::util::sgn(velocity) - kG - kV * velocity) / kA; } /** @@ -210,8 +210,8 @@ class ElevatorFeedforward { * @param velocity The velocity of the elevator. * @return The minimum possible acceleration at the given velocity. */ - constexpr units::unit_t MinAchievableAcceleration( - units::volt_t maxVoltage, units::unit_t velocity) { + constexpr wpi::units::unit_t MinAchievableAcceleration( + wpi::units::volt_t maxVoltage, wpi::units::unit_t velocity) { return MaxAchievableAcceleration(-maxVoltage, velocity); } @@ -220,74 +220,74 @@ class ElevatorFeedforward { * * @param kS The static gain. */ - constexpr void SetKs(units::volt_t kS) { this->kS = kS; } + constexpr void SetKs(wpi::units::volt_t kS) { this->kS = kS; } /** * Sets the gravity gain. * * @param kG The gravity gain. */ - constexpr void SetKg(units::volt_t kG) { this->kG = kG; } + constexpr void SetKg(wpi::units::volt_t kG) { this->kG = kG; } /** * Sets the velocity gain. * * @param kV The velocity gain. */ - constexpr void SetKv(units::unit_t kV) { this->kV = kV; } + constexpr void SetKv(wpi::units::unit_t kV) { this->kV = kV; } /** * Sets the acceleration gain. * * @param kA The acceleration gain. */ - constexpr void SetKa(units::unit_t kA) { this->kA = kA; } + constexpr void SetKa(wpi::units::unit_t kA) { this->kA = kA; } /** * Returns the static gain. * * @return The static gain. */ - constexpr units::volt_t GetKs() const { return kS; } + constexpr wpi::units::volt_t GetKs() const { return kS; } /** * Returns the gravity gain. * * @return The gravity gain. */ - constexpr units::volt_t GetKg() const { return kG; } + constexpr wpi::units::volt_t GetKg() const { return kG; } /** * Returns the velocity gain. * * @return The velocity gain. */ - constexpr units::unit_t GetKv() const { return kV; } + constexpr wpi::units::unit_t GetKv() const { return kV; } /** * Returns the acceleration gain. * * @return The acceleration gain. */ - constexpr units::unit_t GetKa() const { return kA; } + constexpr wpi::units::unit_t GetKa() const { return kA; } private: /// The static gain. - units::volt_t kS; + wpi::units::volt_t kS; /// The gravity gain. - units::volt_t kG; + wpi::units::volt_t kG; /// The velocity gain. - units::unit_t kV; + wpi::units::unit_t kV; /// The acceleration gain. - units::unit_t kA; + wpi::units::unit_t kA; /** The period. */ - units::second_t m_dt; + wpi::units::second_t m_dt; }; -} // namespace frc +} // namespace wpi::math #include "wpi/math/controller/proto/ElevatorFeedforwardProto.hpp" #include "wpi/math/controller/struct/ElevatorFeedforwardStruct.hpp" diff --git a/wpimath/src/main/native/include/wpi/math/controller/ImplicitModelFollower.hpp b/wpimath/src/main/native/include/wpi/math/controller/ImplicitModelFollower.hpp index 7ac78eedee..73a5c829cb 100644 --- a/wpimath/src/main/native/include/wpi/math/controller/ImplicitModelFollower.hpp +++ b/wpimath/src/main/native/include/wpi/math/controller/ImplicitModelFollower.hpp @@ -10,7 +10,7 @@ #include "wpi/math/system/LinearSystem.hpp" #include "wpi/units/time.hpp" -namespace frc { +namespace wpi::math { /** * Contains the controller coefficients and logic for an implicit model @@ -123,4 +123,4 @@ class ImplicitModelFollower { Matrixd m_B; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/controller/LTVDifferentialDriveController.hpp b/wpimath/src/main/native/include/wpi/math/controller/LTVDifferentialDriveController.hpp index aa82959153..035e08f5d9 100644 --- a/wpimath/src/main/native/include/wpi/math/controller/LTVDifferentialDriveController.hpp +++ b/wpimath/src/main/native/include/wpi/math/controller/LTVDifferentialDriveController.hpp @@ -19,7 +19,7 @@ #include "wpi/util/SymbolExports.hpp" #include "wpi/util/array.hpp" -namespace frc { +namespace wpi::math { /** * The linear time-varying differential drive controller has a similar form to @@ -54,16 +54,16 @@ class WPILIB_DLLEXPORT LTVDifferentialDriveController { * @param Relems The maximum desired control effort for each input. * @param dt Discretization timestep. */ - LTVDifferentialDriveController(const frc::LinearSystem<2, 2, 2>& plant, - units::meter_t trackwidth, - const wpi::array& Qelems, - const wpi::array& Relems, - units::second_t dt) + LTVDifferentialDriveController(const wpi::math::LinearSystem<2, 2, 2>& plant, + wpi::units::meter_t trackwidth, + const wpi::util::array& Qelems, + const wpi::util::array& Relems, + wpi::units::second_t dt) : m_trackwidth{trackwidth}, m_A{plant.A()}, m_B{plant.B()}, - m_Q{frc::MakeCostMatrix(Qelems)}, - m_R{frc::MakeCostMatrix(Relems)}, + m_Q{wpi::math::MakeCostMatrix(Qelems)}, + m_R{wpi::math::MakeCostMatrix(Relems)}, m_dt{dt} {} /** @@ -97,8 +97,8 @@ class WPILIB_DLLEXPORT LTVDifferentialDriveController { * @param rightVelocityTolerance Right velocity error which is tolerable. */ void SetTolerance(const Pose2d& poseTolerance, - units::meters_per_second_t leftVelocityTolerance, - units::meters_per_second_t rightVelocityTolerance) { + wpi::units::meters_per_second_t leftVelocityTolerance, + wpi::units::meters_per_second_t rightVelocityTolerance) { m_tolerance = Eigen::Vector{ poseTolerance.X().value(), poseTolerance.Y().value(), poseTolerance.Rotation().Radians().value(), @@ -119,10 +119,10 @@ class WPILIB_DLLEXPORT LTVDifferentialDriveController { * @param rightVelocityRef The desired right velocity. */ DifferentialDriveWheelVoltages Calculate( - const Pose2d& currentPose, units::meters_per_second_t leftVelocity, - units::meters_per_second_t rightVelocity, const Pose2d& poseRef, - units::meters_per_second_t leftVelocityRef, - units::meters_per_second_t rightVelocityRef); + const Pose2d& currentPose, wpi::units::meters_per_second_t leftVelocity, + wpi::units::meters_per_second_t rightVelocity, const Pose2d& poseRef, + wpi::units::meters_per_second_t leftVelocityRef, + wpi::units::meters_per_second_t rightVelocityRef); /** * Returns the left and right output voltages of the LTV controller. @@ -137,8 +137,8 @@ class WPILIB_DLLEXPORT LTVDifferentialDriveController { * from a trajectory. */ DifferentialDriveWheelVoltages Calculate( - const Pose2d& currentPose, units::meters_per_second_t leftVelocity, - units::meters_per_second_t rightVelocity, + const Pose2d& currentPose, wpi::units::meters_per_second_t leftVelocity, + wpi::units::meters_per_second_t rightVelocity, const Trajectory::State& desiredState) { // v = (v_r + v_l) / 2 (1) // w = (v_r - v_l) / (2r) (2) @@ -160,7 +160,7 @@ class WPILIB_DLLEXPORT LTVDifferentialDriveController { } private: - units::meter_t m_trackwidth; + wpi::units::meter_t m_trackwidth; // Continuous velocity dynamics Eigen::Matrix m_A; @@ -170,10 +170,10 @@ class WPILIB_DLLEXPORT LTVDifferentialDriveController { Eigen::Matrix m_Q; Eigen::Matrix m_R; - units::second_t m_dt; + wpi::units::second_t m_dt; Eigen::Vector m_error; Eigen::Vector m_tolerance; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/controller/LTVUnicycleController.hpp b/wpimath/src/main/native/include/wpi/math/controller/LTVUnicycleController.hpp index 15012504da..4ce4965eef 100644 --- a/wpimath/src/main/native/include/wpi/math/controller/LTVUnicycleController.hpp +++ b/wpimath/src/main/native/include/wpi/math/controller/LTVUnicycleController.hpp @@ -17,7 +17,7 @@ #include "wpi/util/SymbolExports.hpp" #include "wpi/util/array.hpp" -namespace frc { +namespace wpi::math { /** * The linear time-varying unicycle controller has a similar form to the LQR, @@ -37,7 +37,7 @@ class WPILIB_DLLEXPORT LTVUnicycleController { * * @param dt Discretization timestep. */ - explicit LTVUnicycleController(units::second_t dt) + explicit LTVUnicycleController(wpi::units::second_t dt) : LTVUnicycleController{{0.0625, 0.125, 2.0}, {1.0, 2.0}, dt} {} /** @@ -53,10 +53,10 @@ class WPILIB_DLLEXPORT LTVUnicycleController { * velocity, angular velocity). * @param dt Discretization timestep. */ - LTVUnicycleController(const wpi::array& Qelems, - const wpi::array& Relems, units::second_t dt) - : m_Q{frc::MakeCostMatrix(Qelems)}, - m_R{frc::MakeCostMatrix(Relems)}, + LTVUnicycleController(const wpi::util::array& Qelems, + const wpi::util::array& Relems, wpi::units::second_t dt) + : m_Q{wpi::math::MakeCostMatrix(Qelems)}, + m_R{wpi::math::MakeCostMatrix(Relems)}, m_dt{dt} {} /** @@ -77,9 +77,9 @@ class WPILIB_DLLEXPORT LTVUnicycleController { const auto& eRotate = m_poseError.Rotation(); const auto& tolTranslate = m_poseTolerance.Translation(); const auto& tolRotate = m_poseTolerance.Rotation(); - return units::math::abs(eTranslate.X()) < tolTranslate.X() && - units::math::abs(eTranslate.Y()) < tolTranslate.Y() && - units::math::abs(eRotate.Radians()) < tolRotate.Radians(); + return wpi::units::math::abs(eTranslate.X()) < tolTranslate.X() && + wpi::units::math::abs(eTranslate.Y()) < tolTranslate.Y() && + wpi::units::math::abs(eRotate.Radians()) < tolRotate.Radians(); } /** @@ -104,8 +104,8 @@ class WPILIB_DLLEXPORT LTVUnicycleController { * @param angularVelocityRef The desired angular velocity. */ ChassisSpeeds Calculate(const Pose2d& currentPose, const Pose2d& poseRef, - units::meters_per_second_t linearVelocityRef, - units::radians_per_second_t angularVelocityRef); + wpi::units::meters_per_second_t linearVelocityRef, + wpi::units::radians_per_second_t angularVelocityRef); /** * Returns the linear and angular velocity outputs of the LTV controller. @@ -135,11 +135,11 @@ class WPILIB_DLLEXPORT LTVUnicycleController { Eigen::Matrix m_Q; Eigen::Matrix m_R; - units::second_t m_dt; + wpi::units::second_t m_dt; Pose2d m_poseError; Pose2d m_poseTolerance; bool m_enabled = true; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/controller/LinearPlantInversionFeedforward.hpp b/wpimath/src/main/native/include/wpi/math/controller/LinearPlantInversionFeedforward.hpp index 3165c6988d..2650e3dcbb 100644 --- a/wpimath/src/main/native/include/wpi/math/controller/LinearPlantInversionFeedforward.hpp +++ b/wpimath/src/main/native/include/wpi/math/controller/LinearPlantInversionFeedforward.hpp @@ -14,7 +14,7 @@ #include "wpi/math/system/LinearSystem.hpp" #include "wpi/units/time.hpp" -namespace frc { +namespace wpi::math { /** * Constructs a plant inversion model-based feedforward from a LinearSystem. @@ -44,7 +44,7 @@ class LinearPlantInversionFeedforward { */ template LinearPlantInversionFeedforward( - const LinearSystem& plant, units::second_t dt) + const LinearSystem& plant, wpi::units::second_t dt) : LinearPlantInversionFeedforward(plant.A(), plant.B(), dt) {} /** @@ -56,7 +56,7 @@ class LinearPlantInversionFeedforward { */ LinearPlantInversionFeedforward(const Matrixd& A, const Matrixd& B, - units::second_t dt) + wpi::units::second_t dt) : m_dt(dt) { DiscretizeAB(A, B, dt, &m_A, &m_B); Reset(); @@ -150,7 +150,7 @@ class LinearPlantInversionFeedforward { Matrixd m_A; Matrixd m_B; - units::second_t m_dt; + wpi::units::second_t m_dt; // Current reference StateVector m_r; @@ -159,4 +159,4 @@ class LinearPlantInversionFeedforward { InputVector m_uff; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/controller/LinearQuadraticRegulator.hpp b/wpimath/src/main/native/include/wpi/math/controller/LinearQuadraticRegulator.hpp index a3f5424768..855760a648 100644 --- a/wpimath/src/main/native/include/wpi/math/controller/LinearQuadraticRegulator.hpp +++ b/wpimath/src/main/native/include/wpi/math/controller/LinearQuadraticRegulator.hpp @@ -21,7 +21,7 @@ #include "wpi/util/SymbolExports.hpp" #include "wpi/util/array.hpp" -namespace frc { +namespace wpi::math { /** * Contains the controller coefficients and logic for a linear-quadratic @@ -40,8 +40,8 @@ class LinearQuadraticRegulator { using StateVector = Vectord; using InputVector = Vectord; - using StateArray = wpi::array; - using InputArray = wpi::array; + using StateArray = wpi::util::array; + using InputArray = wpi::util::array; /** * Constructs a controller with the given coefficients and plant. @@ -60,7 +60,7 @@ class LinearQuadraticRegulator { template LinearQuadraticRegulator(const LinearSystem& plant, const StateArray& Qelems, const InputArray& Relems, - units::second_t dt) + wpi::units::second_t dt) : LinearQuadraticRegulator(plant.A(), plant.B(), Qelems, Relems, dt) {} /** @@ -80,7 +80,7 @@ class LinearQuadraticRegulator { LinearQuadraticRegulator(const Matrixd& A, const Matrixd& B, const StateArray& Qelems, const InputArray& Relems, - units::second_t dt) + wpi::units::second_t dt) : LinearQuadraticRegulator(A, B, MakeCostMatrix(Qelems), MakeCostMatrix(Relems), dt) {} @@ -98,7 +98,7 @@ class LinearQuadraticRegulator { const Matrixd& B, const Matrixd& Q, const Matrixd& R, - units::second_t dt) { + wpi::units::second_t dt) { Matrixd discA; Matrixd discB; DiscretizeAB(A, B, dt, &discA, &discB); @@ -153,7 +153,7 @@ class LinearQuadraticRegulator { const Matrixd& Q, const Matrixd& R, const Matrixd& N, - units::second_t dt) { + wpi::units::second_t dt) { Matrixd discA; Matrixd discB; DiscretizeAB(A, B, dt, &discA, &discB); @@ -291,7 +291,7 @@ class LinearQuadraticRegulator { */ template void LatencyCompensate(const LinearSystem& plant, - units::second_t dt, units::second_t inputDelay) { + wpi::units::second_t dt, wpi::units::second_t inputDelay) { Matrixd discA; Matrixd discB; DiscretizeAB(plant.A(), plant.B(), dt, &discA, &discB); @@ -317,4 +317,4 @@ extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT) extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT) LinearQuadraticRegulator<2, 2>; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/controller/PIDController.hpp b/wpimath/src/main/native/include/wpi/math/controller/PIDController.hpp index 5d3ae2fa75..c967ab7fc4 100644 --- a/wpimath/src/main/native/include/wpi/math/controller/PIDController.hpp +++ b/wpimath/src/main/native/include/wpi/math/controller/PIDController.hpp @@ -19,14 +19,14 @@ #include "wpi/util/sendable/SendableHelper.hpp" #include "wpi/util/sendable/SendableRegistry.hpp" -namespace frc { +namespace wpi::math { /** * Implements a PID control loop. */ class WPILIB_DLLEXPORT PIDController - : public wpi::Sendable, - public wpi::SendableHelper { + : public wpi::util::Sendable, + public wpi::util::SendableHelper { public: /** * Allocates a PIDController with the given constants for Kp, Ki, and Kd. @@ -38,7 +38,7 @@ class WPILIB_DLLEXPORT PIDController * default is 20 milliseconds. Must be positive. */ constexpr PIDController(double Kp, double Ki, double Kd, - units::second_t period = 20_ms) + wpi::units::second_t period = 20_ms) : m_Kp(Kp), m_Ki(Ki), m_Kd(Kd), m_period(period) { bool invalidGains = false; if (Kp < 0.0) { @@ -76,7 +76,7 @@ class WPILIB_DLLEXPORT PIDController wpi::math::MathSharedStore::ReportUsage("PIDController", std::to_string(instances)); - wpi::SendableRegistry::Add(this, "PIDController", instances); + wpi::util::SendableRegistry::Add(this, "PIDController", instances); } } @@ -175,7 +175,7 @@ class WPILIB_DLLEXPORT PIDController * * @return The period of the controller. */ - constexpr units::second_t GetPeriod() const { return m_period; } + constexpr wpi::units::second_t GetPeriod() const { return m_period; } /** * Gets the error tolerance of this controller. Defaults to 0.05. @@ -403,7 +403,7 @@ class WPILIB_DLLEXPORT PIDController m_haveMeasurement = false; } - void InitSendable(wpi::SendableBuilder& builder) override; + void InitSendable(wpi::util::SendableBuilder& builder) override; private: // Factor for "proportional" control @@ -419,7 +419,7 @@ class WPILIB_DLLEXPORT PIDController double m_iZone = std::numeric_limits::infinity(); // The period (in seconds) of the control loop running this controller - units::second_t m_period; + wpi::units::second_t m_period; double m_maximumIntegral = 1.0; @@ -457,4 +457,4 @@ class WPILIB_DLLEXPORT PIDController inline static int instances = 0; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/controller/ProfiledPIDController.hpp b/wpimath/src/main/native/include/wpi/math/controller/ProfiledPIDController.hpp index f1a8196f1d..07ac7f41f7 100644 --- a/wpimath/src/main/native/include/wpi/math/controller/ProfiledPIDController.hpp +++ b/wpimath/src/main/native/include/wpi/math/controller/ProfiledPIDController.hpp @@ -17,7 +17,7 @@ #include "wpi/util/sendable/SendableBuilder.hpp" #include "wpi/util/sendable/SendableHelper.hpp" -namespace frc { +namespace wpi::math { namespace detail { WPILIB_DLLEXPORT int IncrementAndGetProfiledPIDControllerInstances(); @@ -29,16 +29,16 @@ int IncrementAndGetProfiledPIDControllerInstances(); */ template class ProfiledPIDController - : public wpi::Sendable, - public wpi::SendableHelper> { + : public wpi::util::Sendable, + public wpi::util::SendableHelper> { public: - using Distance_t = units::unit_t; + using Distance_t = wpi::units::unit_t; using Velocity = - units::compound_unit>; - using Velocity_t = units::unit_t; + wpi::units::compound_unit>; + using Velocity_t = wpi::units::unit_t; using Acceleration = - units::compound_unit>; - using Acceleration_t = units::unit_t; + wpi::units::compound_unit>; + using Acceleration_t = wpi::units::unit_t; using State = typename TrapezoidProfile::State; using Constraints = typename TrapezoidProfile::Constraints; @@ -56,7 +56,7 @@ class ProfiledPIDController */ constexpr ProfiledPIDController(double Kp, double Ki, double Kd, Constraints constraints, - units::second_t period = 20_ms) + wpi::units::second_t period = 20_ms) : m_controller{Kp, Ki, Kd, period}, m_constraints{constraints}, m_profile{m_constraints} { @@ -64,7 +64,7 @@ class ProfiledPIDController int instances = detail::IncrementAndGetProfiledPIDControllerInstances(); wpi::math::MathSharedStore::ReportUsage("ProfiledPIDController", std::to_string(instances)); - wpi::SendableRegistry::Add(this, "ProfiledPIDController", instances); + wpi::util::SendableRegistry::Add(this, "ProfiledPIDController", instances); } } @@ -156,7 +156,7 @@ class ProfiledPIDController * * @return The period of the controller. */ - constexpr units::second_t GetPeriod() const { + constexpr wpi::units::second_t GetPeriod() const { return m_controller.GetPeriod(); } @@ -327,9 +327,9 @@ class ProfiledPIDController if (m_controller.IsContinuousInputEnabled()) { // Get error which is smallest distance between goal and measurement auto errorBound = (m_maximumInput - m_minimumInput) / 2.0; - auto goalMinDistance = frc::InputModulus( + auto goalMinDistance = wpi::math::InputModulus( m_goal.position - measurement, -errorBound, errorBound); - auto setpointMinDistance = frc::InputModulus( + auto setpointMinDistance = wpi::math::InputModulus( m_setpoint.position - measurement, -errorBound, errorBound); // Recompute the profile goal with the smallest error, thus giving the @@ -377,7 +377,7 @@ class ProfiledPIDController */ constexpr double Calculate( Distance_t measurement, Distance_t goal, - typename frc::TrapezoidProfile::Constraints constraints) { + typename wpi::math::TrapezoidProfile::Constraints constraints) { SetConstraints(constraints); return Calculate(measurement, goal); } @@ -413,7 +413,7 @@ class ProfiledPIDController Reset(measuredPosition, Velocity_t{0}); } - void InitSendable(wpi::SendableBuilder& builder) override { + void InitSendable(wpi::util::SendableBuilder& builder) override { builder.SetSmartDashboardType("ProfiledPIDController"); builder.AddDoubleProperty( "p", [this] { return GetP(); }, [this](double value) { SetP(value); }); @@ -447,10 +447,10 @@ class ProfiledPIDController Distance_t m_minimumInput{0}; Distance_t m_maximumInput{0}; - typename frc::TrapezoidProfile::Constraints m_constraints; + typename wpi::math::TrapezoidProfile::Constraints m_constraints; TrapezoidProfile m_profile; - typename frc::TrapezoidProfile::State m_goal; - typename frc::TrapezoidProfile::State m_setpoint; + typename wpi::math::TrapezoidProfile::State m_goal; + typename wpi::math::TrapezoidProfile::State m_setpoint; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/controller/SimpleMotorFeedforward.hpp b/wpimath/src/main/native/include/wpi/math/controller/SimpleMotorFeedforward.hpp index 2f87995c49..83fd827790 100644 --- a/wpimath/src/main/native/include/wpi/math/controller/SimpleMotorFeedforward.hpp +++ b/wpimath/src/main/native/include/wpi/math/controller/SimpleMotorFeedforward.hpp @@ -13,23 +13,23 @@ #include "wpi/units/voltage.hpp" #include "wpi/util/MathExtras.hpp" -namespace frc { +namespace wpi::math { /** * A helper class that computes feedforward voltages for a simple * permanent-magnet DC motor. */ template - requires units::length_unit || units::angle_unit + requires wpi::units::length_unit || wpi::units::angle_unit class SimpleMotorFeedforward { public: using Velocity = - units::compound_unit>; + wpi::units::compound_unit>; using Acceleration = - units::compound_unit>; - using kv_unit = units::compound_unit>; + wpi::units::compound_unit>; + using kv_unit = wpi::units::compound_unit>; using ka_unit = - units::compound_unit>; + wpi::units::compound_unit>; /** * Creates a new SimpleMotorFeedforward with the specified gains. @@ -43,20 +43,20 @@ class SimpleMotorFeedforward { * @throws IllegalArgumentException for period ≤ zero. */ constexpr SimpleMotorFeedforward( - units::volt_t kS, units::unit_t kV, - units::unit_t kA = units::unit_t(0), - units::second_t dt = 20_ms) + wpi::units::volt_t kS, wpi::units::unit_t kV, + wpi::units::unit_t kA = wpi::units::unit_t(0), + wpi::units::second_t dt = 20_ms) : kS(kS), kV(kV), kA(kA), m_dt(dt) { if (kV.value() < 0) { wpi::math::MathSharedStore::ReportError( "kV must be a non-negative number, got {}!", kV.value()); - this->kV = units::unit_t{0}; + this->kV = wpi::units::unit_t{0}; wpi::math::MathSharedStore::ReportWarning("kV defaulted to 0."); } if (kA.value() < 0) { wpi::math::MathSharedStore::ReportError( "kA must be a non-negative number, got {}!", kA.value()); - this->kA = units::unit_t{0}; + this->kA = wpi::units::unit_t{0}; wpi::math::MathSharedStore::ReportWarning("kA defaulted to 0."); } if (dt <= 0_ms) { @@ -75,7 +75,7 @@ class SimpleMotorFeedforward { * @param velocity The velocity setpoint. * @return The computed feedforward, in volts. */ - constexpr units::volt_t Calculate(units::unit_t velocity) const { + constexpr wpi::units::volt_t Calculate(wpi::units::unit_t velocity) const { return Calculate(velocity, velocity); } @@ -89,19 +89,19 @@ class SimpleMotorFeedforward { * @param nextVelocity The next velocity setpoint. * @return The computed feedforward, in volts. */ - constexpr units::volt_t Calculate( - units::unit_t currentVelocity, - units::unit_t nextVelocity) const { + constexpr wpi::units::volt_t Calculate( + wpi::units::unit_t currentVelocity, + wpi::units::unit_t nextVelocity) const { // See wpimath/algorithms.md#Simple_motor_feedforward for derivation if (kA < decltype(kA)(1e-9)) { - return kS * wpi::sgn(nextVelocity) + kV * nextVelocity; + return kS * wpi::util::sgn(nextVelocity) + kV * nextVelocity; } else { double A = -kV.value() / kA.value(); double B = 1.0 / kA.value(); double A_d = gcem::exp(A * m_dt.value()); double B_d = A > -1e-9 ? B * m_dt.value() : 1.0 / A * (A_d - 1.0) * B; - return kS * wpi::sgn(currentVelocity) + - units::volt_t{ + return kS * wpi::util::sgn(currentVelocity) + + wpi::units::volt_t{ 1.0 / B_d * (nextVelocity.value() - A_d * currentVelocity.value())}; } @@ -121,9 +121,9 @@ class SimpleMotorFeedforward { * @param acceleration The acceleration of the motor. * @return The maximum possible velocity at the given acceleration. */ - constexpr units::unit_t MaxAchievableVelocity( - units::volt_t maxVoltage, - units::unit_t acceleration) const { + constexpr wpi::units::unit_t MaxAchievableVelocity( + wpi::units::volt_t maxVoltage, + wpi::units::unit_t acceleration) const { // Assume max velocity is positive return (maxVoltage - kS - kA * acceleration) / kV; } @@ -139,9 +139,9 @@ class SimpleMotorFeedforward { * @param acceleration The acceleration of the motor. * @return The minimum possible velocity at the given acceleration. */ - constexpr units::unit_t MinAchievableVelocity( - units::volt_t maxVoltage, - units::unit_t acceleration) const { + constexpr wpi::units::unit_t MinAchievableVelocity( + wpi::units::volt_t maxVoltage, + wpi::units::unit_t acceleration) const { // Assume min velocity is positive, ks flips sign return (-maxVoltage + kS - kA * acceleration) / kV; } @@ -157,9 +157,9 @@ class SimpleMotorFeedforward { * @param velocity The velocity of the motor. * @return The maximum possible acceleration at the given velocity. */ - constexpr units::unit_t MaxAchievableAcceleration( - units::volt_t maxVoltage, units::unit_t velocity) const { - return (maxVoltage - kS * wpi::sgn(velocity) - kV * velocity) / kA; + constexpr wpi::units::unit_t MaxAchievableAcceleration( + wpi::units::volt_t maxVoltage, wpi::units::unit_t velocity) const { + return (maxVoltage - kS * wpi::util::sgn(velocity) - kV * velocity) / kA; } /** @@ -173,8 +173,8 @@ class SimpleMotorFeedforward { * @param velocity The velocity of the motor. * @return The minimum possible acceleration at the given velocity. */ - constexpr units::unit_t MinAchievableAcceleration( - units::volt_t maxVoltage, units::unit_t velocity) const { + constexpr wpi::units::unit_t MinAchievableAcceleration( + wpi::units::volt_t maxVoltage, wpi::units::unit_t velocity) const { return MaxAchievableAcceleration(-maxVoltage, velocity); } @@ -183,62 +183,62 @@ class SimpleMotorFeedforward { * * @param kS The static gain. */ - constexpr void SetKs(units::volt_t kS) { this->kS = kS; } + constexpr void SetKs(wpi::units::volt_t kS) { this->kS = kS; } /** * Sets the velocity gain. * * @param kV The velocity gain. */ - constexpr void SetKv(units::unit_t kV) { this->kV = kV; } + constexpr void SetKv(wpi::units::unit_t kV) { this->kV = kV; } /** * Sets the acceleration gain. * * @param kA The acceleration gain. */ - constexpr void SetKa(units::unit_t kA) { this->kA = kA; } + constexpr void SetKa(wpi::units::unit_t kA) { this->kA = kA; } /** * Returns the static gain. * * @return The static gain. */ - constexpr units::volt_t GetKs() const { return kS; } + constexpr wpi::units::volt_t GetKs() const { return kS; } /** * Returns the velocity gain. * * @return The velocity gain. */ - constexpr units::unit_t GetKv() const { return kV; } + constexpr wpi::units::unit_t GetKv() const { return kV; } /** * Returns the acceleration gain. * * @return The acceleration gain. */ - constexpr units::unit_t GetKa() const { return kA; } + constexpr wpi::units::unit_t GetKa() const { return kA; } /** * Returns the period. * * @return The period. */ - constexpr units::second_t GetDt() const { return m_dt; } + constexpr wpi::units::second_t GetDt() const { return m_dt; } private: /** The static gain. */ - units::volt_t kS; + wpi::units::volt_t kS; /** The velocity gain. */ - units::unit_t kV; + wpi::units::unit_t kV; /** The acceleration gain. */ - units::unit_t kA; + wpi::units::unit_t kA; /** The period. */ - units::second_t m_dt; + wpi::units::second_t m_dt; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/controller/proto/ArmFeedforwardProto.hpp b/wpimath/src/main/native/include/wpi/math/controller/proto/ArmFeedforwardProto.hpp index ce8ca33f37..abf98630ac 100644 --- a/wpimath/src/main/native/include/wpi/math/controller/proto/ArmFeedforwardProto.hpp +++ b/wpimath/src/main/native/include/wpi/math/controller/proto/ArmFeedforwardProto.hpp @@ -11,10 +11,10 @@ #include "wpimath/protobuf/controller.npb.h" template <> -struct WPILIB_DLLEXPORT wpi::Protobuf { +struct WPILIB_DLLEXPORT wpi::util::Protobuf { using MessageStruct = wpi_proto_ProtobufArmFeedforward; - using InputStream = wpi::ProtoInputStream; - using OutputStream = wpi::ProtoOutputStream; - static std::optional Unpack(InputStream& stream); - static bool Pack(OutputStream& stream, const frc::ArmFeedforward& value); + using InputStream = wpi::util::ProtoInputStream; + using OutputStream = wpi::util::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const wpi::math::ArmFeedforward& value); }; diff --git a/wpimath/src/main/native/include/wpi/math/controller/proto/DifferentialDriveFeedforwardProto.hpp b/wpimath/src/main/native/include/wpi/math/controller/proto/DifferentialDriveFeedforwardProto.hpp index 156fb67c96..575fdb13e5 100644 --- a/wpimath/src/main/native/include/wpi/math/controller/proto/DifferentialDriveFeedforwardProto.hpp +++ b/wpimath/src/main/native/include/wpi/math/controller/proto/DifferentialDriveFeedforwardProto.hpp @@ -11,13 +11,13 @@ #include "wpimath/protobuf/controller.npb.h" template <> -struct WPILIB_DLLEXPORT wpi::Protobuf { +struct WPILIB_DLLEXPORT wpi::util::Protobuf { using MessageStruct = wpi_proto_ProtobufDifferentialDriveFeedforward; - using InputStream = wpi::ProtoInputStream; + using InputStream = wpi::util::ProtoInputStream; using OutputStream = - wpi::ProtoOutputStream; - static std::optional Unpack( + wpi::util::ProtoOutputStream; + static std::optional Unpack( InputStream& stream); static bool Pack(OutputStream& stream, - const frc::DifferentialDriveFeedforward& value); + const wpi::math::DifferentialDriveFeedforward& value); }; diff --git a/wpimath/src/main/native/include/wpi/math/controller/proto/DifferentialDriveWheelVoltagesProto.hpp b/wpimath/src/main/native/include/wpi/math/controller/proto/DifferentialDriveWheelVoltagesProto.hpp index 491a84ede7..6b6308f448 100644 --- a/wpimath/src/main/native/include/wpi/math/controller/proto/DifferentialDriveWheelVoltagesProto.hpp +++ b/wpimath/src/main/native/include/wpi/math/controller/proto/DifferentialDriveWheelVoltagesProto.hpp @@ -11,14 +11,14 @@ #include "wpimath/protobuf/controller.npb.h" template <> -struct WPILIB_DLLEXPORT wpi::Protobuf { +struct WPILIB_DLLEXPORT wpi::util::Protobuf { using MessageStruct = wpi_proto_ProtobufDifferentialDriveWheelVoltages; using InputStream = - wpi::ProtoInputStream; + wpi::util::ProtoInputStream; using OutputStream = - wpi::ProtoOutputStream; - static std::optional Unpack( + wpi::util::ProtoOutputStream; + static std::optional Unpack( InputStream& stream); static bool Pack(OutputStream& stream, - const frc::DifferentialDriveWheelVoltages& value); + const wpi::math::DifferentialDriveWheelVoltages& value); }; diff --git a/wpimath/src/main/native/include/wpi/math/controller/proto/ElevatorFeedforwardProto.hpp b/wpimath/src/main/native/include/wpi/math/controller/proto/ElevatorFeedforwardProto.hpp index e585e3dc14..a0a97da5e2 100644 --- a/wpimath/src/main/native/include/wpi/math/controller/proto/ElevatorFeedforwardProto.hpp +++ b/wpimath/src/main/native/include/wpi/math/controller/proto/ElevatorFeedforwardProto.hpp @@ -11,10 +11,10 @@ #include "wpimath/protobuf/controller.npb.h" template <> -struct WPILIB_DLLEXPORT wpi::Protobuf { +struct WPILIB_DLLEXPORT wpi::util::Protobuf { using MessageStruct = wpi_proto_ProtobufElevatorFeedforward; - using InputStream = wpi::ProtoInputStream; - using OutputStream = wpi::ProtoOutputStream; - static std::optional Unpack(InputStream& stream); - static bool Pack(OutputStream& stream, const frc::ElevatorFeedforward& value); + using InputStream = wpi::util::ProtoInputStream; + using OutputStream = wpi::util::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const wpi::math::ElevatorFeedforward& value); }; diff --git a/wpimath/src/main/native/include/wpi/math/controller/proto/SimpleMotorFeedforwardProto.hpp b/wpimath/src/main/native/include/wpi/math/controller/proto/SimpleMotorFeedforwardProto.hpp index f4d0101c88..1008e8cb5d 100644 --- a/wpimath/src/main/native/include/wpi/math/controller/proto/SimpleMotorFeedforwardProto.hpp +++ b/wpimath/src/main/native/include/wpi/math/controller/proto/SimpleMotorFeedforwardProto.hpp @@ -11,48 +11,48 @@ #include "wpimath/protobuf/controller.npb.h" // Everything is converted into units for -// frc::SimpleMotorFeedforward or -// frc::SimpleMotorFeedforward +// wpi::math::SimpleMotorFeedforward or +// wpi::math::SimpleMotorFeedforward template - requires units::length_unit || units::angle_unit -struct wpi::Protobuf> { + requires wpi::units::length_unit || wpi::units::angle_unit +struct wpi::util::Protobuf> { using MessageStruct = wpi_proto_ProtobufSimpleMotorFeedforward; using InputStream = - wpi::ProtoInputStream>; + wpi::util::ProtoInputStream>; using OutputStream = - wpi::ProtoOutputStream>; + wpi::util::ProtoOutputStream>; - static std::optional> Unpack( + static std::optional> Unpack( InputStream& stream) { using BaseUnit = - units::unit, units::traits::base_unit_of>; - using BaseFeedforward = frc::SimpleMotorFeedforward; + wpi::units::unit, wpi::units::traits::base_unit_of>; + using BaseFeedforward = wpi::math::SimpleMotorFeedforward; wpi_proto_ProtobufSimpleMotorFeedforward msg; if (!stream.Decode(msg)) { return {}; } - return frc::SimpleMotorFeedforward{ - units::volt_t{msg.ks}, - units::unit_t{msg.kv}, - units::unit_t{msg.ka}, - units::second_t{msg.dt}, + return wpi::math::SimpleMotorFeedforward{ + wpi::units::volt_t{msg.ks}, + wpi::units::unit_t{msg.kv}, + wpi::units::unit_t{msg.ka}, + wpi::units::second_t{msg.dt}, }; } static bool Pack(OutputStream& stream, - const frc::SimpleMotorFeedforward& value) { + const wpi::math::SimpleMotorFeedforward& value) { using BaseUnit = - units::unit, units::traits::base_unit_of>; - using BaseFeedforward = frc::SimpleMotorFeedforward; + wpi::units::unit, wpi::units::traits::base_unit_of>; + using BaseFeedforward = wpi::math::SimpleMotorFeedforward; wpi_proto_ProtobufSimpleMotorFeedforward msg{ .ks = value.GetKs().value(), - .kv = units::unit_t{value.GetKv()} + .kv = wpi::units::unit_t{value.GetKv()} .value(), - .ka = units::unit_t{value.GetKa()} + .ka = wpi::units::unit_t{value.GetKa()} .value(), - .dt = units::second_t{value.GetDt()}.value(), + .dt = wpi::units::second_t{value.GetDt()}.value(), }; return stream.Encode(msg); } diff --git a/wpimath/src/main/native/include/wpi/math/controller/struct/ArmFeedforwardStruct.hpp b/wpimath/src/main/native/include/wpi/math/controller/struct/ArmFeedforwardStruct.hpp index f4889e2820..b107258299 100644 --- a/wpimath/src/main/native/include/wpi/math/controller/struct/ArmFeedforwardStruct.hpp +++ b/wpimath/src/main/native/include/wpi/math/controller/struct/ArmFeedforwardStruct.hpp @@ -9,15 +9,15 @@ #include "wpi/util/struct/Struct.hpp" template <> -struct WPILIB_DLLEXPORT wpi::Struct { +struct WPILIB_DLLEXPORT wpi::util::Struct { static constexpr std::string_view GetTypeName() { return "ArmFeedforward"; } static constexpr size_t GetSize() { return 32; } static constexpr std::string_view GetSchema() { return "double ks;double kg;double kv;double ka"; } - static frc::ArmFeedforward Unpack(std::span data); - static void Pack(std::span data, const frc::ArmFeedforward& value); + static wpi::math::ArmFeedforward Unpack(std::span data); + static void Pack(std::span data, const wpi::math::ArmFeedforward& value); }; -static_assert(wpi::StructSerializable); +static_assert(wpi::util::StructSerializable); diff --git a/wpimath/src/main/native/include/wpi/math/controller/struct/DifferentialDriveFeedforwardStruct.hpp b/wpimath/src/main/native/include/wpi/math/controller/struct/DifferentialDriveFeedforwardStruct.hpp index bbdbd1aac9..5302dfe68d 100644 --- a/wpimath/src/main/native/include/wpi/math/controller/struct/DifferentialDriveFeedforwardStruct.hpp +++ b/wpimath/src/main/native/include/wpi/math/controller/struct/DifferentialDriveFeedforwardStruct.hpp @@ -9,7 +9,7 @@ #include "wpi/util/struct/Struct.hpp" template <> -struct WPILIB_DLLEXPORT wpi::Struct { +struct WPILIB_DLLEXPORT wpi::util::Struct { static constexpr std::string_view GetTypeName() { return "DifferentialDriveFeedforward"; } @@ -19,10 +19,10 @@ struct WPILIB_DLLEXPORT wpi::Struct { "ka_angular"; } - static frc::DifferentialDriveFeedforward Unpack( + static wpi::math::DifferentialDriveFeedforward Unpack( std::span data); static void Pack(std::span data, - const frc::DifferentialDriveFeedforward& value); + const wpi::math::DifferentialDriveFeedforward& value); }; -static_assert(wpi::StructSerializable); +static_assert(wpi::util::StructSerializable); diff --git a/wpimath/src/main/native/include/wpi/math/controller/struct/DifferentialDriveWheelVoltagesStruct.hpp b/wpimath/src/main/native/include/wpi/math/controller/struct/DifferentialDriveWheelVoltagesStruct.hpp index d1f40c3262..80f0484964 100644 --- a/wpimath/src/main/native/include/wpi/math/controller/struct/DifferentialDriveWheelVoltagesStruct.hpp +++ b/wpimath/src/main/native/include/wpi/math/controller/struct/DifferentialDriveWheelVoltagesStruct.hpp @@ -9,7 +9,7 @@ #include "wpi/util/struct/Struct.hpp" template <> -struct WPILIB_DLLEXPORT wpi::Struct { +struct WPILIB_DLLEXPORT wpi::util::Struct { static constexpr std::string_view GetTypeName() { return "DifferentialDriveWheelVoltages"; } @@ -18,10 +18,10 @@ struct WPILIB_DLLEXPORT wpi::Struct { return "double left;double right"; } - static frc::DifferentialDriveWheelVoltages Unpack( + static wpi::math::DifferentialDriveWheelVoltages Unpack( std::span data); static void Pack(std::span data, - const frc::DifferentialDriveWheelVoltages& value); + const wpi::math::DifferentialDriveWheelVoltages& value); }; -static_assert(wpi::StructSerializable); +static_assert(wpi::util::StructSerializable); diff --git a/wpimath/src/main/native/include/wpi/math/controller/struct/ElevatorFeedforwardStruct.hpp b/wpimath/src/main/native/include/wpi/math/controller/struct/ElevatorFeedforwardStruct.hpp index 1927eedfbb..9a9a24d141 100644 --- a/wpimath/src/main/native/include/wpi/math/controller/struct/ElevatorFeedforwardStruct.hpp +++ b/wpimath/src/main/native/include/wpi/math/controller/struct/ElevatorFeedforwardStruct.hpp @@ -9,7 +9,7 @@ #include "wpi/util/struct/Struct.hpp" template <> -struct WPILIB_DLLEXPORT wpi::Struct { +struct WPILIB_DLLEXPORT wpi::util::Struct { static constexpr std::string_view GetTypeName() { return "ElevatorFeedforward"; } @@ -18,9 +18,9 @@ struct WPILIB_DLLEXPORT wpi::Struct { return "double ks;double kg;double kv;double ka"; } - static frc::ElevatorFeedforward Unpack(std::span data); + static wpi::math::ElevatorFeedforward Unpack(std::span data); static void Pack(std::span data, - const frc::ElevatorFeedforward& value); + const wpi::math::ElevatorFeedforward& value); }; -static_assert(wpi::StructSerializable); +static_assert(wpi::util::StructSerializable); diff --git a/wpimath/src/main/native/include/wpi/math/controller/struct/SimpleMotorFeedforwardStruct.hpp b/wpimath/src/main/native/include/wpi/math/controller/struct/SimpleMotorFeedforwardStruct.hpp index c984128612..4e7898159b 100644 --- a/wpimath/src/main/native/include/wpi/math/controller/struct/SimpleMotorFeedforwardStruct.hpp +++ b/wpimath/src/main/native/include/wpi/math/controller/struct/SimpleMotorFeedforwardStruct.hpp @@ -9,12 +9,12 @@ #include "wpi/util/struct/Struct.hpp" // Everything is converted into units for -// frc::SimpleMotorFeedforward or -// frc::SimpleMotorFeedforward +// wpi::math::SimpleMotorFeedforward or +// wpi::math::SimpleMotorFeedforward template - requires units::length_unit || units::angle_unit -struct wpi::Struct> { + requires wpi::units::length_unit || wpi::units::angle_unit +struct wpi::util::Struct> { static constexpr std::string_view GetTypeName() { return "SimpleMotorFeedforward"; } @@ -23,46 +23,46 @@ struct wpi::Struct> { return "double ks;double kv;double ka;double dt"; } - static frc::SimpleMotorFeedforward Unpack( + static wpi::math::SimpleMotorFeedforward Unpack( std::span data) { using BaseUnit = - units::unit, units::traits::base_unit_of>; - using BaseFeedforward = frc::SimpleMotorFeedforward; + wpi::units::unit, wpi::units::traits::base_unit_of>; + using BaseFeedforward = wpi::math::SimpleMotorFeedforward; constexpr size_t kKsOff = 0; constexpr size_t kKvOff = kKsOff + 8; constexpr size_t kKaOff = kKvOff + 8; constexpr size_t kDtOff = kKaOff + 8; - return {units::volt_t{wpi::UnpackStruct(data)}, - units::unit_t{ - wpi::UnpackStruct(data)}, - units::unit_t{ - wpi::UnpackStruct(data)}, - units::second_t{wpi::UnpackStruct(data)}}; + return {wpi::units::volt_t{wpi::util::UnpackStruct(data)}, + wpi::units::unit_t{ + wpi::util::UnpackStruct(data)}, + wpi::units::unit_t{ + wpi::util::UnpackStruct(data)}, + wpi::units::second_t{wpi::util::UnpackStruct(data)}}; } static void Pack(std::span data, - const frc::SimpleMotorFeedforward& value) { + const wpi::math::SimpleMotorFeedforward& value) { using BaseUnit = - units::unit, units::traits::base_unit_of>; - using BaseFeedforward = frc::SimpleMotorFeedforward; + wpi::units::unit, wpi::units::traits::base_unit_of>; + using BaseFeedforward = wpi::math::SimpleMotorFeedforward; constexpr size_t kKsOff = 0; constexpr size_t kKvOff = kKsOff + 8; constexpr size_t kKaOff = kKvOff + 8; constexpr size_t kDtOff = kKaOff + 8; - wpi::PackStruct(data, value.GetKs().value()); - wpi::PackStruct( - data, units::unit_t{value.GetKv()} + wpi::util::PackStruct(data, value.GetKs().value()); + wpi::util::PackStruct( + data, wpi::units::unit_t{value.GetKv()} .value()); - wpi::PackStruct( - data, units::unit_t{value.GetKa()} + wpi::util::PackStruct( + data, wpi::units::unit_t{value.GetKa()} .value()); - wpi::PackStruct(data, units::second_t{value.GetDt()}.value()); + wpi::util::PackStruct(data, wpi::units::second_t{value.GetDt()}.value()); } }; static_assert( - wpi::StructSerializable>); + wpi::util::StructSerializable>); static_assert( - wpi::StructSerializable>); + wpi::util::StructSerializable>); static_assert( - wpi::StructSerializable>); + wpi::util::StructSerializable>); diff --git a/wpimath/src/main/native/include/wpi/math/estimator/AngleStatistics.hpp b/wpimath/src/main/native/include/wpi/math/estimator/AngleStatistics.hpp index 2b2b86ddd0..263bd99cf6 100644 --- a/wpimath/src/main/native/include/wpi/math/estimator/AngleStatistics.hpp +++ b/wpimath/src/main/native/include/wpi/math/estimator/AngleStatistics.hpp @@ -10,7 +10,7 @@ #include "wpi/math/linalg/EigenCore.hpp" #include "wpi/math/util/MathUtil.hpp" -namespace frc { +namespace wpi::math { /** * Subtracts a and b while normalizing the resulting value in the selected row @@ -26,7 +26,7 @@ Vectord AngleResidual(const Vectord& a, const Vectord& b, int angleStateIdx) { Vectord ret = a - b; ret[angleStateIdx] = - AngleModulus(units::radian_t{ret[angleStateIdx]}).value(); + AngleModulus(wpi::units::radian_t{ret[angleStateIdx]}).value(); return ret; } @@ -124,4 +124,4 @@ AngleMean(int angleStateIdx) { }; } -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/estimator/DifferentialDrivePoseEstimator.hpp b/wpimath/src/main/native/include/wpi/math/estimator/DifferentialDrivePoseEstimator.hpp index 2fe52337fb..d59a144471 100644 --- a/wpimath/src/main/native/include/wpi/math/estimator/DifferentialDrivePoseEstimator.hpp +++ b/wpimath/src/main/native/include/wpi/math/estimator/DifferentialDrivePoseEstimator.hpp @@ -13,7 +13,7 @@ #include "wpi/util/SymbolExports.hpp" #include "wpi/util/array.hpp" -namespace frc { +namespace wpi::math { /** * This class wraps Differential Drive Odometry to fuse latency-compensated * vision measurements with differential drive encoder measurements. It will @@ -51,8 +51,8 @@ class WPILIB_DLLEXPORT DifferentialDrivePoseEstimator */ DifferentialDrivePoseEstimator(DifferentialDriveKinematics& kinematics, const Rotation2d& gyroAngle, - units::meter_t leftDistance, - units::meter_t rightDistance, + wpi::units::meter_t leftDistance, + wpi::units::meter_t rightDistance, const Pose2d& initialPose); /** @@ -74,9 +74,9 @@ class WPILIB_DLLEXPORT DifferentialDrivePoseEstimator */ DifferentialDrivePoseEstimator( DifferentialDriveKinematics& kinematics, const Rotation2d& gyroAngle, - units::meter_t leftDistance, units::meter_t rightDistance, - const Pose2d& initialPose, const wpi::array& stateStdDevs, - const wpi::array& visionMeasurementStdDevs); + wpi::units::meter_t leftDistance, wpi::units::meter_t rightDistance, + const Pose2d& initialPose, const wpi::util::array& stateStdDevs, + const wpi::util::array& visionMeasurementStdDevs); /** * Resets the robot's position on the field. @@ -86,8 +86,8 @@ class WPILIB_DLLEXPORT DifferentialDrivePoseEstimator * @param rightDistance The distance traveled by the right encoder. * @param pose The estimated pose of the robot on the field. */ - void ResetPosition(const Rotation2d& gyroAngle, units::meter_t leftDistance, - units::meter_t rightDistance, const Pose2d& pose) { + void ResetPosition(const Rotation2d& gyroAngle, wpi::units::meter_t leftDistance, + wpi::units::meter_t rightDistance, const Pose2d& pose) { PoseEstimator::ResetPosition(gyroAngle, {leftDistance, rightDistance}, pose); } @@ -102,8 +102,8 @@ class WPILIB_DLLEXPORT DifferentialDrivePoseEstimator * * @return The estimated pose of the robot. */ - Pose2d Update(const Rotation2d& gyroAngle, units::meter_t leftDistance, - units::meter_t rightDistance) { + Pose2d Update(const Rotation2d& gyroAngle, wpi::units::meter_t leftDistance, + wpi::units::meter_t rightDistance) { return PoseEstimator::Update(gyroAngle, {leftDistance, rightDistance}); } @@ -118,10 +118,10 @@ class WPILIB_DLLEXPORT DifferentialDrivePoseEstimator * * @return The estimated pose of the robot. */ - Pose2d UpdateWithTime(units::second_t currentTime, + Pose2d UpdateWithTime(wpi::units::second_t currentTime, const Rotation2d& gyroAngle, - units::meter_t leftDistance, - units::meter_t rightDistance) { + wpi::units::meter_t leftDistance, + wpi::units::meter_t rightDistance) { return PoseEstimator::UpdateWithTime(currentTime, gyroAngle, {leftDistance, rightDistance}); } @@ -130,4 +130,4 @@ class WPILIB_DLLEXPORT DifferentialDrivePoseEstimator DifferentialDriveOdometry m_odometryImpl; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/estimator/DifferentialDrivePoseEstimator3d.hpp b/wpimath/src/main/native/include/wpi/math/estimator/DifferentialDrivePoseEstimator3d.hpp index 136dd73bbe..07a1857983 100644 --- a/wpimath/src/main/native/include/wpi/math/estimator/DifferentialDrivePoseEstimator3d.hpp +++ b/wpimath/src/main/native/include/wpi/math/estimator/DifferentialDrivePoseEstimator3d.hpp @@ -13,7 +13,7 @@ #include "wpi/util/SymbolExports.hpp" #include "wpi/util/array.hpp" -namespace frc { +namespace wpi::math { /** * This class wraps Differential Drive Odometry to fuse latency-compensated * vision measurements with differential drive encoder measurements. It will @@ -56,8 +56,8 @@ class WPILIB_DLLEXPORT DifferentialDrivePoseEstimator3d */ DifferentialDrivePoseEstimator3d(DifferentialDriveKinematics& kinematics, const Rotation3d& gyroAngle, - units::meter_t leftDistance, - units::meter_t rightDistance, + wpi::units::meter_t leftDistance, + wpi::units::meter_t rightDistance, const Pose3d& initialPose); /** @@ -79,9 +79,9 @@ class WPILIB_DLLEXPORT DifferentialDrivePoseEstimator3d */ DifferentialDrivePoseEstimator3d( DifferentialDriveKinematics& kinematics, const Rotation3d& gyroAngle, - units::meter_t leftDistance, units::meter_t rightDistance, - const Pose3d& initialPose, const wpi::array& stateStdDevs, - const wpi::array& visionMeasurementStdDevs); + wpi::units::meter_t leftDistance, wpi::units::meter_t rightDistance, + const Pose3d& initialPose, const wpi::util::array& stateStdDevs, + const wpi::util::array& visionMeasurementStdDevs); /** * Resets the robot's position on the field. @@ -91,8 +91,8 @@ class WPILIB_DLLEXPORT DifferentialDrivePoseEstimator3d * @param rightDistance The distance traveled by the right encoder. * @param pose The estimated pose of the robot on the field. */ - void ResetPosition(const Rotation3d& gyroAngle, units::meter_t leftDistance, - units::meter_t rightDistance, const Pose3d& pose) { + void ResetPosition(const Rotation3d& gyroAngle, wpi::units::meter_t leftDistance, + wpi::units::meter_t rightDistance, const Pose3d& pose) { PoseEstimator3d::ResetPosition(gyroAngle, {leftDistance, rightDistance}, pose); } @@ -107,8 +107,8 @@ class WPILIB_DLLEXPORT DifferentialDrivePoseEstimator3d * * @return The estimated pose of the robot. */ - Pose3d Update(const Rotation3d& gyroAngle, units::meter_t leftDistance, - units::meter_t rightDistance) { + Pose3d Update(const Rotation3d& gyroAngle, wpi::units::meter_t leftDistance, + wpi::units::meter_t rightDistance) { return PoseEstimator3d::Update(gyroAngle, {leftDistance, rightDistance}); } @@ -123,10 +123,10 @@ class WPILIB_DLLEXPORT DifferentialDrivePoseEstimator3d * * @return The estimated pose of the robot. */ - Pose3d UpdateWithTime(units::second_t currentTime, + Pose3d UpdateWithTime(wpi::units::second_t currentTime, const Rotation3d& gyroAngle, - units::meter_t leftDistance, - units::meter_t rightDistance) { + wpi::units::meter_t leftDistance, + wpi::units::meter_t rightDistance) { return PoseEstimator3d::UpdateWithTime(currentTime, gyroAngle, {leftDistance, rightDistance}); } @@ -135,4 +135,4 @@ class WPILIB_DLLEXPORT DifferentialDrivePoseEstimator3d DifferentialDriveOdometry3d m_odometryImpl; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/estimator/ExtendedKalmanFilter.hpp b/wpimath/src/main/native/include/wpi/math/estimator/ExtendedKalmanFilter.hpp index 96c74b09f7..103da61dd2 100644 --- a/wpimath/src/main/native/include/wpi/math/estimator/ExtendedKalmanFilter.hpp +++ b/wpimath/src/main/native/include/wpi/math/estimator/ExtendedKalmanFilter.hpp @@ -20,7 +20,7 @@ #include "wpi/units/time.hpp" #include "wpi/util/array.hpp" -namespace frc { +namespace wpi::math { /** * A Kalman filter combines predictions from a model and measurements to give an @@ -53,8 +53,8 @@ class ExtendedKalmanFilter { using InputVector = Vectord; using OutputVector = Vectord; - using StateArray = wpi::array; - using OutputArray = wpi::array; + using StateArray = wpi::util::array; + using OutputArray = wpi::util::array; using StateMatrix = Matrixd; @@ -77,7 +77,7 @@ class ExtendedKalmanFilter { std::function f, std::function h, const StateArray& stateStdDevs, const OutputArray& measurementStdDevs, - units::second_t dt) + wpi::units::second_t dt) : m_f(std::move(f)), m_h(std::move(h)) { m_contQ = MakeCovMatrix(stateStdDevs); m_contR = MakeCovMatrix(measurementStdDevs); @@ -165,7 +165,7 @@ class ExtendedKalmanFilter { residualFuncY, std::function addFuncX, - units::second_t dt) + wpi::units::second_t dt) : m_f(std::move(f)), m_h(std::move(h)), m_residualFuncY(std::move(residualFuncY)), @@ -284,7 +284,7 @@ class ExtendedKalmanFilter { * @param u New control input from controller. * @param dt Timestep for prediction. */ - void Predict(const InputVector& u, units::second_t dt) { + void Predict(const InputVector& u, wpi::units::second_t dt) { // Find continuous A StateMatrix contA = NumericalJacobianX(m_f, m_xHat, u); @@ -423,9 +423,9 @@ class ExtendedKalmanFilter { StateMatrix m_P; StateMatrix m_contQ; Matrixd m_contR; - units::second_t m_dt; + wpi::units::second_t m_dt; StateMatrix m_initP; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/estimator/KalmanFilter.hpp b/wpimath/src/main/native/include/wpi/math/estimator/KalmanFilter.hpp index 12b98de097..67178aa589 100644 --- a/wpimath/src/main/native/include/wpi/math/estimator/KalmanFilter.hpp +++ b/wpimath/src/main/native/include/wpi/math/estimator/KalmanFilter.hpp @@ -20,7 +20,7 @@ #include "wpi/units/time.hpp" #include "wpi/util/array.hpp" -namespace frc { +namespace wpi::math { /** * A Kalman filter combines predictions from a model and measurements to give an @@ -49,8 +49,8 @@ class KalmanFilter { using InputVector = Vectord; using OutputVector = Vectord; - using StateArray = wpi::array; - using OutputArray = wpi::array; + using StateArray = wpi::util::array; + using OutputArray = wpi::util::array; using StateMatrix = Matrixd; @@ -69,7 +69,7 @@ class KalmanFilter { */ KalmanFilter(LinearSystem& plant, const StateArray& stateStdDevs, - const OutputArray& measurementStdDevs, units::second_t dt) { + const OutputArray& measurementStdDevs, wpi::units::second_t dt) { m_plant = &plant; m_contQ = MakeCovMatrix(stateStdDevs); @@ -181,7 +181,7 @@ class KalmanFilter { * @param u New control input from controller. * @param dt Timestep for prediction. */ - void Predict(const InputVector& u, units::second_t dt) { + void Predict(const InputVector& u, wpi::units::second_t dt) { // Find discrete A and Q StateMatrix discA; StateMatrix discQ; @@ -257,7 +257,7 @@ class KalmanFilter { StateMatrix m_P; StateMatrix m_contQ; Matrixd m_contR; - units::second_t m_dt; + wpi::units::second_t m_dt; StateMatrix m_initP; }; @@ -267,4 +267,4 @@ extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT) extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT) KalmanFilter<2, 1, 1>; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/estimator/KalmanFilterLatencyCompensator.hpp b/wpimath/src/main/native/include/wpi/math/estimator/KalmanFilterLatencyCompensator.hpp index 3cdc7fb3b1..dc0dc4052e 100644 --- a/wpimath/src/main/native/include/wpi/math/estimator/KalmanFilterLatencyCompensator.hpp +++ b/wpimath/src/main/native/include/wpi/math/estimator/KalmanFilterLatencyCompensator.hpp @@ -14,7 +14,7 @@ #include "wpi/units/math.hpp" #include "wpi/units/time.hpp" -namespace frc { +namespace wpi::math { /** * This class incorporates time-delayed measurements into a Kalman filter's @@ -62,7 +62,7 @@ class KalmanFilterLatencyCompensator { * @param timestamp The timestamp of the state. */ void AddObserverState(const KalmanFilterType& observer, Vectord u, - Vectord localY, units::second_t timestamp) { + Vectord localY, wpi::units::second_t timestamp) { // Add the new state into the vector. m_pastObserverSnapshots.emplace_back(timestamp, ObserverSnapshot{observer, u, localY}); @@ -86,10 +86,10 @@ class KalmanFilterLatencyCompensator { */ template void ApplyPastGlobalMeasurement( - KalmanFilterType* observer, units::second_t nominalDt, Vectord y, + KalmanFilterType* observer, wpi::units::second_t nominalDt, Vectord y, std::function& u, const Vectord& y)> globalMeasurementCorrect, - units::second_t timestamp) { + wpi::units::second_t timestamp) { if (m_pastObserverSnapshots.size() == 0) { // State map was empty, which means that we got a measurement right at // startup. The only thing we can do is ignore the measurement. @@ -130,14 +130,14 @@ class KalmanFilterLatencyCompensator { int prevIdx = nextIdx - 1; // Find the snapshot closest in time to global measurement - units::second_t prevTimeDiff = - units::math::abs(timestamp - m_pastObserverSnapshots[prevIdx].first); - units::second_t nextTimeDiff = - units::math::abs(timestamp - m_pastObserverSnapshots[nextIdx].first); + wpi::units::second_t prevTimeDiff = + wpi::units::math::abs(timestamp - m_pastObserverSnapshots[prevIdx].first); + wpi::units::second_t nextTimeDiff = + wpi::units::math::abs(timestamp - m_pastObserverSnapshots[nextIdx].first); indexOfClosestEntry = prevTimeDiff < nextTimeDiff ? prevIdx : nextIdx; } - units::second_t lastTimestamp = + wpi::units::second_t lastTimestamp = m_pastObserverSnapshots[indexOfClosestEntry].first - nominalDt; // We will now go back in time to the state of the system at the time when @@ -174,7 +174,7 @@ class KalmanFilterLatencyCompensator { private: static constexpr size_t kMaxPastObserverStates = 300; - std::vector> + std::vector> m_pastObserverSnapshots; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/estimator/MecanumDrivePoseEstimator.hpp b/wpimath/src/main/native/include/wpi/math/estimator/MecanumDrivePoseEstimator.hpp index 3db122aad7..ce390e8178 100644 --- a/wpimath/src/main/native/include/wpi/math/estimator/MecanumDrivePoseEstimator.hpp +++ b/wpimath/src/main/native/include/wpi/math/estimator/MecanumDrivePoseEstimator.hpp @@ -16,7 +16,7 @@ #include "wpi/util/SymbolExports.hpp" #include "wpi/util/array.hpp" -namespace frc { +namespace wpi::math { /** * This class wraps Mecanum Drive Odometry to fuse latency-compensated * vision measurements with mecanum drive encoder velocity measurements. It will @@ -74,11 +74,11 @@ class WPILIB_DLLEXPORT MecanumDrivePoseEstimator MecanumDrivePoseEstimator( MecanumDriveKinematics& kinematics, const Rotation2d& gyroAngle, const MecanumDriveWheelPositions& wheelPositions, - const Pose2d& initialPose, const wpi::array& stateStdDevs, - const wpi::array& visionMeasurementStdDevs); + const Pose2d& initialPose, const wpi::util::array& stateStdDevs, + const wpi::util::array& visionMeasurementStdDevs); private: MecanumDriveOdometry m_odometryImpl; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/estimator/MecanumDrivePoseEstimator3d.hpp b/wpimath/src/main/native/include/wpi/math/estimator/MecanumDrivePoseEstimator3d.hpp index 171c90a212..d44db79225 100644 --- a/wpimath/src/main/native/include/wpi/math/estimator/MecanumDrivePoseEstimator3d.hpp +++ b/wpimath/src/main/native/include/wpi/math/estimator/MecanumDrivePoseEstimator3d.hpp @@ -16,7 +16,7 @@ #include "wpi/util/SymbolExports.hpp" #include "wpi/util/array.hpp" -namespace frc { +namespace wpi::math { /** * This class wraps Mecanum Drive Odometry to fuse latency-compensated * vision measurements with mecanum drive encoder velocity measurements. It will @@ -79,11 +79,11 @@ class WPILIB_DLLEXPORT MecanumDrivePoseEstimator3d MecanumDrivePoseEstimator3d( MecanumDriveKinematics& kinematics, const Rotation3d& gyroAngle, const MecanumDriveWheelPositions& wheelPositions, - const Pose3d& initialPose, const wpi::array& stateStdDevs, - const wpi::array& visionMeasurementStdDevs); + const Pose3d& initialPose, const wpi::util::array& stateStdDevs, + const wpi::util::array& visionMeasurementStdDevs); private: MecanumDriveOdometry3d m_odometryImpl; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/estimator/MerweScaledSigmaPoints.hpp b/wpimath/src/main/native/include/wpi/math/estimator/MerweScaledSigmaPoints.hpp index 558d1af014..e008debc71 100644 --- a/wpimath/src/main/native/include/wpi/math/estimator/MerweScaledSigmaPoints.hpp +++ b/wpimath/src/main/native/include/wpi/math/estimator/MerweScaledSigmaPoints.hpp @@ -8,7 +8,7 @@ #include "wpi/math/linalg/EigenCore.hpp" -namespace frc { +namespace wpi::math { /** * Generates sigma points and weights according to Van der Merwe's 2004 @@ -125,4 +125,4 @@ class MerweScaledSigmaPoints { } }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/estimator/MerweUKF.hpp b/wpimath/src/main/native/include/wpi/math/estimator/MerweUKF.hpp index 7f2ede4207..5a12166cd4 100644 --- a/wpimath/src/main/native/include/wpi/math/estimator/MerweUKF.hpp +++ b/wpimath/src/main/native/include/wpi/math/estimator/MerweUKF.hpp @@ -8,7 +8,7 @@ #include "wpi/math/estimator/UnscentedKalmanFilter.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::math { template using MerweUKF = UnscentedKalmanFilter>; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/estimator/PoseEstimator.hpp b/wpimath/src/main/native/include/wpi/math/estimator/PoseEstimator.hpp index 0c2238aab8..9ac8ed792e 100644 --- a/wpimath/src/main/native/include/wpi/math/estimator/PoseEstimator.hpp +++ b/wpimath/src/main/native/include/wpi/math/estimator/PoseEstimator.hpp @@ -21,7 +21,7 @@ #include "wpi/util/SymbolExports.hpp" #include "wpi/util/array.hpp" -namespace frc { +namespace wpi::math { /** * This class wraps odometry to fuse latency-compensated @@ -61,8 +61,8 @@ class WPILIB_DLLEXPORT PoseEstimator { */ PoseEstimator(Kinematics& kinematics, Odometry& odometry, - const wpi::array& stateStdDevs, - const wpi::array& visionMeasurementStdDevs) + const wpi::util::array& stateStdDevs, + const wpi::util::array& visionMeasurementStdDevs) : m_odometry(odometry) { for (size_t i = 0; i < 3; ++i) { m_q[i] = stateStdDevs[i] * stateStdDevs[i]; @@ -82,8 +82,8 @@ class WPILIB_DLLEXPORT PoseEstimator { * less. */ void SetVisionMeasurementStdDevs( - const wpi::array& visionMeasurementStdDevs) { - wpi::array r{wpi::empty_array}; + const wpi::util::array& visionMeasurementStdDevs) { + wpi::util::array r{wpi::util::empty_array}; for (size_t i = 0; i < 3; ++i) { r[i] = visionMeasurementStdDevs[i] * visionMeasurementStdDevs[i]; } @@ -169,7 +169,7 @@ class WPILIB_DLLEXPORT PoseEstimator { * @return The pose at the given timestamp (or std::nullopt if the buffer is * empty). */ - std::optional SampleAt(units::second_t timestamp) const { + std::optional SampleAt(wpi::units::second_t timestamp) const { // Step 0: If there are no odometry updates to sample, skip. if (m_odometryPoseBuffer.GetInternalBuffer().empty()) { return std::nullopt; @@ -178,9 +178,9 @@ class WPILIB_DLLEXPORT PoseEstimator { // Step 1: Make sure timestamp matches the sample from the odometry pose // buffer. (When sampling, the buffer will always use a timestamp // between the first and last timestamps) - units::second_t oldestOdometryTimestamp = + wpi::units::second_t oldestOdometryTimestamp = m_odometryPoseBuffer.GetInternalBuffer().front().first; - units::second_t newestOdometryTimestamp = + wpi::units::second_t newestOdometryTimestamp = m_odometryPoseBuffer.GetInternalBuffer().back().first; timestamp = std::clamp(timestamp, oldestOdometryTimestamp, newestOdometryTimestamp); @@ -228,11 +228,11 @@ class WPILIB_DLLEXPORT PoseEstimator { * that if you don't use your own time source by calling UpdateWithTime(), * then you must use a timestamp with an epoch since FPGA startup (i.e., * the epoch of this timestamp is the same epoch as - * frc::Timer::GetTimestamp(). This means that you should use - * frc::Timer::GetTimestamp() as your time source in this case. + * wpi::math::Timer::GetTimestamp(). This means that you should use + * wpi::math::Timer::GetTimestamp() as your time source in this case. */ void AddVisionMeasurement(const Pose2d& visionRobotPose, - units::second_t timestamp) { + wpi::units::second_t timestamp) { // Step 0: If this measurement is old enough to be outside the pose buffer's // timespan, skip. if (m_odometryPoseBuffer.GetInternalBuffer().empty() || @@ -273,9 +273,9 @@ class WPILIB_DLLEXPORT PoseEstimator { twist.dtheta.value()}; // Step 6: Convert back to Twist2d. - Twist2d scaledTwist{units::meter_t{k_times_twist(0)}, - units::meter_t{k_times_twist(1)}, - units::radian_t{k_times_twist(2)}}; + Twist2d scaledTwist{wpi::units::meter_t{k_times_twist(0)}, + wpi::units::meter_t{k_times_twist(1)}, + wpi::units::radian_t{k_times_twist(2)}}; // Step 7: Calculate and record the vision update. VisionUpdate visionUpdate{visionSample.value() + scaledTwist.Exp(), @@ -312,16 +312,16 @@ class WPILIB_DLLEXPORT PoseEstimator { * that if you don't use your own time source by calling UpdateWithTime(), * then you must use a timestamp with an epoch since FPGA startup (i.e., * the epoch of this timestamp is the same epoch as - * frc::Timer::GetTimestamp(). This means that you should use - * frc::Timer::GetTimestamp() as your time source in this case. + * wpi::math::Timer::GetTimestamp(). This means that you should use + * wpi::math::Timer::GetTimestamp() as your time source in this case. * @param visionMeasurementStdDevs Standard deviations of the vision pose * measurement (x position in meters, y position in meters, and heading in * radians). Increase these numbers to trust the vision pose measurement * less. */ void AddVisionMeasurement( - const Pose2d& visionRobotPose, units::second_t timestamp, - const wpi::array& visionMeasurementStdDevs) { + const Pose2d& visionRobotPose, wpi::units::second_t timestamp, + const wpi::util::array& visionMeasurementStdDevs) { SetVisionMeasurementStdDevs(visionMeasurementStdDevs); AddVisionMeasurement(visionRobotPose, timestamp); } @@ -351,7 +351,7 @@ class WPILIB_DLLEXPORT PoseEstimator { * * @return The estimated pose of the robot in meters. */ - Pose2d UpdateWithTime(units::second_t currentTime, + Pose2d UpdateWithTime(wpi::units::second_t currentTime, const Rotation2d& gyroAngle, const WheelPositions& wheelPositions) { auto odometryEstimate = m_odometry.Update(gyroAngle, wheelPositions); @@ -379,7 +379,7 @@ class WPILIB_DLLEXPORT PoseEstimator { } // Step 1: Find the oldest timestamp that needs a vision update. - units::second_t oldestOdometryTimestamp = + wpi::units::second_t oldestOdometryTimestamp = m_odometryPoseBuffer.GetInternalBuffer().front().first; // Step 2: If there are no vision updates before that timestamp, skip. @@ -422,10 +422,10 @@ class WPILIB_DLLEXPORT PoseEstimator { } }; - static constexpr units::second_t kBufferDuration = 1.5_s; + static constexpr wpi::units::second_t kBufferDuration = 1.5_s; Odometry& m_odometry; - wpi::array m_q{wpi::empty_array}; + wpi::util::array m_q{wpi::util::empty_array}; Eigen::Matrix3d m_visionK = Eigen::Matrix3d::Zero(); // Maps timestamps to odometry-only pose estimates @@ -433,9 +433,9 @@ class WPILIB_DLLEXPORT PoseEstimator { // Maps timestamps to vision updates // Always contains one entry before the oldest entry in m_odometryPoseBuffer, // unless there have been no vision measurements after the last reset - std::map m_visionUpdates; + std::map m_visionUpdates; Pose2d m_poseEstimate; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/estimator/PoseEstimator3d.hpp b/wpimath/src/main/native/include/wpi/math/estimator/PoseEstimator3d.hpp index 6d475470c6..2d19ba821f 100644 --- a/wpimath/src/main/native/include/wpi/math/estimator/PoseEstimator3d.hpp +++ b/wpimath/src/main/native/include/wpi/math/estimator/PoseEstimator3d.hpp @@ -23,7 +23,7 @@ #include "wpi/util/SymbolExports.hpp" #include "wpi/util/array.hpp" -namespace frc { +namespace wpi::math { /** * This class wraps odometry to fuse latency-compensated @@ -67,8 +67,8 @@ class WPILIB_DLLEXPORT PoseEstimator3d { */ PoseEstimator3d(Kinematics& kinematics, Odometry3d& odometry, - const wpi::array& stateStdDevs, - const wpi::array& visionMeasurementStdDevs) + const wpi::util::array& stateStdDevs, + const wpi::util::array& visionMeasurementStdDevs) : m_odometry(odometry) { for (size_t i = 0; i < 4; ++i) { m_q[i] = stateStdDevs[i] * stateStdDevs[i]; @@ -88,8 +88,8 @@ class WPILIB_DLLEXPORT PoseEstimator3d { * less. */ void SetVisionMeasurementStdDevs( - const wpi::array& visionMeasurementStdDevs) { - wpi::array r{wpi::empty_array}; + const wpi::util::array& visionMeasurementStdDevs) { + wpi::util::array r{wpi::util::empty_array}; for (size_t i = 0; i < 4; ++i) { r[i] = visionMeasurementStdDevs[i] * visionMeasurementStdDevs[i]; } @@ -178,7 +178,7 @@ class WPILIB_DLLEXPORT PoseEstimator3d { * @return The pose at the given timestamp (or std::nullopt if the buffer is * empty). */ - std::optional SampleAt(units::second_t timestamp) const { + std::optional SampleAt(wpi::units::second_t timestamp) const { // Step 0: If there are no odometry updates to sample, skip. if (m_odometryPoseBuffer.GetInternalBuffer().empty()) { return std::nullopt; @@ -187,9 +187,9 @@ class WPILIB_DLLEXPORT PoseEstimator3d { // Step 1: Make sure timestamp matches the sample from the odometry pose // buffer. (When sampling, the buffer will always use a timestamp // between the first and last timestamps) - units::second_t oldestOdometryTimestamp = + wpi::units::second_t oldestOdometryTimestamp = m_odometryPoseBuffer.GetInternalBuffer().front().first; - units::second_t newestOdometryTimestamp = + wpi::units::second_t newestOdometryTimestamp = m_odometryPoseBuffer.GetInternalBuffer().back().first; timestamp = std::clamp(timestamp, oldestOdometryTimestamp, newestOdometryTimestamp); @@ -237,11 +237,11 @@ class WPILIB_DLLEXPORT PoseEstimator3d { * that if you don't use your own time source by calling UpdateWithTime(), * then you must use a timestamp with an epoch since FPGA startup (i.e., * the epoch of this timestamp is the same epoch as - * frc::Timer::GetFPGATimestamp(). This means that you should use - * frc::Timer::GetFPGATimestamp() as your time source in this case. + * wpi::math::Timer::GetFPGATimestamp(). This means that you should use + * wpi::math::Timer::GetFPGATimestamp() as your time source in this case. */ void AddVisionMeasurement(const Pose3d& visionRobotPose, - units::second_t timestamp) { + wpi::units::second_t timestamp) { // Step 0: If this measurement is old enough to be outside the pose buffer's // timespan, skip. if (m_odometryPoseBuffer.GetInternalBuffer().empty() || @@ -277,16 +277,16 @@ class WPILIB_DLLEXPORT PoseEstimator3d { // Step 5: We should not trust the twist entirely, so instead we scale this // twist by a Kalman gain matrix representing how much we trust vision // measurements compared to our current pose. - frc::Vectord<6> k_times_twist = - m_visionK * frc::Vectord<6>{twist.dx.value(), twist.dy.value(), + wpi::math::Vectord<6> k_times_twist = + m_visionK * wpi::math::Vectord<6>{twist.dx.value(), twist.dy.value(), twist.dz.value(), twist.rx.value(), twist.ry.value(), twist.rz.value()}; // Step 6: Convert back to Twist3d. Twist3d scaledTwist{ - units::meter_t{k_times_twist(0)}, units::meter_t{k_times_twist(1)}, - units::meter_t{k_times_twist(2)}, units::radian_t{k_times_twist(3)}, - units::radian_t{k_times_twist(4)}, units::radian_t{k_times_twist(5)}}; + wpi::units::meter_t{k_times_twist(0)}, wpi::units::meter_t{k_times_twist(1)}, + wpi::units::meter_t{k_times_twist(2)}, wpi::units::radian_t{k_times_twist(3)}, + wpi::units::radian_t{k_times_twist(4)}, wpi::units::radian_t{k_times_twist(5)}}; // Step 7: Calculate and record the vision update. VisionUpdate visionUpdate{visionSample.value() + scaledTwist.Exp(), @@ -323,16 +323,16 @@ class WPILIB_DLLEXPORT PoseEstimator3d { * that if you don't use your own time source by calling UpdateWithTime(), * then you must use a timestamp with an epoch since FPGA startup (i.e., * the epoch of this timestamp is the same epoch as - * frc::Timer::GetFPGATimestamp(). This means that you should use - * frc::Timer::GetFPGATimestamp() as your time source in this case. + * wpi::math::Timer::GetFPGATimestamp(). This means that you should use + * wpi::math::Timer::GetFPGATimestamp() as your time source in this case. * @param visionMeasurementStdDevs Standard deviations of the vision pose * measurement (x position in meters, y position in meters, and heading in * radians). Increase these numbers to trust the vision pose measurement * less. */ void AddVisionMeasurement( - const Pose3d& visionRobotPose, units::second_t timestamp, - const wpi::array& visionMeasurementStdDevs) { + const Pose3d& visionRobotPose, wpi::units::second_t timestamp, + const wpi::util::array& visionMeasurementStdDevs) { SetVisionMeasurementStdDevs(visionMeasurementStdDevs); AddVisionMeasurement(visionRobotPose, timestamp); } @@ -362,7 +362,7 @@ class WPILIB_DLLEXPORT PoseEstimator3d { * * @return The estimated pose of the robot in meters. */ - Pose3d UpdateWithTime(units::second_t currentTime, + Pose3d UpdateWithTime(wpi::units::second_t currentTime, const Rotation3d& gyroAngle, const WheelPositions& wheelPositions) { auto odometryEstimate = m_odometry.Update(gyroAngle, wheelPositions); @@ -390,7 +390,7 @@ class WPILIB_DLLEXPORT PoseEstimator3d { } // Step 1: Find the oldest timestamp that needs a vision update. - units::second_t oldestOdometryTimestamp = + wpi::units::second_t oldestOdometryTimestamp = m_odometryPoseBuffer.GetInternalBuffer().front().first; // Step 2: If there are no vision updates before that timestamp, skip. @@ -433,20 +433,20 @@ class WPILIB_DLLEXPORT PoseEstimator3d { } }; - static constexpr units::second_t kBufferDuration = 1.5_s; + static constexpr wpi::units::second_t kBufferDuration = 1.5_s; Odometry3d& m_odometry; - wpi::array m_q{wpi::empty_array}; - frc::Matrixd<6, 6> m_visionK = frc::Matrixd<6, 6>::Zero(); + wpi::util::array m_q{wpi::util::empty_array}; + wpi::math::Matrixd<6, 6> m_visionK = wpi::math::Matrixd<6, 6>::Zero(); // Maps timestamps to odometry-only pose estimates TimeInterpolatableBuffer m_odometryPoseBuffer{kBufferDuration}; // Maps timestamps to vision updates // Always contains one entry before the oldest entry in m_odometryPoseBuffer, // unless there have been no vision measurements after the last reset - std::map m_visionUpdates; + std::map m_visionUpdates; Pose3d m_poseEstimate; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/estimator/S3SigmaPoints.hpp b/wpimath/src/main/native/include/wpi/math/estimator/S3SigmaPoints.hpp index 4f226d6703..956f8cb9cd 100644 --- a/wpimath/src/main/native/include/wpi/math/estimator/S3SigmaPoints.hpp +++ b/wpimath/src/main/native/include/wpi/math/estimator/S3SigmaPoints.hpp @@ -8,7 +8,7 @@ #include "wpi/math/linalg/EigenCore.hpp" #include "wpi/util/array.hpp" -namespace frc { +namespace wpi::math { /** * Generates sigma points and weights according to Papakonstantinou's paper[1] @@ -57,7 +57,7 @@ class S3SigmaPoints { Matrixd SquareRootSigmaPoints( const Vectord& x, const Matrixd& S) const { // table (1), equation (12) - wpi::array q{wpi::empty_array}; + wpi::util::array q{wpi::util::empty_array}; for (size_t t = 1; t <= States; ++t) { q[t - 1] = m_alpha * std::sqrt(static_cast(t * (States + 1)) / static_cast(t + 1)); @@ -131,4 +131,4 @@ class S3SigmaPoints { } }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/estimator/S3UKF.hpp b/wpimath/src/main/native/include/wpi/math/estimator/S3UKF.hpp index 8eaea80512..1e3b2a5310 100644 --- a/wpimath/src/main/native/include/wpi/math/estimator/S3UKF.hpp +++ b/wpimath/src/main/native/include/wpi/math/estimator/S3UKF.hpp @@ -8,7 +8,7 @@ #include "wpi/math/estimator/UnscentedKalmanFilter.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::math { template using S3UKF = @@ -21,4 +21,4 @@ extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT) extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT) UnscentedKalmanFilter<5, 3, 3, S3SigmaPoints<5>>; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/estimator/SigmaPoints.hpp b/wpimath/src/main/native/include/wpi/math/estimator/SigmaPoints.hpp index c21d329114..4b5a5ca88c 100644 --- a/wpimath/src/main/native/include/wpi/math/estimator/SigmaPoints.hpp +++ b/wpimath/src/main/native/include/wpi/math/estimator/SigmaPoints.hpp @@ -8,7 +8,7 @@ #include "wpi/math/linalg/EigenCore.hpp" -namespace frc { +namespace wpi::math { template concept SigmaPoints = @@ -23,4 +23,4 @@ concept SigmaPoints = { t.Wc(i) } -> std::same_as; } && std::default_initializable; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/estimator/SteadyStateKalmanFilter.hpp b/wpimath/src/main/native/include/wpi/math/estimator/SteadyStateKalmanFilter.hpp index 07f1321088..61b7d5cabe 100644 --- a/wpimath/src/main/native/include/wpi/math/estimator/SteadyStateKalmanFilter.hpp +++ b/wpimath/src/main/native/include/wpi/math/estimator/SteadyStateKalmanFilter.hpp @@ -21,7 +21,7 @@ #include "wpi/util/SymbolExports.hpp" #include "wpi/util/array.hpp" -namespace frc { +namespace wpi::math { /** * A Kalman filter combines predictions from a model and measurements to give an @@ -54,8 +54,8 @@ class SteadyStateKalmanFilter { using InputVector = Vectord; using OutputVector = Vectord; - using StateArray = wpi::array; - using OutputArray = wpi::array; + using StateArray = wpi::util::array; + using OutputArray = wpi::util::array; /** * Constructs a steady-state Kalman filter with the given plant. @@ -73,7 +73,7 @@ class SteadyStateKalmanFilter { SteadyStateKalmanFilter(LinearSystem& plant, const StateArray& stateStdDevs, const OutputArray& measurementStdDevs, - units::second_t dt) { + wpi::units::second_t dt) { m_plant = &plant; auto contQ = MakeCovMatrix(stateStdDevs); @@ -205,7 +205,7 @@ class SteadyStateKalmanFilter { * @param u New control input from controller. * @param dt Timestep for prediction. */ - void Predict(const InputVector& u, units::second_t dt) { + void Predict(const InputVector& u, wpi::units::second_t dt) { m_xHat = m_plant->CalculateX(m_xHat, u, dt); } @@ -242,4 +242,4 @@ extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT) extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT) SteadyStateKalmanFilter<2, 1, 1>; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/estimator/SwerveDrivePoseEstimator.hpp b/wpimath/src/main/native/include/wpi/math/estimator/SwerveDrivePoseEstimator.hpp index 0ca22472b7..0ef9557a44 100644 --- a/wpimath/src/main/native/include/wpi/math/estimator/SwerveDrivePoseEstimator.hpp +++ b/wpimath/src/main/native/include/wpi/math/estimator/SwerveDrivePoseEstimator.hpp @@ -15,7 +15,7 @@ #include "wpi/util/SymbolExports.hpp" #include "wpi/util/array.hpp" -namespace frc { +namespace wpi::math { /** * This class wraps Swerve Drive Odometry to fuse latency-compensated @@ -30,8 +30,8 @@ namespace frc { */ template class SwerveDrivePoseEstimator - : public PoseEstimator, - wpi::array> { + : public PoseEstimator, + wpi::util::array> { public: /** * Constructs a SwerveDrivePoseEstimator with default standard deviations @@ -52,7 +52,7 @@ class SwerveDrivePoseEstimator SwerveDrivePoseEstimator( SwerveDriveKinematics& kinematics, const Rotation2d& gyroAngle, - const wpi::array& modulePositions, + const wpi::util::array& modulePositions, const Pose2d& initialPose) : SwerveDrivePoseEstimator{kinematics, gyroAngle, modulePositions, initialPose, @@ -78,9 +78,9 @@ class SwerveDrivePoseEstimator SwerveDrivePoseEstimator( SwerveDriveKinematics& kinematics, const Rotation2d& gyroAngle, - const wpi::array& modulePositions, - const Pose2d& initialPose, const wpi::array& stateStdDevs, - const wpi::array& visionMeasurementStdDevs) + const wpi::util::array& modulePositions, + const Pose2d& initialPose, const wpi::util::array& stateStdDevs, + const wpi::util::array& visionMeasurementStdDevs) : SwerveDrivePoseEstimator::PoseEstimator( kinematics, m_odometryImpl, stateStdDevs, visionMeasurementStdDevs), m_odometryImpl{kinematics, gyroAngle, modulePositions, initialPose} { @@ -94,4 +94,4 @@ class SwerveDrivePoseEstimator extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT) SwerveDrivePoseEstimator<4>; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/estimator/SwerveDrivePoseEstimator3d.hpp b/wpimath/src/main/native/include/wpi/math/estimator/SwerveDrivePoseEstimator3d.hpp index 5719af034e..9cdba71d31 100644 --- a/wpimath/src/main/native/include/wpi/math/estimator/SwerveDrivePoseEstimator3d.hpp +++ b/wpimath/src/main/native/include/wpi/math/estimator/SwerveDrivePoseEstimator3d.hpp @@ -15,7 +15,7 @@ #include "wpi/util/SymbolExports.hpp" #include "wpi/util/array.hpp" -namespace frc { +namespace wpi::math { /** * This class wraps Swerve Drive Odometry to fuse latency-compensated @@ -34,8 +34,8 @@ namespace frc { */ template class SwerveDrivePoseEstimator3d - : public PoseEstimator3d, - wpi::array> { + : public PoseEstimator3d, + wpi::util::array> { public: /** * Constructs a SwerveDrivePoseEstimator3d with default standard deviations @@ -57,7 +57,7 @@ class SwerveDrivePoseEstimator3d SwerveDrivePoseEstimator3d( SwerveDriveKinematics& kinematics, const Rotation3d& gyroAngle, - const wpi::array& modulePositions, + const wpi::util::array& modulePositions, const Pose3d& initialPose) : SwerveDrivePoseEstimator3d{kinematics, gyroAngle, modulePositions, initialPose, @@ -84,9 +84,9 @@ class SwerveDrivePoseEstimator3d SwerveDrivePoseEstimator3d( SwerveDriveKinematics& kinematics, const Rotation3d& gyroAngle, - const wpi::array& modulePositions, - const Pose3d& initialPose, const wpi::array& stateStdDevs, - const wpi::array& visionMeasurementStdDevs) + const wpi::util::array& modulePositions, + const Pose3d& initialPose, const wpi::util::array& stateStdDevs, + const wpi::util::array& visionMeasurementStdDevs) : SwerveDrivePoseEstimator3d::PoseEstimator3d( kinematics, m_odometryImpl, stateStdDevs, visionMeasurementStdDevs), m_odometryImpl{kinematics, gyroAngle, modulePositions, initialPose} { @@ -100,4 +100,4 @@ class SwerveDrivePoseEstimator3d extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT) SwerveDrivePoseEstimator3d<4>; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/estimator/UnscentedKalmanFilter.hpp b/wpimath/src/main/native/include/wpi/math/estimator/UnscentedKalmanFilter.hpp index 90d436afd7..b6e42d9bb6 100644 --- a/wpimath/src/main/native/include/wpi/math/estimator/UnscentedKalmanFilter.hpp +++ b/wpimath/src/main/native/include/wpi/math/estimator/UnscentedKalmanFilter.hpp @@ -20,7 +20,7 @@ #include "wpi/util/SymbolExports.hpp" #include "wpi/util/array.hpp" -namespace frc { +namespace wpi::math { /** * A Kalman filter combines predictions from a model and measurements to give an @@ -67,8 +67,8 @@ class UnscentedKalmanFilter { using InputVector = Vectord; using OutputVector = Vectord; - using StateArray = wpi::array; - using OutputArray = wpi::array; + using StateArray = wpi::util::array; + using OutputArray = wpi::util::array; using StateMatrix = Matrixd; @@ -91,7 +91,7 @@ class UnscentedKalmanFilter { std::function f, std::function h, const StateArray& stateStdDevs, const OutputArray& measurementStdDevs, - units::second_t dt) + wpi::units::second_t dt) : m_f(std::move(f)), m_h(std::move(h)) { m_contQ = MakeCovMatrix(stateStdDevs); m_contR = MakeCovMatrix(measurementStdDevs); @@ -161,7 +161,7 @@ class UnscentedKalmanFilter { residualFuncY, std::function addFuncX, - units::second_t dt) + wpi::units::second_t dt) : m_f(std::move(f)), m_h(std::move(h)), m_meanFuncX(std::move(meanFuncX)), @@ -251,7 +251,7 @@ class UnscentedKalmanFilter { * @param u New control input from controller. * @param dt Timestep for prediction. */ - void Predict(const InputVector& u, units::second_t dt) { + void Predict(const InputVector& u, wpi::units::second_t dt) { m_dt = dt; // Discretize Q before projecting mean and covariance forward @@ -491,9 +491,9 @@ class UnscentedKalmanFilter { StateMatrix m_contQ; Matrixd m_contR; Matrixd m_sigmasF; - units::second_t m_dt; + wpi::units::second_t m_dt; SigmaPoints m_pts; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/estimator/UnscentedTransform.hpp b/wpimath/src/main/native/include/wpi/math/estimator/UnscentedTransform.hpp index 62909c269d..b1ee8527c1 100644 --- a/wpimath/src/main/native/include/wpi/math/estimator/UnscentedTransform.hpp +++ b/wpimath/src/main/native/include/wpi/math/estimator/UnscentedTransform.hpp @@ -11,7 +11,7 @@ #include "wpi/math/linalg/EigenCore.hpp" -namespace frc { +namespace wpi::math { /** * Computes unscented transform of a set of sigma points and weights. CovDim @@ -103,4 +103,4 @@ SquareRootUnscentedTransform( return std::make_tuple(x, S); } -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/filter/Debouncer.hpp b/wpimath/src/main/native/include/wpi/math/filter/Debouncer.hpp index 76106ea087..3972d25507 100644 --- a/wpimath/src/main/native/include/wpi/math/filter/Debouncer.hpp +++ b/wpimath/src/main/native/include/wpi/math/filter/Debouncer.hpp @@ -8,7 +8,7 @@ #include "wpi/util/SymbolExports.hpp" #include "wpi/util/timestamp.h" -namespace frc { +namespace wpi::math { /** * A simple debounce filter for boolean streams. Requires that the boolean * change value from baseline for a specified period of time before the filtered @@ -36,7 +36,7 @@ class WPILIB_DLLEXPORT Debouncer { * @param type Which type of state change the debouncing will be * performed on. */ - explicit Debouncer(units::second_t debounceTime, + explicit Debouncer(wpi::units::second_t debounceTime, DebounceType type = DebounceType::kRising); /** @@ -53,7 +53,7 @@ class WPILIB_DLLEXPORT Debouncer { * @param time The number of seconds the value must change from baseline * for the filtered value to change. */ - constexpr void SetDebounceTime(units::second_t time) { + constexpr void SetDebounceTime(wpi::units::second_t time) { m_debounceTime = time; } @@ -63,7 +63,7 @@ class WPILIB_DLLEXPORT Debouncer { * @return The number of seconds the value must change from baseline * for the filtered value to change. */ - constexpr units::second_t GetDebounceTime() const { return m_debounceTime; } + constexpr wpi::units::second_t GetDebounceTime() const { return m_debounceTime; } /** * Set the debounce type. @@ -84,14 +84,14 @@ class WPILIB_DLLEXPORT Debouncer { constexpr DebounceType GetDebounceType() const { return m_debounceType; } private: - units::second_t m_debounceTime; + wpi::units::second_t m_debounceTime; bool m_baseline; DebounceType m_debounceType; - units::second_t m_prevTime; + wpi::units::second_t m_prevTime; void ResetTimer(); bool HasElapsed() const; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/filter/LinearFilter.hpp b/wpimath/src/main/native/include/wpi/math/filter/LinearFilter.hpp index 09e0a392a1..3d47e12c4d 100644 --- a/wpimath/src/main/native/include/wpi/math/filter/LinearFilter.hpp +++ b/wpimath/src/main/native/include/wpi/math/filter/LinearFilter.hpp @@ -20,7 +20,7 @@ #include "wpi/util/array.hpp" #include "wpi/util/circular_buffer.hpp" -namespace frc { +namespace wpi::math { /** * This class implements a linear, digital filter. All types of FIR and IIR @@ -128,7 +128,7 @@ class LinearFilter { * user. */ static constexpr LinearFilter SinglePoleIIR(double timeConstant, - units::second_t period) { + wpi::units::second_t period) { double gain = gcem::exp(-period.value() / timeConstant); return LinearFilter({1.0 - gain}, {-gain}); } @@ -148,7 +148,7 @@ class LinearFilter { * user. */ static constexpr LinearFilter HighPass(double timeConstant, - units::second_t period) { + wpi::units::second_t period) { double gain = gcem::exp(-period.value() / timeConstant); return LinearFilter({gain, -gain}, {-gain}); } @@ -191,7 +191,7 @@ class LinearFilter { */ template static LinearFilter FiniteDifference( - const wpi::array& stencil, units::second_t period) { + const wpi::util::array& stencil, wpi::units::second_t period) { // See // https://en.wikipedia.org/wiki/Finite_difference_coefficient#Arbitrary_stencil_points // @@ -257,9 +257,9 @@ class LinearFilter { * @param period The period in seconds between samples taken by the user. */ template - static LinearFilter BackwardFiniteDifference(units::second_t period) { + static LinearFilter BackwardFiniteDifference(wpi::units::second_t period) { // Generate stencil points from -(samples - 1) to 0 - wpi::array stencil{wpi::empty_array}; + wpi::util::array stencil{wpi::util::empty_array}; for (int i = 0; i < Samples; ++i) { stencil[i] = -(Samples - 1) + i; } @@ -384,8 +384,8 @@ class LinearFilter { constexpr T LastValue() const { return m_lastOutput; } private: - wpi::circular_buffer m_inputs; - wpi::circular_buffer m_outputs; + wpi::util::circular_buffer m_inputs; + wpi::util::circular_buffer m_outputs; std::vector m_inputGains; std::vector m_outputGains; T m_lastOutput{0.0}; @@ -407,4 +407,4 @@ class LinearFilter { } }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/filter/MedianFilter.hpp b/wpimath/src/main/native/include/wpi/math/filter/MedianFilter.hpp index 694ff7c954..b378d22b2c 100644 --- a/wpimath/src/main/native/include/wpi/math/filter/MedianFilter.hpp +++ b/wpimath/src/main/native/include/wpi/math/filter/MedianFilter.hpp @@ -10,7 +10,7 @@ #include "wpi/util/Algorithm.hpp" #include "wpi/util/circular_buffer.hpp" -namespace frc { +namespace wpi::math { /** * A class that implements a moving-window median filter. Useful for reducing * measurement noise, especially with processes that generate occasional, @@ -36,7 +36,7 @@ class MedianFilter { */ constexpr T Calculate(T next) { // Insert next value at proper point in sorted array - wpi::insert_sorted(m_orderedValues, next); + wpi::util::insert_sorted(m_orderedValues, next); size_t curSize = m_orderedValues.size(); @@ -78,8 +78,8 @@ class MedianFilter { } private: - wpi::circular_buffer m_valueBuffer; + wpi::util::circular_buffer m_valueBuffer; std::vector m_orderedValues; size_t m_size; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/filter/SlewRateLimiter.hpp b/wpimath/src/main/native/include/wpi/math/filter/SlewRateLimiter.hpp index 9e954cdc83..37c8320768 100644 --- a/wpimath/src/main/native/include/wpi/math/filter/SlewRateLimiter.hpp +++ b/wpimath/src/main/native/include/wpi/math/filter/SlewRateLimiter.hpp @@ -10,7 +10,7 @@ #include "wpi/units/time.hpp" #include "wpi/util/timestamp.h" -namespace frc { +namespace wpi::math { /** * A class that limits the rate of change of an input value. Useful for * implementing voltage, setpoint, and/or output ramps. A slew-rate limit @@ -23,9 +23,9 @@ namespace frc { template class SlewRateLimiter { public: - using Unit_t = units::unit_t; - using Rate = units::compound_unit>; - using Rate_t = units::unit_t; + using Unit_t = wpi::units::unit_t; + using Rate = wpi::units::compound_unit>; + using Rate_t = wpi::units::unit_t; /** * Creates a new SlewRateLimiter with the given positive and negative rate @@ -45,7 +45,7 @@ class SlewRateLimiter { m_negativeRateLimit{negativeRateLimit}, m_prevVal{initialValue}, m_prevTime{ - units::microsecond_t{wpi::math::MathSharedStore::GetTimestamp()}} {} + wpi::units::microsecond_t{wpi::math::MathSharedStore::GetTimestamp()}} {} /** * Creates a new SlewRateLimiter with the given positive rate limit and @@ -64,8 +64,8 @@ class SlewRateLimiter { * rate. */ Unit_t Calculate(Unit_t input) { - units::second_t currentTime = wpi::math::MathSharedStore::GetTimestamp(); - units::second_t elapsedTime = currentTime - m_prevTime; + wpi::units::second_t currentTime = wpi::math::MathSharedStore::GetTimestamp(); + wpi::units::second_t elapsedTime = currentTime - m_prevTime; m_prevVal += std::clamp(input - m_prevVal, m_negativeRateLimit * elapsedTime, m_positiveRateLimit * elapsedTime); @@ -95,6 +95,6 @@ class SlewRateLimiter { Rate_t m_positiveRateLimit; Rate_t m_negativeRateLimit; Unit_t m_prevVal; - units::second_t m_prevTime; + wpi::units::second_t m_prevTime; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/geometry/CoordinateAxis.hpp b/wpimath/src/main/native/include/wpi/math/geometry/CoordinateAxis.hpp index d5d8fbfb07..335b129432 100644 --- a/wpimath/src/main/native/include/wpi/math/geometry/CoordinateAxis.hpp +++ b/wpimath/src/main/native/include/wpi/math/geometry/CoordinateAxis.hpp @@ -11,7 +11,7 @@ #include "wpi/math/geometry/Rotation3d.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::math { /** * A class representing a coordinate system axis within the NWU coordinate @@ -74,4 +74,4 @@ class WPILIB_DLLEXPORT CoordinateAxis { Eigen::Vector3d m_axis; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/geometry/CoordinateSystem.hpp b/wpimath/src/main/native/include/wpi/math/geometry/CoordinateSystem.hpp index 5b5efb64b5..ff3fd7ebbd 100644 --- a/wpimath/src/main/native/include/wpi/math/geometry/CoordinateSystem.hpp +++ b/wpimath/src/main/native/include/wpi/math/geometry/CoordinateSystem.hpp @@ -10,7 +10,7 @@ #include "wpi/math/geometry/Translation3d.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::math { /** * A helper class that converts Pose3d objects between different standard @@ -139,4 +139,4 @@ class WPILIB_DLLEXPORT CoordinateSystem { Rotation3d m_rotation; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/geometry/Ellipse2d.hpp b/wpimath/src/main/native/include/wpi/math/geometry/Ellipse2d.hpp index 37a2481f80..6f9a5a4653 100644 --- a/wpimath/src/main/native/include/wpi/math/geometry/Ellipse2d.hpp +++ b/wpimath/src/main/native/include/wpi/math/geometry/Ellipse2d.hpp @@ -17,7 +17,7 @@ #include "wpi/util/SymbolExports.hpp" #include "wpi/util/array.hpp" -namespace frc { +namespace wpi::math { /** * Represents a 2d ellipse space containing translational, rotational, and @@ -33,8 +33,8 @@ class WPILIB_DLLEXPORT Ellipse2d { * @param xSemiAxis The x semi-axis. * @param ySemiAxis The y semi-axis. */ - constexpr Ellipse2d(const Pose2d& center, units::meter_t xSemiAxis, - units::meter_t ySemiAxis) + constexpr Ellipse2d(const Pose2d& center, wpi::units::meter_t xSemiAxis, + wpi::units::meter_t ySemiAxis) : m_center{center}, m_xSemiAxis{xSemiAxis}, m_ySemiAxis{ySemiAxis} { if (xSemiAxis <= 0_m || ySemiAxis <= 0_m) { throw std::invalid_argument("Ellipse2d semi-axes must be positive"); @@ -71,14 +71,14 @@ class WPILIB_DLLEXPORT Ellipse2d { * * @return The x semi-axis. */ - constexpr units::meter_t XSemiAxis() const { return m_xSemiAxis; } + constexpr wpi::units::meter_t XSemiAxis() const { return m_xSemiAxis; } /** * Returns the y semi-axis. * * @return The y semi-axis. */ - constexpr units::meter_t YSemiAxis() const { return m_ySemiAxis; } + constexpr wpi::units::meter_t YSemiAxis() const { return m_ySemiAxis; } /** * Returns the focal points of the ellipse. In a perfect circle, this will @@ -86,21 +86,21 @@ class WPILIB_DLLEXPORT Ellipse2d { * * @return The focal points. */ - constexpr wpi::array FocalPoints() const { + constexpr wpi::util::array FocalPoints() const { // Major semi-axis - auto a = units::math::max(m_xSemiAxis, m_ySemiAxis); + auto a = wpi::units::math::max(m_xSemiAxis, m_ySemiAxis); // Minor semi-axis - auto b = units::math::min(m_xSemiAxis, m_ySemiAxis); + auto b = wpi::units::math::min(m_xSemiAxis, m_ySemiAxis); - auto c = units::math::sqrt(a * a - b * b); + auto c = wpi::units::math::sqrt(a * a - b * b); if (m_xSemiAxis > m_ySemiAxis) { - return wpi::array{ + return wpi::util::array{ (m_center + Transform2d{-c, 0_m, Rotation2d{}}).Translation(), (m_center + Transform2d{c, 0_m, Rotation2d{}}).Translation()}; } else { - return wpi::array{ + return wpi::util::array{ (m_center + Transform2d{0_m, -c, Rotation2d{}}).Translation(), (m_center + Transform2d{0_m, c, Rotation2d{}}).Translation()}; } @@ -153,7 +153,7 @@ class WPILIB_DLLEXPORT Ellipse2d { * @param point The point to check. * @return The distance (0, if the point is contained by the ellipse) */ - units::meter_t Distance(const Translation2d& point) const { + wpi::units::meter_t Distance(const Translation2d& point) const { return Nearest(point).Distance(point); } @@ -174,14 +174,14 @@ class WPILIB_DLLEXPORT Ellipse2d { */ constexpr bool operator==(const Ellipse2d& other) const { return m_center == other.m_center && - units::math::abs(m_xSemiAxis - other.m_xSemiAxis) < 1E-9_m && - units::math::abs(m_ySemiAxis - other.m_ySemiAxis) < 1E-9_m; + wpi::units::math::abs(m_xSemiAxis - other.m_xSemiAxis) < 1E-9_m && + wpi::units::math::abs(m_ySemiAxis - other.m_ySemiAxis) < 1E-9_m; } private: Pose2d m_center; - units::meter_t m_xSemiAxis; - units::meter_t m_ySemiAxis; + wpi::units::meter_t m_xSemiAxis; + wpi::units::meter_t m_ySemiAxis; /** * Solves the equation of an ellipse from the given point. This is a helper @@ -210,7 +210,7 @@ class WPILIB_DLLEXPORT Ellipse2d { } }; -} // namespace frc +} // namespace wpi::math #include "wpi/math/geometry/proto/Ellipse2dProto.hpp" #include "wpi/math/geometry/struct/Ellipse2dStruct.hpp" diff --git a/wpimath/src/main/native/include/wpi/math/geometry/Pose2d.hpp b/wpimath/src/main/native/include/wpi/math/geometry/Pose2d.hpp index 66a8899db7..0d506e20a1 100644 --- a/wpimath/src/main/native/include/wpi/math/geometry/Pose2d.hpp +++ b/wpimath/src/main/native/include/wpi/math/geometry/Pose2d.hpp @@ -17,7 +17,7 @@ #include "wpi/util/SymbolExports.hpp" #include "wpi/util/json_fwd.hpp" -namespace frc { +namespace wpi::math { class Transform2d; @@ -49,7 +49,7 @@ class WPILIB_DLLEXPORT Pose2d { * @param y The y component of the translational component of the pose. * @param rotation The rotational component of the pose. */ - constexpr Pose2d(units::meter_t x, units::meter_t y, Rotation2d rotation) + constexpr Pose2d(wpi::units::meter_t x, wpi::units::meter_t y, Rotation2d rotation) : m_translation{x, y}, m_rotation{std::move(rotation)} {} /** @@ -110,14 +110,14 @@ class WPILIB_DLLEXPORT Pose2d { * * @return The x component of the pose's translation. */ - constexpr units::meter_t X() const { return m_translation.X(); } + constexpr wpi::units::meter_t X() const { return m_translation.X(); } /** * Returns the Y component of the pose's translation. * * @return The y component of the pose's translation. */ - constexpr units::meter_t Y() const { return m_translation.Y(); } + constexpr wpi::units::meter_t Y() const { return m_translation.Y(); } /** * Returns the underlying rotation. @@ -265,26 +265,26 @@ class WPILIB_DLLEXPORT Pose2d { }; WPILIB_DLLEXPORT -void to_json(wpi::json& json, const Pose2d& pose); +void to_json(wpi::util::json& json, const Pose2d& pose); WPILIB_DLLEXPORT -void from_json(const wpi::json& json, Pose2d& pose); +void from_json(const wpi::util::json& json, Pose2d& pose); -} // namespace frc +} // namespace wpi::math #include "wpi/math/geometry/proto/Pose2dProto.hpp" #include "wpi/math/geometry/struct/Pose2dStruct.hpp" #include "wpi/math/geometry/Transform2d.hpp" -namespace frc { +namespace wpi::math { constexpr Transform2d Pose2d::operator-(const Pose2d& other) const { const auto pose = this->RelativeTo(other); return Transform2d{pose.Translation(), pose.Rotation()}; } -constexpr Pose2d Pose2d::TransformBy(const frc::Transform2d& other) const { +constexpr Pose2d Pose2d::TransformBy(const wpi::math::Transform2d& other) const { return {m_translation + (other.Translation().RotateBy(m_rotation)), other.Rotation() + m_rotation}; } @@ -294,4 +294,4 @@ constexpr Pose2d Pose2d::RelativeTo(const Pose2d& other) const { return {transform.Translation(), transform.Rotation()}; } -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/geometry/Pose3d.hpp b/wpimath/src/main/native/include/wpi/math/geometry/Pose3d.hpp index b90cc984d2..e66b047142 100644 --- a/wpimath/src/main/native/include/wpi/math/geometry/Pose3d.hpp +++ b/wpimath/src/main/native/include/wpi/math/geometry/Pose3d.hpp @@ -20,7 +20,7 @@ #include "wpi/util/SymbolExports.hpp" #include "wpi/util/json_fwd.hpp" -namespace frc { +namespace wpi::math { class Transform3d; @@ -53,7 +53,7 @@ class WPILIB_DLLEXPORT Pose3d { * @param z The z component of the translational component of the pose. * @param rotation The rotational component of the pose. */ - constexpr Pose3d(units::meter_t x, units::meter_t y, units::meter_t z, + constexpr Pose3d(wpi::units::meter_t x, wpi::units::meter_t y, wpi::units::meter_t z, Rotation3d rotation) : m_translation{x, y, z}, m_rotation{std::move(rotation)} {} @@ -126,21 +126,21 @@ class WPILIB_DLLEXPORT Pose3d { * * @return The x component of the pose's translation. */ - constexpr units::meter_t X() const { return m_translation.X(); } + constexpr wpi::units::meter_t X() const { return m_translation.X(); } /** * Returns the Y component of the pose's translation. * * @return The y component of the pose's translation. */ - constexpr units::meter_t Y() const { return m_translation.Y(); } + constexpr wpi::units::meter_t Y() const { return m_translation.Y(); } /** * Returns the Z component of the pose's translation. * * @return The z component of the pose's translation. */ - constexpr units::meter_t Z() const { return m_translation.Z(); } + constexpr wpi::units::meter_t Z() const { return m_translation.Z(); } /** * Returns the underlying rotation. @@ -297,16 +297,16 @@ class WPILIB_DLLEXPORT Pose3d { }; WPILIB_DLLEXPORT -void to_json(wpi::json& json, const Pose3d& pose); +void to_json(wpi::util::json& json, const Pose3d& pose); WPILIB_DLLEXPORT -void from_json(const wpi::json& json, Pose3d& pose); +void from_json(const wpi::util::json& json, Pose3d& pose); -} // namespace frc +} // namespace wpi::math #include "wpi/math/geometry/Transform3d.hpp" -namespace frc { +namespace wpi::math { constexpr Transform3d Pose3d::operator-(const Pose3d& other) const { const auto pose = this->RelativeTo(other); @@ -323,7 +323,7 @@ constexpr Pose3d Pose3d::RelativeTo(const Pose3d& other) const { return {transform.Translation(), transform.Rotation()}; } -} // namespace frc +} // namespace wpi::math #include "wpi/math/geometry/proto/Pose3dProto.hpp" #include "wpi/math/geometry/struct/Pose3dStruct.hpp" diff --git a/wpimath/src/main/native/include/wpi/math/geometry/Quaternion.hpp b/wpimath/src/main/native/include/wpi/math/geometry/Quaternion.hpp index 4fa3831c92..b25e5f32a9 100644 --- a/wpimath/src/main/native/include/wpi/math/geometry/Quaternion.hpp +++ b/wpimath/src/main/native/include/wpi/math/geometry/Quaternion.hpp @@ -12,7 +12,7 @@ #include "wpi/util/SymbolExports.hpp" #include "wpi/util/json_fwd.hpp" -namespace frc { +namespace wpi::math { /** * Represents a quaternion. @@ -328,12 +328,12 @@ class WPILIB_DLLEXPORT Quaternion { }; WPILIB_DLLEXPORT -void to_json(wpi::json& json, const Quaternion& quaternion); +void to_json(wpi::util::json& json, const Quaternion& quaternion); WPILIB_DLLEXPORT -void from_json(const wpi::json& json, Quaternion& quaternion); +void from_json(const wpi::util::json& json, Quaternion& quaternion); -} // namespace frc +} // namespace wpi::math #include "wpi/math/geometry/proto/QuaternionProto.hpp" #include "wpi/math/geometry/struct/QuaternionStruct.hpp" diff --git a/wpimath/src/main/native/include/wpi/math/geometry/Rectangle2d.hpp b/wpimath/src/main/native/include/wpi/math/geometry/Rectangle2d.hpp index 10ef949680..a13d0b87ac 100644 --- a/wpimath/src/main/native/include/wpi/math/geometry/Rectangle2d.hpp +++ b/wpimath/src/main/native/include/wpi/math/geometry/Rectangle2d.hpp @@ -15,7 +15,7 @@ #include "wpi/units/math.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::math { /** * Represents a 2d rectangular space containing translational, rotational, and @@ -33,8 +33,8 @@ class WPILIB_DLLEXPORT Rectangle2d { * @param yWidth The y size component of the rectangle, in unrotated * coordinate frame. */ - constexpr Rectangle2d(const Pose2d& center, units::meter_t xWidth, - units::meter_t yWidth) + constexpr Rectangle2d(const Pose2d& center, wpi::units::meter_t xWidth, + wpi::units::meter_t yWidth) : m_center{center}, m_xWidth{xWidth}, m_yWidth{yWidth} { if (xWidth < 0_m || yWidth < 0_m) { throw std::invalid_argument( @@ -52,8 +52,8 @@ class WPILIB_DLLEXPORT Rectangle2d { constexpr Rectangle2d(const Translation2d& cornerA, const Translation2d& cornerB) : m_center{(cornerA + cornerB) / 2.0, Rotation2d{}}, - m_xWidth{units::math::abs(cornerA.X() - cornerB.X())}, - m_yWidth{units::math::abs(cornerA.Y() - cornerB.Y())} {} + m_xWidth{wpi::units::math::abs(cornerA.X() - cornerB.X())}, + m_yWidth{wpi::units::math::abs(cornerA.Y() - cornerB.Y())} {} /** * Returns the center of the rectangle. @@ -74,14 +74,14 @@ class WPILIB_DLLEXPORT Rectangle2d { * * @return The x size component of the rectangle. */ - constexpr units::meter_t XWidth() const { return m_xWidth; } + constexpr wpi::units::meter_t XWidth() const { return m_xWidth; } /** * Returns the y size component of the rectangle. * * @return The y size component of the rectangle. */ - constexpr units::meter_t YWidth() const { return m_yWidth; } + constexpr wpi::units::meter_t YWidth() const { return m_yWidth; } /** * Transforms the center of the rectangle and returns the new rectangle. @@ -114,14 +114,14 @@ class WPILIB_DLLEXPORT Rectangle2d { auto pointInRect = point - m_center.Translation(); pointInRect = pointInRect.RotateBy(-m_center.Rotation()); - if (units::math::abs(units::math::abs(pointInRect.X()) - m_xWidth / 2.0) <= + if (wpi::units::math::abs(wpi::units::math::abs(pointInRect.X()) - m_xWidth / 2.0) <= 1E-9_m) { // Point rests on left/right perimeter - return units::math::abs(pointInRect.Y()) <= m_yWidth / 2.0; - } else if (units::math::abs(units::math::abs(pointInRect.Y()) - + return wpi::units::math::abs(pointInRect.Y()) <= m_yWidth / 2.0; + } else if (wpi::units::math::abs(wpi::units::math::abs(pointInRect.Y()) - m_yWidth / 2.0) <= 1E-9_m) { // Point rests on top/bottom perimeter - return units::math::abs(pointInRect.X()) <= m_xWidth / 2.0; + return wpi::units::math::abs(pointInRect.X()) <= m_xWidth / 2.0; } return false; @@ -153,7 +153,7 @@ class WPILIB_DLLEXPORT Rectangle2d { * @param point The point to check. * @return The distance (0, if the point is contained by the rectangle) */ - constexpr units::meter_t Distance(const Translation2d& point) const { + constexpr wpi::units::meter_t Distance(const Translation2d& point) const { return Nearest(point).Distance(point); } @@ -193,17 +193,17 @@ class WPILIB_DLLEXPORT Rectangle2d { */ constexpr bool operator==(const Rectangle2d& other) const { return m_center == other.m_center && - units::math::abs(m_xWidth - other.m_xWidth) < 1E-9_m && - units::math::abs(m_yWidth - other.m_yWidth) < 1E-9_m; + wpi::units::math::abs(m_xWidth - other.m_xWidth) < 1E-9_m && + wpi::units::math::abs(m_yWidth - other.m_yWidth) < 1E-9_m; } private: Pose2d m_center; - units::meter_t m_xWidth; - units::meter_t m_yWidth; + wpi::units::meter_t m_xWidth; + wpi::units::meter_t m_yWidth; }; -} // namespace frc +} // namespace wpi::math #include "wpi/math/geometry/proto/Rectangle2dProto.hpp" #include "wpi/math/geometry/struct/Rectangle2dStruct.hpp" diff --git a/wpimath/src/main/native/include/wpi/math/geometry/Rotation2d.hpp b/wpimath/src/main/native/include/wpi/math/geometry/Rotation2d.hpp index 0961421dcd..0980ff2f24 100644 --- a/wpimath/src/main/native/include/wpi/math/geometry/Rotation2d.hpp +++ b/wpimath/src/main/native/include/wpi/math/geometry/Rotation2d.hpp @@ -17,7 +17,7 @@ #include "wpi/util/SymbolExports.hpp" #include "wpi/util/json_fwd.hpp" -namespace frc { +namespace wpi::math { /** * A rotation in a 2D coordinate frame represented by a point on the unit circle @@ -35,9 +35,9 @@ class WPILIB_DLLEXPORT Rotation2d { * * @param value The value of the angle. */ - constexpr Rotation2d(units::angle_unit auto value) // NOLINT - : m_cos{gcem::cos(value.template convert().value())}, - m_sin{gcem::sin(value.template convert().value())} {} + constexpr Rotation2d(wpi::units::angle_unit auto value) // NOLINT + : m_cos{gcem::cos(value.template convert().value())}, + m_sin{gcem::sin(value.template convert().value())} {} /** * Constructs a Rotation2d with the given x and y (cosine and sine) @@ -57,7 +57,7 @@ class WPILIB_DLLEXPORT Rotation2d { if (!std::is_constant_evaluated()) { wpi::math::MathSharedStore::ReportError( "x and y components of Rotation2d are zero\n{}", - wpi::GetStackTrace(1)); + wpi::util::GetStackTrace(1)); } } } @@ -106,7 +106,7 @@ class WPILIB_DLLEXPORT Rotation2d { * π. * * For example, Rotation2d{30_deg} + Rotation2d{60_deg} equals - * Rotation2d{units::radian_t{std::numbers::pi/2.0}} + * Rotation2d{wpi::units::radian_t{std::numbers::pi/2.0}} * * @param other The rotation to add. * @@ -121,7 +121,7 @@ class WPILIB_DLLEXPORT Rotation2d { * rotation. * * For example, Rotation2d{10_deg} - Rotation2d{100_deg} equals - * Rotation2d{units::radian_t{-std::numbers::pi/2.0}} + * Rotation2d{wpi::units::radian_t{-std::numbers::pi/2.0}} * * @param other The rotation to subtract. * @@ -203,8 +203,8 @@ class WPILIB_DLLEXPORT Rotation2d { * * @return The radian value of the rotation constrained within [-π, π]. */ - constexpr units::radian_t Radians() const { - return units::radian_t{gcem::atan2(m_sin, m_cos)}; + constexpr wpi::units::radian_t Radians() const { + return wpi::units::radian_t{gcem::atan2(m_sin, m_cos)}; } /** @@ -212,7 +212,7 @@ class WPILIB_DLLEXPORT Rotation2d { * * @return The degree value of the rotation constrained within [-180, 180]. */ - constexpr units::degree_t Degrees() const { return Radians(); } + constexpr wpi::units::degree_t Degrees() const { return Radians(); } /** * Returns the cosine of the rotation. @@ -241,12 +241,12 @@ class WPILIB_DLLEXPORT Rotation2d { }; WPILIB_DLLEXPORT -void to_json(wpi::json& json, const Rotation2d& rotation); +void to_json(wpi::util::json& json, const Rotation2d& rotation); WPILIB_DLLEXPORT -void from_json(const wpi::json& json, Rotation2d& rotation); +void from_json(const wpi::util::json& json, Rotation2d& rotation); -} // namespace frc +} // namespace wpi::math #include "wpi/math/geometry/proto/Rotation2dProto.hpp" #include "wpi/math/geometry/struct/Rotation2dStruct.hpp" diff --git a/wpimath/src/main/native/include/wpi/math/geometry/Rotation3d.hpp b/wpimath/src/main/native/include/wpi/math/geometry/Rotation3d.hpp index 9548c4ce4c..2ad0e70f9d 100644 --- a/wpimath/src/main/native/include/wpi/math/geometry/Rotation3d.hpp +++ b/wpimath/src/main/native/include/wpi/math/geometry/Rotation3d.hpp @@ -21,7 +21,7 @@ #include "wpi/util/SymbolExports.hpp" #include "wpi/util/json_fwd.hpp" -namespace frc { +namespace wpi::math { /** * A rotation in a 3D coordinate frame represented by a quaternion. @@ -54,17 +54,17 @@ class WPILIB_DLLEXPORT Rotation3d { * @param pitch The counterclockwise rotation angle around the Y axis (pitch). * @param yaw The counterclockwise rotation angle around the Z axis (yaw). */ - constexpr Rotation3d(units::radian_t roll, units::radian_t pitch, - units::radian_t yaw) { + constexpr Rotation3d(wpi::units::radian_t roll, wpi::units::radian_t pitch, + wpi::units::radian_t yaw) { // https://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles#Euler_angles_to_quaternion_conversion - double cr = units::math::cos(roll * 0.5); - double sr = units::math::sin(roll * 0.5); + double cr = wpi::units::math::cos(roll * 0.5); + double sr = wpi::units::math::sin(roll * 0.5); - double cp = units::math::cos(pitch * 0.5); - double sp = units::math::sin(pitch * 0.5); + double cp = wpi::units::math::cos(pitch * 0.5); + double sp = wpi::units::math::sin(pitch * 0.5); - double cy = units::math::cos(yaw * 0.5); - double sy = units::math::sin(yaw * 0.5); + double cy = wpi::units::math::cos(yaw * 0.5); + double sy = wpi::units::math::sin(yaw * 0.5); m_q = Quaternion{cr * cp * cy + sr * sp * sy, sr * cp * cy - cr * sp * sy, cr * sp * cy + sr * cp * sy, cr * cp * sy - sr * sp * cy}; @@ -77,17 +77,17 @@ class WPILIB_DLLEXPORT Rotation3d { * @param axis The rotation axis. * @param angle The rotation around the axis. */ - constexpr Rotation3d(const Eigen::Vector3d& axis, units::radian_t angle) { + constexpr Rotation3d(const Eigen::Vector3d& axis, wpi::units::radian_t angle) { double norm = ct_matrix{axis}.norm(); if (norm == 0.0) { return; } // https://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles#Definition - Eigen::Vector3d v{{axis(0) / norm * units::math::sin(angle / 2.0), - axis(1) / norm * units::math::sin(angle / 2.0), - axis(2) / norm * units::math::sin(angle / 2.0)}}; - m_q = Quaternion{units::math::cos(angle / 2.0), v(0), v(1), v(2)}; + Eigen::Vector3d v{{axis(0) / norm * wpi::units::math::sin(angle / 2.0), + axis(1) / norm * wpi::units::math::sin(angle / 2.0), + axis(2) / norm * wpi::units::math::sin(angle / 2.0)}}; + m_q = Quaternion{wpi::units::math::cos(angle / 2.0), v(0), v(1), v(2)}; } /** @@ -98,7 +98,7 @@ class WPILIB_DLLEXPORT Rotation3d { * @param rvec The rotation vector. */ constexpr explicit Rotation3d(const Eigen::Vector3d& rvec) - : Rotation3d{rvec, units::radian_t{ct_matrix{rvec}.norm()}} {} + : Rotation3d{rvec, wpi::units::radian_t{ct_matrix{rvec}.norm()}} {} /** * Constructs a Rotation3d from a rotation matrix. @@ -282,10 +282,10 @@ class WPILIB_DLLEXPORT Rotation3d { // https://en.wikipedia.org/wiki/Slerp#Quaternion_Slerp if (m_q.W() >= 0.0) { return Rotation3d{Eigen::Vector3d{{m_q.X(), m_q.Y(), m_q.Z()}}, - 2.0 * units::radian_t{scalar * gcem::acos(m_q.W())}}; + 2.0 * wpi::units::radian_t{scalar * gcem::acos(m_q.W())}}; } else { return Rotation3d{Eigen::Vector3d{{-m_q.X(), -m_q.Y(), -m_q.Z()}}, - 2.0 * units::radian_t{scalar * gcem::acos(-m_q.W())}}; + 2.0 * wpi::units::radian_t{scalar * gcem::acos(-m_q.W())}}; } } @@ -331,7 +331,7 @@ class WPILIB_DLLEXPORT Rotation3d { /** * Returns the counterclockwise rotation angle around the X axis (roll). */ - constexpr units::radian_t X() const { + constexpr wpi::units::radian_t X() const { double w = m_q.W(); double x = m_q.X(); double y = m_q.Y(); @@ -342,7 +342,7 @@ class WPILIB_DLLEXPORT Rotation3d { double sxcy = 2.0 * (w * x + y * z); double cy_sq = cxcy * cxcy + sxcy * sxcy; if (cy_sq > 1e-20) { - return units::radian_t{gcem::atan2(sxcy, cxcy)}; + return wpi::units::radian_t{gcem::atan2(sxcy, cxcy)}; } else { return 0_rad; } @@ -351,7 +351,7 @@ class WPILIB_DLLEXPORT Rotation3d { /** * Returns the counterclockwise rotation angle around the Y axis (pitch). */ - constexpr units::radian_t Y() const { + constexpr wpi::units::radian_t Y() const { double w = m_q.W(); double x = m_q.X(); double y = m_q.Y(); @@ -360,16 +360,16 @@ class WPILIB_DLLEXPORT Rotation3d { // https://en.wikipedia.org/wiki/Conversion_between_quaternions_and_Euler_angles#Quaternion_to_Euler_angles_(in_3-2-1_sequence)_conversion double ratio = 2.0 * (w * y - z * x); if (gcem::abs(ratio) >= 1.0) { - return units::radian_t{gcem::copysign(std::numbers::pi / 2.0, ratio)}; + return wpi::units::radian_t{gcem::copysign(std::numbers::pi / 2.0, ratio)}; } else { - return units::radian_t{gcem::asin(ratio)}; + return wpi::units::radian_t{gcem::asin(ratio)}; } } /** * Returns the counterclockwise rotation angle around the Z axis (yaw). */ - constexpr units::radian_t Z() const { + constexpr wpi::units::radian_t Z() const { double w = m_q.W(); double x = m_q.X(); double y = m_q.Y(); @@ -380,9 +380,9 @@ class WPILIB_DLLEXPORT Rotation3d { double cysz = 2.0 * (w * z + x * y); double cy_sq = cycz * cycz + cysz * cysz; if (cy_sq > 1e-20) { - return units::radian_t{gcem::atan2(cysz, cycz)}; + return wpi::units::radian_t{gcem::atan2(cysz, cycz)}; } else { - return units::radian_t{gcem::atan2(2.0 * w * z, w * w - z * z)}; + return wpi::units::radian_t{gcem::atan2(2.0 * w * z, w * w - z * z)}; } } @@ -401,9 +401,9 @@ class WPILIB_DLLEXPORT Rotation3d { /** * Returns the angle in the axis-angle representation of this rotation. */ - constexpr units::radian_t Angle() const { + constexpr wpi::units::radian_t Angle() const { double norm = gcem::hypot(m_q.X(), m_q.Y(), m_q.Z()); - return units::radian_t{2.0 * gcem::atan2(norm, m_q.W())}; + return wpi::units::radian_t{2.0 * gcem::atan2(norm, m_q.W())}; } /** @@ -442,12 +442,12 @@ class WPILIB_DLLEXPORT Rotation3d { }; WPILIB_DLLEXPORT -void to_json(wpi::json& json, const Rotation3d& rotation); +void to_json(wpi::util::json& json, const Rotation3d& rotation); WPILIB_DLLEXPORT -void from_json(const wpi::json& json, Rotation3d& rotation); +void from_json(const wpi::util::json& json, Rotation3d& rotation); -} // namespace frc +} // namespace wpi::math #include "wpi/math/geometry/proto/Rotation3dProto.hpp" #include "wpi/math/geometry/struct/Rotation3dStruct.hpp" diff --git a/wpimath/src/main/native/include/wpi/math/geometry/Transform2d.hpp b/wpimath/src/main/native/include/wpi/math/geometry/Transform2d.hpp index fe257e76cf..685ce95260 100644 --- a/wpimath/src/main/native/include/wpi/math/geometry/Transform2d.hpp +++ b/wpimath/src/main/native/include/wpi/math/geometry/Transform2d.hpp @@ -10,7 +10,7 @@ #include "wpi/math/geometry/Translation2d.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::math { class Pose2d; struct Twist2d; @@ -46,7 +46,7 @@ class WPILIB_DLLEXPORT Transform2d { * @param y The y component of the translational component of the transform. * @param rotation The rotational component of the transform. */ - constexpr Transform2d(units::meter_t x, units::meter_t y, Rotation2d rotation) + constexpr Transform2d(wpi::units::meter_t x, wpi::units::meter_t y, Rotation2d rotation) : m_translation{x, y}, m_rotation{std::move(rotation)} {} /** @@ -81,14 +81,14 @@ class WPILIB_DLLEXPORT Transform2d { * * @return The x component of the transformation's translation. */ - constexpr units::meter_t X() const { return m_translation.X(); } + constexpr wpi::units::meter_t X() const { return m_translation.X(); } /** * Returns the Y component of the transformation's translation. * * @return The y component of the transformation's translation. */ - constexpr units::meter_t Y() const { return m_translation.Y(); } + constexpr wpi::units::meter_t Y() const { return m_translation.Y(); } /** * Returns an affine transformation matrix representation of this @@ -168,12 +168,12 @@ class WPILIB_DLLEXPORT Transform2d { Rotation2d m_rotation; }; -} // namespace frc +} // namespace wpi::math #include "wpi/math/geometry/Pose2d.hpp" #include "wpi/math/geometry/Twist2d.hpp" -namespace frc { +namespace wpi::math { constexpr Transform2d::Transform2d(const Pose2d& initial, const Pose2d& final) { // We are rotating the difference between the translations @@ -207,10 +207,10 @@ constexpr Twist2d Transform2d::Log() const { m_translation.RotateBy({halfThetaByTanOfHalfDtheta, -halfDtheta}) * gcem::hypot(halfThetaByTanOfHalfDtheta, halfDtheta); - return {translationPart.X(), translationPart.Y(), units::radian_t{dtheta}}; + return {translationPart.X(), translationPart.Y(), wpi::units::radian_t{dtheta}}; } -} // namespace frc +} // namespace wpi::math #include "wpi/math/geometry/proto/Transform2dProto.hpp" #include "wpi/math/geometry/struct/Transform2dStruct.hpp" diff --git a/wpimath/src/main/native/include/wpi/math/geometry/Transform3d.hpp b/wpimath/src/main/native/include/wpi/math/geometry/Transform3d.hpp index e235986578..cbdc0f492c 100644 --- a/wpimath/src/main/native/include/wpi/math/geometry/Transform3d.hpp +++ b/wpimath/src/main/native/include/wpi/math/geometry/Transform3d.hpp @@ -10,7 +10,7 @@ #include "wpi/math/geometry/Translation3d.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::math { class Pose3d; struct Twist3d; @@ -47,7 +47,7 @@ class WPILIB_DLLEXPORT Transform3d { * @param z The z component of the translational component of the transform. * @param rotation The rotational component of the transform. */ - constexpr Transform3d(units::meter_t x, units::meter_t y, units::meter_t z, + constexpr Transform3d(wpi::units::meter_t x, wpi::units::meter_t y, wpi::units::meter_t z, Rotation3d rotation) : m_translation{x, y, z}, m_rotation{std::move(rotation)} {} @@ -82,9 +82,9 @@ class WPILIB_DLLEXPORT Transform3d { * @see Rotation3d(Rotation2d) * @see Translation3d(Translation2d) */ - constexpr explicit Transform3d(const frc::Transform2d& transform) - : m_translation{frc::Translation3d{transform.Translation()}}, - m_rotation{frc::Rotation3d{transform.Rotation()}} {} + constexpr explicit Transform3d(const wpi::math::Transform2d& transform) + : m_translation{wpi::math::Translation3d{transform.Translation()}}, + m_rotation{wpi::math::Rotation3d{transform.Rotation()}} {} /** * Returns the translation component of the transformation. @@ -98,21 +98,21 @@ class WPILIB_DLLEXPORT Transform3d { * * @return The x component of the transformation's translation. */ - constexpr units::meter_t X() const { return m_translation.X(); } + constexpr wpi::units::meter_t X() const { return m_translation.X(); } /** * Returns the Y component of the transformation's translation. * * @return The y component of the transformation's translation. */ - constexpr units::meter_t Y() const { return m_translation.Y(); } + constexpr wpi::units::meter_t Y() const { return m_translation.Y(); } /** * Returns the Z component of the transformation's translation. * * @return The z component of the transformation's translation. */ - constexpr units::meter_t Z() const { return m_translation.Z(); } + constexpr wpi::units::meter_t Z() const { return m_translation.Z(); } /** * Returns an affine transformation matrix representation of this @@ -193,13 +193,13 @@ class WPILIB_DLLEXPORT Transform3d { Rotation3d m_rotation; }; -} // namespace frc +} // namespace wpi::math #include "wpi/math/geometry/Pose3d.hpp" #include "wpi/math/geometry/Twist3d.hpp" #include "wpi/math/geometry/detail/RotationVectorToMatrix.hpp" -namespace frc { +namespace wpi::math { constexpr Transform3d::Transform3d(const Pose3d& initial, const Pose3d& final) { // We are rotating the difference between the translations @@ -254,12 +254,12 @@ constexpr Twist3d Transform3d::Log() const { Vector3d translation_component = V_inv * u; - return Twist3d{units::meter_t{translation_component(0)}, - units::meter_t{translation_component(1)}, - units::meter_t{translation_component(2)}, - units::radian_t{rvec(0)}, - units::radian_t{rvec(1)}, - units::radian_t{rvec(2)}}; + return Twist3d{wpi::units::meter_t{translation_component(0)}, + wpi::units::meter_t{translation_component(1)}, + wpi::units::meter_t{translation_component(2)}, + wpi::units::radian_t{rvec(0)}, + wpi::units::radian_t{rvec(1)}, + wpi::units::radian_t{rvec(2)}}; }; if (std::is_constant_evaluated()) { @@ -268,7 +268,7 @@ constexpr Twist3d Transform3d::Log() const { return impl.template operator()(); } -} // namespace frc +} // namespace wpi::math #include "wpi/math/geometry/proto/Transform3dProto.hpp" #include "wpi/math/geometry/struct/Transform3dStruct.hpp" diff --git a/wpimath/src/main/native/include/wpi/math/geometry/Translation2d.hpp b/wpimath/src/main/native/include/wpi/math/geometry/Translation2d.hpp index 9270e38448..dcaa62ca90 100644 --- a/wpimath/src/main/native/include/wpi/math/geometry/Translation2d.hpp +++ b/wpimath/src/main/native/include/wpi/math/geometry/Translation2d.hpp @@ -17,7 +17,7 @@ #include "wpi/util/SymbolExports.hpp" #include "wpi/util/json_fwd.hpp" -namespace frc { +namespace wpi::math { /** * Represents a translation in 2D space. @@ -41,7 +41,7 @@ class WPILIB_DLLEXPORT Translation2d { * @param x The x component of the translation. * @param y The y component of the translation. */ - constexpr Translation2d(units::meter_t x, units::meter_t y) + constexpr Translation2d(wpi::units::meter_t x, wpi::units::meter_t y) : m_x{x}, m_y{y} {} /** @@ -51,7 +51,7 @@ class WPILIB_DLLEXPORT Translation2d { * @param distance The distance from the origin to the end of the translation. * @param angle The angle between the x-axis and the translation vector. */ - constexpr Translation2d(units::meter_t distance, const Rotation2d& angle) + constexpr Translation2d(wpi::units::meter_t distance, const Rotation2d& angle) : m_x{distance * angle.Cos()}, m_y{distance * angle.Sin()} {} /** @@ -61,7 +61,7 @@ class WPILIB_DLLEXPORT Translation2d { * @param vector The translation vector. */ constexpr explicit Translation2d(const Eigen::Vector2d& vector) - : m_x{units::meter_t{vector.x()}}, m_y{units::meter_t{vector.y()}} {} + : m_x{wpi::units::meter_t{vector.x()}}, m_y{wpi::units::meter_t{vector.y()}} {} /** * Calculates the distance between two translations in 2D space. @@ -72,8 +72,8 @@ class WPILIB_DLLEXPORT Translation2d { * * @return The distance between the two translations. */ - constexpr units::meter_t Distance(const Translation2d& other) const { - return units::math::hypot(other.m_x - m_x, other.m_y - m_y); + constexpr wpi::units::meter_t Distance(const Translation2d& other) const { + return wpi::units::math::hypot(other.m_x - m_x, other.m_y - m_y); } /** @@ -87,10 +87,10 @@ class WPILIB_DLLEXPORT Translation2d { * @param other The translation to compute the squared distance to. * @return The square of the distance between the two translations. */ - constexpr units::square_meter_t SquaredDistance( + constexpr wpi::units::square_meter_t SquaredDistance( const Translation2d& other) const { - return units::math::pow<2>(other.m_x - m_x) + - units::math::pow<2>(other.m_y - m_y); + return wpi::units::math::pow<2>(other.m_x - m_x) + + wpi::units::math::pow<2>(other.m_y - m_y); } /** @@ -98,14 +98,14 @@ class WPILIB_DLLEXPORT Translation2d { * * @return The X component of the translation. */ - constexpr units::meter_t X() const { return m_x; } + constexpr wpi::units::meter_t X() const { return m_x; } /** * Returns the Y component of the translation. * * @return The Y component of the translation. */ - constexpr units::meter_t Y() const { return m_y; } + constexpr wpi::units::meter_t Y() const { return m_y; } /** * Returns a 2D translation vector representation of this translation. @@ -121,7 +121,7 @@ class WPILIB_DLLEXPORT Translation2d { * * @return The norm of the translation. */ - constexpr units::meter_t Norm() const { return units::math::hypot(m_x, m_y); } + constexpr wpi::units::meter_t Norm() const { return wpi::units::math::hypot(m_x, m_y); } /** * Returns the squared norm, or squared distance from the origin to the @@ -130,8 +130,8 @@ class WPILIB_DLLEXPORT Translation2d { * * @return The squared norm of the translation. */ - constexpr units::square_meter_t SquaredNorm() const { - return units::math::pow<2>(m_x) + units::math::pow<2>(m_y); + constexpr wpi::units::square_meter_t SquaredNorm() const { + return wpi::units::math::pow<2>(m_x) + wpi::units::math::pow<2>(m_y); } /** @@ -195,7 +195,7 @@ class WPILIB_DLLEXPORT Translation2d { * @param other The translation to compute the dot product with. * @return The dot product between the two translations. */ - constexpr units::square_meter_t Dot(const Translation2d& other) const { + constexpr wpi::units::square_meter_t Dot(const Translation2d& other) const { return m_x * other.X() + m_y * other.Y(); } @@ -208,7 +208,7 @@ class WPILIB_DLLEXPORT Translation2d { * @param other The translation to compute the cross product with. * @return The cross product between the two translations. */ - constexpr units::square_meter_t Cross(const Translation2d& other) const { + constexpr wpi::units::square_meter_t Cross(const Translation2d& other) const { return m_x * other.Y() - m_y * other.X(); } @@ -282,8 +282,8 @@ class WPILIB_DLLEXPORT Translation2d { * @return Whether the two objects are equal. */ constexpr bool operator==(const Translation2d& other) const { - return units::math::abs(m_x - other.m_x) < 1E-9_m && - units::math::abs(m_y - other.m_y) < 1E-9_m; + return wpi::units::math::abs(m_x - other.m_x) < 1E-9_m && + wpi::units::math::abs(m_y - other.m_y) < 1E-9_m; } /** @@ -315,17 +315,17 @@ class WPILIB_DLLEXPORT Translation2d { } private: - units::meter_t m_x = 0_m; - units::meter_t m_y = 0_m; + wpi::units::meter_t m_x = 0_m; + wpi::units::meter_t m_y = 0_m; }; WPILIB_DLLEXPORT -void to_json(wpi::json& json, const Translation2d& state); +void to_json(wpi::util::json& json, const Translation2d& state); WPILIB_DLLEXPORT -void from_json(const wpi::json& json, Translation2d& state); +void from_json(const wpi::util::json& json, Translation2d& state); -} // namespace frc +} // namespace wpi::math #include "wpi/math/geometry/proto/Translation2dProto.hpp" #include "wpi/math/geometry/struct/Translation2dStruct.hpp" diff --git a/wpimath/src/main/native/include/wpi/math/geometry/Translation3d.hpp b/wpimath/src/main/native/include/wpi/math/geometry/Translation3d.hpp index 564394ad6e..2f2d80261a 100644 --- a/wpimath/src/main/native/include/wpi/math/geometry/Translation3d.hpp +++ b/wpimath/src/main/native/include/wpi/math/geometry/Translation3d.hpp @@ -18,7 +18,7 @@ #include "wpi/util/SymbolExports.hpp" #include "wpi/util/json_fwd.hpp" -namespace frc { +namespace wpi::math { /** * Represents a translation in 3D space. @@ -43,7 +43,7 @@ class WPILIB_DLLEXPORT Translation3d { * @param y The y component of the translation. * @param z The z component of the translation. */ - constexpr Translation3d(units::meter_t x, units::meter_t y, units::meter_t z) + constexpr Translation3d(wpi::units::meter_t x, wpi::units::meter_t y, wpi::units::meter_t z) : m_x{x}, m_y{y}, m_z{z} {} /** @@ -53,7 +53,7 @@ class WPILIB_DLLEXPORT Translation3d { * @param distance The distance from the origin to the end of the translation. * @param angle The angle between the x-axis and the translation vector. */ - constexpr Translation3d(units::meter_t distance, const Rotation3d& angle) { + constexpr Translation3d(wpi::units::meter_t distance, const Rotation3d& angle) { auto rectangular = Translation3d{distance, 0_m, 0_m}.RotateBy(angle); m_x = rectangular.X(); m_y = rectangular.Y(); @@ -67,9 +67,9 @@ class WPILIB_DLLEXPORT Translation3d { * @param vector The translation vector. */ constexpr explicit Translation3d(const Eigen::Vector3d& vector) - : m_x{units::meter_t{vector.x()}}, - m_y{units::meter_t{vector.y()}}, - m_z{units::meter_t{vector.z()}} {} + : m_x{wpi::units::meter_t{vector.x()}}, + m_y{wpi::units::meter_t{vector.y()}}, + m_z{wpi::units::meter_t{vector.z()}} {} /** * Constructs a 3D translation from a 2D translation in the X-Y plane. @@ -91,10 +91,10 @@ class WPILIB_DLLEXPORT Translation3d { * * @return The distance between the two translations. */ - constexpr units::meter_t Distance(const Translation3d& other) const { - return units::math::sqrt(units::math::pow<2>(other.m_x - m_x) + - units::math::pow<2>(other.m_y - m_y) + - units::math::pow<2>(other.m_z - m_z)); + constexpr wpi::units::meter_t Distance(const Translation3d& other) const { + return wpi::units::math::sqrt(wpi::units::math::pow<2>(other.m_x - m_x) + + wpi::units::math::pow<2>(other.m_y - m_y) + + wpi::units::math::pow<2>(other.m_z - m_z)); } /** @@ -108,11 +108,11 @@ class WPILIB_DLLEXPORT Translation3d { * @param other The translation to compute the squared distance to. * @return The squared distance between the two translations. */ - constexpr units::square_meter_t SquaredDistance( + constexpr wpi::units::square_meter_t SquaredDistance( const Translation3d& other) const { - return units::math::pow<2>(other.m_x - m_x) + - units::math::pow<2>(other.m_y - m_y) + - units::math::pow<2>(other.m_z - m_z); + return wpi::units::math::pow<2>(other.m_x - m_x) + + wpi::units::math::pow<2>(other.m_y - m_y) + + wpi::units::math::pow<2>(other.m_z - m_z); } /** @@ -120,21 +120,21 @@ class WPILIB_DLLEXPORT Translation3d { * * @return The Z component of the translation. */ - constexpr units::meter_t X() const { return m_x; } + constexpr wpi::units::meter_t X() const { return m_x; } /** * Returns the Y component of the translation. * * @return The Y component of the translation. */ - constexpr units::meter_t Y() const { return m_y; } + constexpr wpi::units::meter_t Y() const { return m_y; } /** * Returns the Z component of the translation. * * @return The Z component of the translation. */ - constexpr units::meter_t Z() const { return m_z; } + constexpr wpi::units::meter_t Z() const { return m_z; } /** * Returns a 3D translation vector representation of this translation. @@ -150,8 +150,8 @@ class WPILIB_DLLEXPORT Translation3d { * * @return The norm of the translation. */ - constexpr units::meter_t Norm() const { - return units::math::sqrt(m_x * m_x + m_y * m_y + m_z * m_z); + constexpr wpi::units::meter_t Norm() const { + return wpi::units::math::sqrt(m_x * m_x + m_y * m_y + m_z * m_z); } /** @@ -161,7 +161,7 @@ class WPILIB_DLLEXPORT Translation3d { * * @return The squared norm of the translation. */ - constexpr units::square_meter_t SquaredNorm() const { + constexpr wpi::units::square_meter_t SquaredNorm() const { return m_x * m_x + m_y * m_y + m_z * m_z; } @@ -178,8 +178,8 @@ class WPILIB_DLLEXPORT Translation3d { constexpr Translation3d RotateBy(const Rotation3d& other) const { Quaternion p{0.0, m_x.value(), m_y.value(), m_z.value()}; auto qprime = other.GetQuaternion() * p * other.GetQuaternion().Inverse(); - return Translation3d{units::meter_t{qprime.X()}, units::meter_t{qprime.Y()}, - units::meter_t{qprime.Z()}}; + return Translation3d{wpi::units::meter_t{qprime.X()}, wpi::units::meter_t{qprime.Y()}, + wpi::units::meter_t{qprime.Z()}}; } /** @@ -203,7 +203,7 @@ class WPILIB_DLLEXPORT Translation3d { * @param other The translation to compute the dot product with. * @return The dot product between the two translations. */ - constexpr units::square_meter_t Dot(const Translation3d& other) const { + constexpr wpi::units::square_meter_t Dot(const Translation3d& other) const { return m_x * other.X() + m_y * other.Y() + m_z * other.Z(); } @@ -218,9 +218,9 @@ class WPILIB_DLLEXPORT Translation3d { * @param other The translation to compute the cross product with. * @return The cross product between the two translations. */ - constexpr Eigen::Vector Cross( + constexpr Eigen::Vector Cross( const Translation3d& other) const { - return Eigen::Vector{ + return Eigen::Vector{ {m_y * other.Z() - other.Y() * m_z}, {m_z * other.X() - other.Z() * m_x}, {m_x * other.Y() - other.X() * m_y}}; @@ -305,9 +305,9 @@ class WPILIB_DLLEXPORT Translation3d { * @return Whether the two objects are equal. */ constexpr bool operator==(const Translation3d& other) const { - return units::math::abs(m_x - other.m_x) < 1E-9_m && - units::math::abs(m_y - other.m_y) < 1E-9_m && - units::math::abs(m_z - other.m_z) < 1E-9_m; + return wpi::units::math::abs(m_x - other.m_x) < 1E-9_m && + wpi::units::math::abs(m_y - other.m_y) < 1E-9_m && + wpi::units::math::abs(m_z - other.m_z) < 1E-9_m; } /** @@ -339,18 +339,18 @@ class WPILIB_DLLEXPORT Translation3d { } private: - units::meter_t m_x = 0_m; - units::meter_t m_y = 0_m; - units::meter_t m_z = 0_m; + wpi::units::meter_t m_x = 0_m; + wpi::units::meter_t m_y = 0_m; + wpi::units::meter_t m_z = 0_m; }; WPILIB_DLLEXPORT -void to_json(wpi::json& json, const Translation3d& state); +void to_json(wpi::util::json& json, const Translation3d& state); WPILIB_DLLEXPORT -void from_json(const wpi::json& json, Translation3d& state); +void from_json(const wpi::util::json& json, Translation3d& state); -} // namespace frc +} // namespace wpi::math #include "wpi/math/geometry/proto/Translation3dProto.hpp" #include "wpi/math/geometry/struct/Translation3dStruct.hpp" diff --git a/wpimath/src/main/native/include/wpi/math/geometry/Twist2d.hpp b/wpimath/src/main/native/include/wpi/math/geometry/Twist2d.hpp index 9406c4fe1b..6280d17e18 100644 --- a/wpimath/src/main/native/include/wpi/math/geometry/Twist2d.hpp +++ b/wpimath/src/main/native/include/wpi/math/geometry/Twist2d.hpp @@ -9,7 +9,7 @@ #include "wpi/units/math.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::math { class Transform2d; @@ -24,17 +24,17 @@ struct WPILIB_DLLEXPORT Twist2d { /** * Linear "dx" component */ - units::meter_t dx = 0_m; + wpi::units::meter_t dx = 0_m; /** * Linear "dy" component */ - units::meter_t dy = 0_m; + wpi::units::meter_t dy = 0_m; /** * Angular "dtheta" component (radians) */ - units::radian_t dtheta = 0_rad; + wpi::units::radian_t dtheta = 0_rad; /** * Obtain a new Transform2d from a (constant curvature) velocity. @@ -61,9 +61,9 @@ struct WPILIB_DLLEXPORT Twist2d { * @return Whether the two objects are equal. */ constexpr bool operator==(const Twist2d& other) const { - return units::math::abs(dx - other.dx) < 1E-9_m && - units::math::abs(dy - other.dy) < 1E-9_m && - units::math::abs(dtheta - other.dtheta) < 1E-9_rad; + return wpi::units::math::abs(dx - other.dx) < 1E-9_m && + wpi::units::math::abs(dy - other.dy) < 1E-9_m && + wpi::units::math::abs(dtheta - other.dtheta) < 1E-9_rad; } /** @@ -77,11 +77,11 @@ struct WPILIB_DLLEXPORT Twist2d { } }; -} // namespace frc +} // namespace wpi::math #include "wpi/math/geometry/Transform2d.hpp" -namespace frc { +namespace wpi::math { constexpr Transform2d Twist2d::Exp() const { const auto theta = dtheta.value(); @@ -101,7 +101,7 @@ constexpr Transform2d Twist2d::Exp() const { Rotation2d{cosTheta, sinTheta}); } -} // namespace frc +} // namespace wpi::math #include "wpi/math/geometry/proto/Twist2dProto.hpp" #include "wpi/math/geometry/struct/Twist2dStruct.hpp" diff --git a/wpimath/src/main/native/include/wpi/math/geometry/Twist3d.hpp b/wpimath/src/main/native/include/wpi/math/geometry/Twist3d.hpp index 01debdd51c..036362307b 100644 --- a/wpimath/src/main/native/include/wpi/math/geometry/Twist3d.hpp +++ b/wpimath/src/main/native/include/wpi/math/geometry/Twist3d.hpp @@ -9,7 +9,7 @@ #include "wpi/units/math.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::math { class Transform3d; @@ -24,32 +24,32 @@ struct WPILIB_DLLEXPORT Twist3d { /** * Linear "dx" component */ - units::meter_t dx = 0_m; + wpi::units::meter_t dx = 0_m; /** * Linear "dy" component */ - units::meter_t dy = 0_m; + wpi::units::meter_t dy = 0_m; /** * Linear "dz" component */ - units::meter_t dz = 0_m; + wpi::units::meter_t dz = 0_m; /** * Rotation vector x component. */ - units::radian_t rx = 0_rad; + wpi::units::radian_t rx = 0_rad; /** * Rotation vector y component. */ - units::radian_t ry = 0_rad; + wpi::units::radian_t ry = 0_rad; /** * Rotation vector z component. */ - units::radian_t rz = 0_rad; + wpi::units::radian_t rz = 0_rad; /** * Obtain a new Transform3d from a (constant curvature) velocity. @@ -76,12 +76,12 @@ struct WPILIB_DLLEXPORT Twist3d { * @return Whether the two objects are equal. */ constexpr bool operator==(const Twist3d& other) const { - return units::math::abs(dx - other.dx) < 1E-9_m && - units::math::abs(dy - other.dy) < 1E-9_m && - units::math::abs(dz - other.dz) < 1E-9_m && - units::math::abs(rx - other.rx) < 1E-9_rad && - units::math::abs(ry - other.ry) < 1E-9_rad && - units::math::abs(rz - other.rz) < 1E-9_rad; + return wpi::units::math::abs(dx - other.dx) < 1E-9_m && + wpi::units::math::abs(dy - other.dy) < 1E-9_m && + wpi::units::math::abs(dz - other.dz) < 1E-9_m && + wpi::units::math::abs(rx - other.rx) < 1E-9_rad && + wpi::units::math::abs(ry - other.ry) < 1E-9_rad && + wpi::units::math::abs(rz - other.rz) < 1E-9_rad; } /** @@ -96,12 +96,12 @@ struct WPILIB_DLLEXPORT Twist3d { } }; -} // namespace frc +} // namespace wpi::math #include "wpi/math/geometry/Transform3d.hpp" #include "wpi/math/geometry/detail/RotationVectorToMatrix.hpp" -namespace frc { +namespace wpi::math { constexpr Transform3d Twist3d::Exp() const { // Implementation from Section 3.2 of https://ethaneade.org/lie.pdf @@ -147,9 +147,9 @@ constexpr Transform3d Twist3d::Exp() const { Vector3d translation_component = V * u; const Transform3d transform{ - Translation3d{units::meter_t{translation_component(0)}, - units::meter_t{translation_component(1)}, - units::meter_t{translation_component(2)}}, + Translation3d{wpi::units::meter_t{translation_component(0)}, + wpi::units::meter_t{translation_component(1)}, + wpi::units::meter_t{translation_component(2)}}, Rotation3d{R}}; return transform; @@ -161,7 +161,7 @@ constexpr Transform3d Twist3d::Exp() const { return impl.template operator()(); } -} // namespace frc +} // namespace wpi::math #include "wpi/math/geometry/proto/Twist3dProto.hpp" #include "wpi/math/geometry/struct/Twist3dStruct.hpp" diff --git a/wpimath/src/main/native/include/wpi/math/geometry/detail/RotationVectorToMatrix.hpp b/wpimath/src/main/native/include/wpi/math/geometry/detail/RotationVectorToMatrix.hpp index a955970db8..e8ecfccbf7 100644 --- a/wpimath/src/main/native/include/wpi/math/geometry/detail/RotationVectorToMatrix.hpp +++ b/wpimath/src/main/native/include/wpi/math/geometry/detail/RotationVectorToMatrix.hpp @@ -8,7 +8,7 @@ #include "wpi/math/linalg/ct_matrix.hpp" -namespace frc::detail { +namespace wpi::math::detail { constexpr ct_matrix3d RotationVectorToMatrix(const ct_vector3d& rotation) { return ct_matrix3d{{0.0, -rotation(2), rotation(1)}, @@ -23,4 +23,4 @@ constexpr Eigen::Matrix3d RotationVectorToMatrix( {-rotation(1), rotation(0), 0.0}}; } -} // namespace frc::detail +} // namespace wpi::math::detail diff --git a/wpimath/src/main/native/include/wpi/math/geometry/proto/Ellipse2dProto.hpp b/wpimath/src/main/native/include/wpi/math/geometry/proto/Ellipse2dProto.hpp index d8b8ddaa09..41f9bee1d3 100644 --- a/wpimath/src/main/native/include/wpi/math/geometry/proto/Ellipse2dProto.hpp +++ b/wpimath/src/main/native/include/wpi/math/geometry/proto/Ellipse2dProto.hpp @@ -10,10 +10,10 @@ #include "wpimath/protobuf/geometry2d.npb.h" template <> -struct WPILIB_DLLEXPORT wpi::Protobuf { +struct WPILIB_DLLEXPORT wpi::util::Protobuf { using MessageStruct = wpi_proto_ProtobufEllipse2d; - using InputStream = wpi::ProtoInputStream; - using OutputStream = wpi::ProtoOutputStream; - static std::optional Unpack(InputStream& stream); - static bool Pack(OutputStream& stream, const frc::Ellipse2d& value); + using InputStream = wpi::util::ProtoInputStream; + using OutputStream = wpi::util::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const wpi::math::Ellipse2d& value); }; diff --git a/wpimath/src/main/native/include/wpi/math/geometry/proto/Pose2dProto.hpp b/wpimath/src/main/native/include/wpi/math/geometry/proto/Pose2dProto.hpp index 1f832c77d6..e9d31e4a6a 100644 --- a/wpimath/src/main/native/include/wpi/math/geometry/proto/Pose2dProto.hpp +++ b/wpimath/src/main/native/include/wpi/math/geometry/proto/Pose2dProto.hpp @@ -11,10 +11,10 @@ #include "wpimath/protobuf/geometry2d.npb.h" template <> -struct WPILIB_DLLEXPORT wpi::Protobuf { +struct WPILIB_DLLEXPORT wpi::util::Protobuf { using MessageStruct = wpi_proto_ProtobufPose2d; - using InputStream = wpi::ProtoInputStream; - using OutputStream = wpi::ProtoOutputStream; - static std::optional Unpack(InputStream& stream); - static bool Pack(OutputStream& stream, const frc::Pose2d& value); + using InputStream = wpi::util::ProtoInputStream; + using OutputStream = wpi::util::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const wpi::math::Pose2d& value); }; diff --git a/wpimath/src/main/native/include/wpi/math/geometry/proto/Pose3dProto.hpp b/wpimath/src/main/native/include/wpi/math/geometry/proto/Pose3dProto.hpp index 46fdd17871..5714cbc731 100644 --- a/wpimath/src/main/native/include/wpi/math/geometry/proto/Pose3dProto.hpp +++ b/wpimath/src/main/native/include/wpi/math/geometry/proto/Pose3dProto.hpp @@ -10,10 +10,10 @@ #include "wpimath/protobuf/geometry3d.npb.h" template <> -struct WPILIB_DLLEXPORT wpi::Protobuf { +struct WPILIB_DLLEXPORT wpi::util::Protobuf { using MessageStruct = wpi_proto_ProtobufPose3d; - using InputStream = wpi::ProtoInputStream; - using OutputStream = wpi::ProtoOutputStream; - static std::optional Unpack(InputStream& stream); - static bool Pack(OutputStream& stream, const frc::Pose3d& value); + using InputStream = wpi::util::ProtoInputStream; + using OutputStream = wpi::util::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const wpi::math::Pose3d& value); }; diff --git a/wpimath/src/main/native/include/wpi/math/geometry/proto/QuaternionProto.hpp b/wpimath/src/main/native/include/wpi/math/geometry/proto/QuaternionProto.hpp index a9cb881d2e..1540d03765 100644 --- a/wpimath/src/main/native/include/wpi/math/geometry/proto/QuaternionProto.hpp +++ b/wpimath/src/main/native/include/wpi/math/geometry/proto/QuaternionProto.hpp @@ -10,10 +10,10 @@ #include "wpimath/protobuf/geometry3d.npb.h" template <> -struct WPILIB_DLLEXPORT wpi::Protobuf { +struct WPILIB_DLLEXPORT wpi::util::Protobuf { using MessageStruct = wpi_proto_ProtobufQuaternion; - using InputStream = wpi::ProtoInputStream; - using OutputStream = wpi::ProtoOutputStream; - static std::optional Unpack(InputStream& stream); - static bool Pack(OutputStream& stream, const frc::Quaternion& value); + using InputStream = wpi::util::ProtoInputStream; + using OutputStream = wpi::util::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const wpi::math::Quaternion& value); }; diff --git a/wpimath/src/main/native/include/wpi/math/geometry/proto/Rectangle2dProto.hpp b/wpimath/src/main/native/include/wpi/math/geometry/proto/Rectangle2dProto.hpp index 319b445a5b..b3b25b1a64 100644 --- a/wpimath/src/main/native/include/wpi/math/geometry/proto/Rectangle2dProto.hpp +++ b/wpimath/src/main/native/include/wpi/math/geometry/proto/Rectangle2dProto.hpp @@ -10,10 +10,10 @@ #include "wpimath/protobuf/geometry2d.npb.h" template <> -struct WPILIB_DLLEXPORT wpi::Protobuf { +struct WPILIB_DLLEXPORT wpi::util::Protobuf { using MessageStruct = wpi_proto_ProtobufRectangle2d; - using InputStream = wpi::ProtoInputStream; - using OutputStream = wpi::ProtoOutputStream; - static std::optional Unpack(InputStream& stream); - static bool Pack(OutputStream& stream, const frc::Rectangle2d& value); + using InputStream = wpi::util::ProtoInputStream; + using OutputStream = wpi::util::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const wpi::math::Rectangle2d& value); }; diff --git a/wpimath/src/main/native/include/wpi/math/geometry/proto/Rotation2dProto.hpp b/wpimath/src/main/native/include/wpi/math/geometry/proto/Rotation2dProto.hpp index 91493fcff4..27cb428d3c 100644 --- a/wpimath/src/main/native/include/wpi/math/geometry/proto/Rotation2dProto.hpp +++ b/wpimath/src/main/native/include/wpi/math/geometry/proto/Rotation2dProto.hpp @@ -11,10 +11,10 @@ #include "wpimath/protobuf/geometry2d.npb.h" template <> -struct WPILIB_DLLEXPORT wpi::Protobuf { +struct WPILIB_DLLEXPORT wpi::util::Protobuf { using MessageStruct = wpi_proto_ProtobufRotation2d; - using InputStream = wpi::ProtoInputStream; - using OutputStream = wpi::ProtoOutputStream; - static std::optional Unpack(InputStream& stream); - static bool Pack(OutputStream& stream, const frc::Rotation2d& value); + using InputStream = wpi::util::ProtoInputStream; + using OutputStream = wpi::util::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const wpi::math::Rotation2d& value); }; diff --git a/wpimath/src/main/native/include/wpi/math/geometry/proto/Rotation3dProto.hpp b/wpimath/src/main/native/include/wpi/math/geometry/proto/Rotation3dProto.hpp index 96ff0dfabe..c5f67fb123 100644 --- a/wpimath/src/main/native/include/wpi/math/geometry/proto/Rotation3dProto.hpp +++ b/wpimath/src/main/native/include/wpi/math/geometry/proto/Rotation3dProto.hpp @@ -10,10 +10,10 @@ #include "wpimath/protobuf/geometry3d.npb.h" template <> -struct WPILIB_DLLEXPORT wpi::Protobuf { +struct WPILIB_DLLEXPORT wpi::util::Protobuf { using MessageStruct = wpi_proto_ProtobufRotation3d; - using InputStream = wpi::ProtoInputStream; - using OutputStream = wpi::ProtoOutputStream; - static std::optional Unpack(InputStream& stream); - static bool Pack(OutputStream& stream, const frc::Rotation3d& value); + using InputStream = wpi::util::ProtoInputStream; + using OutputStream = wpi::util::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const wpi::math::Rotation3d& value); }; diff --git a/wpimath/src/main/native/include/wpi/math/geometry/proto/Transform2dProto.hpp b/wpimath/src/main/native/include/wpi/math/geometry/proto/Transform2dProto.hpp index 5c0d5a46a8..47fc5f3888 100644 --- a/wpimath/src/main/native/include/wpi/math/geometry/proto/Transform2dProto.hpp +++ b/wpimath/src/main/native/include/wpi/math/geometry/proto/Transform2dProto.hpp @@ -10,10 +10,10 @@ #include "wpimath/protobuf/geometry2d.npb.h" template <> -struct WPILIB_DLLEXPORT wpi::Protobuf { +struct WPILIB_DLLEXPORT wpi::util::Protobuf { using MessageStruct = wpi_proto_ProtobufTransform2d; - using InputStream = wpi::ProtoInputStream; - using OutputStream = wpi::ProtoOutputStream; - static std::optional Unpack(InputStream& stream); - static bool Pack(OutputStream& stream, const frc::Transform2d& value); + using InputStream = wpi::util::ProtoInputStream; + using OutputStream = wpi::util::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const wpi::math::Transform2d& value); }; diff --git a/wpimath/src/main/native/include/wpi/math/geometry/proto/Transform3dProto.hpp b/wpimath/src/main/native/include/wpi/math/geometry/proto/Transform3dProto.hpp index 9be0d7c8a2..044fe8a5f6 100644 --- a/wpimath/src/main/native/include/wpi/math/geometry/proto/Transform3dProto.hpp +++ b/wpimath/src/main/native/include/wpi/math/geometry/proto/Transform3dProto.hpp @@ -10,10 +10,10 @@ #include "wpimath/protobuf/geometry3d.npb.h" template <> -struct WPILIB_DLLEXPORT wpi::Protobuf { +struct WPILIB_DLLEXPORT wpi::util::Protobuf { using MessageStruct = wpi_proto_ProtobufTransform3d; - using InputStream = wpi::ProtoInputStream; - using OutputStream = wpi::ProtoOutputStream; - static std::optional Unpack(InputStream& stream); - static bool Pack(OutputStream& stream, const frc::Transform3d& value); + using InputStream = wpi::util::ProtoInputStream; + using OutputStream = wpi::util::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const wpi::math::Transform3d& value); }; diff --git a/wpimath/src/main/native/include/wpi/math/geometry/proto/Translation2dProto.hpp b/wpimath/src/main/native/include/wpi/math/geometry/proto/Translation2dProto.hpp index 010f4f25e9..d75009e16a 100644 --- a/wpimath/src/main/native/include/wpi/math/geometry/proto/Translation2dProto.hpp +++ b/wpimath/src/main/native/include/wpi/math/geometry/proto/Translation2dProto.hpp @@ -11,10 +11,10 @@ #include "wpimath/protobuf/geometry2d.npb.h" template <> -struct WPILIB_DLLEXPORT wpi::Protobuf { +struct WPILIB_DLLEXPORT wpi::util::Protobuf { using MessageStruct = wpi_proto_ProtobufTranslation2d; - using InputStream = wpi::ProtoInputStream; - using OutputStream = wpi::ProtoOutputStream; - static std::optional Unpack(InputStream& stream); - static bool Pack(OutputStream& stream, const frc::Translation2d& value); + using InputStream = wpi::util::ProtoInputStream; + using OutputStream = wpi::util::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const wpi::math::Translation2d& value); }; diff --git a/wpimath/src/main/native/include/wpi/math/geometry/proto/Translation3dProto.hpp b/wpimath/src/main/native/include/wpi/math/geometry/proto/Translation3dProto.hpp index 38af2c7841..ae3b19ba8f 100644 --- a/wpimath/src/main/native/include/wpi/math/geometry/proto/Translation3dProto.hpp +++ b/wpimath/src/main/native/include/wpi/math/geometry/proto/Translation3dProto.hpp @@ -10,10 +10,10 @@ #include "wpimath/protobuf/geometry3d.npb.h" template <> -struct WPILIB_DLLEXPORT wpi::Protobuf { +struct WPILIB_DLLEXPORT wpi::util::Protobuf { using MessageStruct = wpi_proto_ProtobufTranslation3d; - using InputStream = wpi::ProtoInputStream; - using OutputStream = wpi::ProtoOutputStream; - static std::optional Unpack(InputStream& stream); - static bool Pack(OutputStream& stream, const frc::Translation3d& value); + using InputStream = wpi::util::ProtoInputStream; + using OutputStream = wpi::util::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const wpi::math::Translation3d& value); }; diff --git a/wpimath/src/main/native/include/wpi/math/geometry/proto/Twist2dProto.hpp b/wpimath/src/main/native/include/wpi/math/geometry/proto/Twist2dProto.hpp index 7ae0a2985c..854f38357f 100644 --- a/wpimath/src/main/native/include/wpi/math/geometry/proto/Twist2dProto.hpp +++ b/wpimath/src/main/native/include/wpi/math/geometry/proto/Twist2dProto.hpp @@ -10,10 +10,10 @@ #include "wpimath/protobuf/geometry2d.npb.h" template <> -struct WPILIB_DLLEXPORT wpi::Protobuf { +struct WPILIB_DLLEXPORT wpi::util::Protobuf { using MessageStruct = wpi_proto_ProtobufTwist2d; - using InputStream = wpi::ProtoInputStream; - using OutputStream = wpi::ProtoOutputStream; - static std::optional Unpack(InputStream& stream); - static bool Pack(OutputStream& stream, const frc::Twist2d& value); + using InputStream = wpi::util::ProtoInputStream; + using OutputStream = wpi::util::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const wpi::math::Twist2d& value); }; diff --git a/wpimath/src/main/native/include/wpi/math/geometry/proto/Twist3dProto.hpp b/wpimath/src/main/native/include/wpi/math/geometry/proto/Twist3dProto.hpp index 768f135d0a..ffe22f583e 100644 --- a/wpimath/src/main/native/include/wpi/math/geometry/proto/Twist3dProto.hpp +++ b/wpimath/src/main/native/include/wpi/math/geometry/proto/Twist3dProto.hpp @@ -10,10 +10,10 @@ #include "wpimath/protobuf/geometry3d.npb.h" template <> -struct WPILIB_DLLEXPORT wpi::Protobuf { +struct WPILIB_DLLEXPORT wpi::util::Protobuf { using MessageStruct = wpi_proto_ProtobufTwist3d; - using InputStream = wpi::ProtoInputStream; - using OutputStream = wpi::ProtoOutputStream; - static std::optional Unpack(InputStream& stream); - static bool Pack(OutputStream& stream, const frc::Twist3d& value); + using InputStream = wpi::util::ProtoInputStream; + using OutputStream = wpi::util::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const wpi::math::Twist3d& value); }; diff --git a/wpimath/src/main/native/include/wpi/math/geometry/struct/Ellipse2dStruct.hpp b/wpimath/src/main/native/include/wpi/math/geometry/struct/Ellipse2dStruct.hpp index 9ddc2809e8..f6b0d9401b 100644 --- a/wpimath/src/main/native/include/wpi/math/geometry/struct/Ellipse2dStruct.hpp +++ b/wpimath/src/main/native/include/wpi/math/geometry/struct/Ellipse2dStruct.hpp @@ -9,22 +9,22 @@ #include "wpi/util/struct/Struct.hpp" template <> -struct WPILIB_DLLEXPORT wpi::Struct { +struct WPILIB_DLLEXPORT wpi::util::Struct { static constexpr std::string_view GetTypeName() { return "Ellipse2d"; } static constexpr size_t GetSize() { - return wpi::GetStructSize() + 16; + return wpi::util::GetStructSize() + 16; } static constexpr std::string_view GetSchema() { return "Pose2d center;double xSemiAxis;double ySemiAxis"; } - static frc::Ellipse2d Unpack(std::span data); - static void Pack(std::span data, const frc::Ellipse2d& value); + static wpi::math::Ellipse2d Unpack(std::span data); + static void Pack(std::span data, const wpi::math::Ellipse2d& value); static void ForEachNested( std::invocable auto fn) { - wpi::ForEachStructSchema(fn); + wpi::util::ForEachStructSchema(fn); } }; -static_assert(wpi::StructSerializable); -static_assert(wpi::HasNestedStruct); +static_assert(wpi::util::StructSerializable); +static_assert(wpi::util::HasNestedStruct); diff --git a/wpimath/src/main/native/include/wpi/math/geometry/struct/Pose2dStruct.hpp b/wpimath/src/main/native/include/wpi/math/geometry/struct/Pose2dStruct.hpp index de4bfc79da..29be60d82b 100644 --- a/wpimath/src/main/native/include/wpi/math/geometry/struct/Pose2dStruct.hpp +++ b/wpimath/src/main/native/include/wpi/math/geometry/struct/Pose2dStruct.hpp @@ -9,24 +9,24 @@ #include "wpi/util/struct/Struct.hpp" template <> -struct WPILIB_DLLEXPORT wpi::Struct { +struct WPILIB_DLLEXPORT wpi::util::Struct { static constexpr std::string_view GetTypeName() { return "Pose2d"; } static constexpr size_t GetSize() { - return wpi::GetStructSize() + - wpi::GetStructSize(); + return wpi::util::GetStructSize() + + wpi::util::GetStructSize(); } static constexpr std::string_view GetSchema() { return "Translation2d translation;Rotation2d rotation"; } - static frc::Pose2d Unpack(std::span data); - static void Pack(std::span data, const frc::Pose2d& value); + static wpi::math::Pose2d Unpack(std::span data); + static void Pack(std::span data, const wpi::math::Pose2d& value); static void ForEachNested( std::invocable auto fn) { - wpi::ForEachStructSchema(fn); - wpi::ForEachStructSchema(fn); + wpi::util::ForEachStructSchema(fn); + wpi::util::ForEachStructSchema(fn); } }; -static_assert(wpi::StructSerializable); -static_assert(wpi::HasNestedStruct); +static_assert(wpi::util::StructSerializable); +static_assert(wpi::util::HasNestedStruct); diff --git a/wpimath/src/main/native/include/wpi/math/geometry/struct/Pose3dStruct.hpp b/wpimath/src/main/native/include/wpi/math/geometry/struct/Pose3dStruct.hpp index bca905129f..5459a9784a 100644 --- a/wpimath/src/main/native/include/wpi/math/geometry/struct/Pose3dStruct.hpp +++ b/wpimath/src/main/native/include/wpi/math/geometry/struct/Pose3dStruct.hpp @@ -9,24 +9,24 @@ #include "wpi/util/struct/Struct.hpp" template <> -struct WPILIB_DLLEXPORT wpi::Struct { +struct WPILIB_DLLEXPORT wpi::util::Struct { static constexpr std::string_view GetTypeName() { return "Pose3d"; } static constexpr size_t GetSize() { - return wpi::GetStructSize() + - wpi::GetStructSize(); + return wpi::util::GetStructSize() + + wpi::util::GetStructSize(); } static constexpr std::string_view GetSchema() { return "Translation3d translation;Rotation3d rotation"; } - static frc::Pose3d Unpack(std::span data); - static void Pack(std::span data, const frc::Pose3d& value); + static wpi::math::Pose3d Unpack(std::span data); + static void Pack(std::span data, const wpi::math::Pose3d& value); static void ForEachNested( std::invocable auto fn) { - wpi::ForEachStructSchema(fn); - wpi::ForEachStructSchema(fn); + wpi::util::ForEachStructSchema(fn); + wpi::util::ForEachStructSchema(fn); } }; -static_assert(wpi::StructSerializable); -static_assert(wpi::HasNestedStruct); +static_assert(wpi::util::StructSerializable); +static_assert(wpi::util::HasNestedStruct); diff --git a/wpimath/src/main/native/include/wpi/math/geometry/struct/QuaternionStruct.hpp b/wpimath/src/main/native/include/wpi/math/geometry/struct/QuaternionStruct.hpp index bb73c93578..6432e30db5 100644 --- a/wpimath/src/main/native/include/wpi/math/geometry/struct/QuaternionStruct.hpp +++ b/wpimath/src/main/native/include/wpi/math/geometry/struct/QuaternionStruct.hpp @@ -9,15 +9,15 @@ #include "wpi/util/struct/Struct.hpp" template <> -struct WPILIB_DLLEXPORT wpi::Struct { +struct WPILIB_DLLEXPORT wpi::util::Struct { static constexpr std::string_view GetTypeName() { return "Quaternion"; } static constexpr size_t GetSize() { return 32; } static constexpr std::string_view GetSchema() { return "double w;double x;double y;double z"; } - static frc::Quaternion Unpack(std::span data); - static void Pack(std::span data, const frc::Quaternion& value); + static wpi::math::Quaternion Unpack(std::span data); + static void Pack(std::span data, const wpi::math::Quaternion& value); }; -static_assert(wpi::StructSerializable); +static_assert(wpi::util::StructSerializable); diff --git a/wpimath/src/main/native/include/wpi/math/geometry/struct/Rectangle2dStruct.hpp b/wpimath/src/main/native/include/wpi/math/geometry/struct/Rectangle2dStruct.hpp index 4ac58c0b1a..b0d2cbf56f 100644 --- a/wpimath/src/main/native/include/wpi/math/geometry/struct/Rectangle2dStruct.hpp +++ b/wpimath/src/main/native/include/wpi/math/geometry/struct/Rectangle2dStruct.hpp @@ -9,22 +9,22 @@ #include "wpi/util/struct/Struct.hpp" template <> -struct WPILIB_DLLEXPORT wpi::Struct { +struct WPILIB_DLLEXPORT wpi::util::Struct { static constexpr std::string_view GetTypeName() { return "Rectangle2d"; } static constexpr size_t GetSize() { - return wpi::GetStructSize() + 16; + return wpi::util::GetStructSize() + 16; } static constexpr std::string_view GetSchema() { return "Pose2d center;double xWidth;double yWidth"; } - static frc::Rectangle2d Unpack(std::span data); - static void Pack(std::span data, const frc::Rectangle2d& value); + static wpi::math::Rectangle2d Unpack(std::span data); + static void Pack(std::span data, const wpi::math::Rectangle2d& value); static void ForEachNested( std::invocable auto fn) { - wpi::ForEachStructSchema(fn); + wpi::util::ForEachStructSchema(fn); } }; -static_assert(wpi::StructSerializable); -static_assert(wpi::HasNestedStruct); +static_assert(wpi::util::StructSerializable); +static_assert(wpi::util::HasNestedStruct); diff --git a/wpimath/src/main/native/include/wpi/math/geometry/struct/Rotation2dStruct.hpp b/wpimath/src/main/native/include/wpi/math/geometry/struct/Rotation2dStruct.hpp index b7915e89e9..32e23dd3c7 100644 --- a/wpimath/src/main/native/include/wpi/math/geometry/struct/Rotation2dStruct.hpp +++ b/wpimath/src/main/native/include/wpi/math/geometry/struct/Rotation2dStruct.hpp @@ -9,13 +9,13 @@ #include "wpi/util/struct/Struct.hpp" template <> -struct WPILIB_DLLEXPORT wpi::Struct { +struct WPILIB_DLLEXPORT wpi::util::Struct { static constexpr std::string_view GetTypeName() { return "Rotation2d"; } static constexpr size_t GetSize() { return 8; } static constexpr std::string_view GetSchema() { return "double value"; } - static frc::Rotation2d Unpack(std::span data); - static void Pack(std::span data, const frc::Rotation2d& value); + static wpi::math::Rotation2d Unpack(std::span data); + static void Pack(std::span data, const wpi::math::Rotation2d& value); }; -static_assert(wpi::StructSerializable); +static_assert(wpi::util::StructSerializable); diff --git a/wpimath/src/main/native/include/wpi/math/geometry/struct/Rotation3dStruct.hpp b/wpimath/src/main/native/include/wpi/math/geometry/struct/Rotation3dStruct.hpp index 6b768dee9a..2f0d94a6fe 100644 --- a/wpimath/src/main/native/include/wpi/math/geometry/struct/Rotation3dStruct.hpp +++ b/wpimath/src/main/native/include/wpi/math/geometry/struct/Rotation3dStruct.hpp @@ -9,20 +9,20 @@ #include "wpi/util/struct/Struct.hpp" template <> -struct WPILIB_DLLEXPORT wpi::Struct { +struct WPILIB_DLLEXPORT wpi::util::Struct { static constexpr std::string_view GetTypeName() { return "Rotation3d"; } static constexpr size_t GetSize() { - return wpi::GetStructSize(); + return wpi::util::GetStructSize(); } static constexpr std::string_view GetSchema() { return "Quaternion q"; } - static frc::Rotation3d Unpack(std::span data); - static void Pack(std::span data, const frc::Rotation3d& value); + static wpi::math::Rotation3d Unpack(std::span data); + static void Pack(std::span data, const wpi::math::Rotation3d& value); static void ForEachNested( std::invocable auto fn) { - wpi::ForEachStructSchema(fn); + wpi::util::ForEachStructSchema(fn); } }; -static_assert(wpi::StructSerializable); -static_assert(wpi::HasNestedStruct); +static_assert(wpi::util::StructSerializable); +static_assert(wpi::util::HasNestedStruct); diff --git a/wpimath/src/main/native/include/wpi/math/geometry/struct/Transform2dStruct.hpp b/wpimath/src/main/native/include/wpi/math/geometry/struct/Transform2dStruct.hpp index 607426ebe0..37d2137fbc 100644 --- a/wpimath/src/main/native/include/wpi/math/geometry/struct/Transform2dStruct.hpp +++ b/wpimath/src/main/native/include/wpi/math/geometry/struct/Transform2dStruct.hpp @@ -9,24 +9,24 @@ #include "wpi/util/struct/Struct.hpp" template <> -struct WPILIB_DLLEXPORT wpi::Struct { +struct WPILIB_DLLEXPORT wpi::util::Struct { static constexpr std::string_view GetTypeName() { return "Transform2d"; } static constexpr size_t GetSize() { - return wpi::GetStructSize() + - wpi::GetStructSize(); + return wpi::util::GetStructSize() + + wpi::util::GetStructSize(); } static constexpr std::string_view GetSchema() { return "Translation2d translation;Rotation2d rotation"; } - static frc::Transform2d Unpack(std::span data); - static void Pack(std::span data, const frc::Transform2d& value); + static wpi::math::Transform2d Unpack(std::span data); + static void Pack(std::span data, const wpi::math::Transform2d& value); static void ForEachNested( std::invocable auto fn) { - wpi::ForEachStructSchema(fn); - wpi::ForEachStructSchema(fn); + wpi::util::ForEachStructSchema(fn); + wpi::util::ForEachStructSchema(fn); } }; -static_assert(wpi::StructSerializable); -static_assert(wpi::HasNestedStruct); +static_assert(wpi::util::StructSerializable); +static_assert(wpi::util::HasNestedStruct); diff --git a/wpimath/src/main/native/include/wpi/math/geometry/struct/Transform3dStruct.hpp b/wpimath/src/main/native/include/wpi/math/geometry/struct/Transform3dStruct.hpp index c1afec39b5..36042cb1e4 100644 --- a/wpimath/src/main/native/include/wpi/math/geometry/struct/Transform3dStruct.hpp +++ b/wpimath/src/main/native/include/wpi/math/geometry/struct/Transform3dStruct.hpp @@ -9,24 +9,24 @@ #include "wpi/util/struct/Struct.hpp" template <> -struct WPILIB_DLLEXPORT wpi::Struct { +struct WPILIB_DLLEXPORT wpi::util::Struct { static constexpr std::string_view GetTypeName() { return "Transform3d"; } static constexpr size_t GetSize() { - return wpi::GetStructSize() + - wpi::GetStructSize(); + return wpi::util::GetStructSize() + + wpi::util::GetStructSize(); } static constexpr std::string_view GetSchema() { return "Translation3d translation;Rotation3d rotation"; } - static frc::Transform3d Unpack(std::span data); - static void Pack(std::span data, const frc::Transform3d& value); + static wpi::math::Transform3d Unpack(std::span data); + static void Pack(std::span data, const wpi::math::Transform3d& value); static void ForEachNested( std::invocable auto fn) { - wpi::ForEachStructSchema(fn); - wpi::ForEachStructSchema(fn); + wpi::util::ForEachStructSchema(fn); + wpi::util::ForEachStructSchema(fn); } }; -static_assert(wpi::StructSerializable); -static_assert(wpi::HasNestedStruct); +static_assert(wpi::util::StructSerializable); +static_assert(wpi::util::HasNestedStruct); diff --git a/wpimath/src/main/native/include/wpi/math/geometry/struct/Translation2dStruct.hpp b/wpimath/src/main/native/include/wpi/math/geometry/struct/Translation2dStruct.hpp index 191c0b268d..48d4b3029b 100644 --- a/wpimath/src/main/native/include/wpi/math/geometry/struct/Translation2dStruct.hpp +++ b/wpimath/src/main/native/include/wpi/math/geometry/struct/Translation2dStruct.hpp @@ -9,13 +9,13 @@ #include "wpi/util/struct/Struct.hpp" template <> -struct WPILIB_DLLEXPORT wpi::Struct { +struct WPILIB_DLLEXPORT wpi::util::Struct { static constexpr std::string_view GetTypeName() { return "Translation2d"; } static constexpr size_t GetSize() { return 16; } static constexpr std::string_view GetSchema() { return "double x;double y"; } - static frc::Translation2d Unpack(std::span data); - static void Pack(std::span data, const frc::Translation2d& value); + static wpi::math::Translation2d Unpack(std::span data); + static void Pack(std::span data, const wpi::math::Translation2d& value); }; -static_assert(wpi::StructSerializable); +static_assert(wpi::util::StructSerializable); diff --git a/wpimath/src/main/native/include/wpi/math/geometry/struct/Translation3dStruct.hpp b/wpimath/src/main/native/include/wpi/math/geometry/struct/Translation3dStruct.hpp index 5a4315df3c..3088182e2c 100644 --- a/wpimath/src/main/native/include/wpi/math/geometry/struct/Translation3dStruct.hpp +++ b/wpimath/src/main/native/include/wpi/math/geometry/struct/Translation3dStruct.hpp @@ -9,15 +9,15 @@ #include "wpi/util/struct/Struct.hpp" template <> -struct WPILIB_DLLEXPORT wpi::Struct { +struct WPILIB_DLLEXPORT wpi::util::Struct { static constexpr std::string_view GetTypeName() { return "Translation3d"; } static constexpr size_t GetSize() { return 24; } static constexpr std::string_view GetSchema() { return "double x;double y;double z"; } - static frc::Translation3d Unpack(std::span data); - static void Pack(std::span data, const frc::Translation3d& value); + static wpi::math::Translation3d Unpack(std::span data); + static void Pack(std::span data, const wpi::math::Translation3d& value); }; -static_assert(wpi::StructSerializable); +static_assert(wpi::util::StructSerializable); diff --git a/wpimath/src/main/native/include/wpi/math/geometry/struct/Twist2dStruct.hpp b/wpimath/src/main/native/include/wpi/math/geometry/struct/Twist2dStruct.hpp index 6b5396f067..2cb5784bc1 100644 --- a/wpimath/src/main/native/include/wpi/math/geometry/struct/Twist2dStruct.hpp +++ b/wpimath/src/main/native/include/wpi/math/geometry/struct/Twist2dStruct.hpp @@ -9,15 +9,15 @@ #include "wpi/util/struct/Struct.hpp" template <> -struct WPILIB_DLLEXPORT wpi::Struct { +struct WPILIB_DLLEXPORT wpi::util::Struct { static constexpr std::string_view GetTypeName() { return "Twist2d"; } static constexpr size_t GetSize() { return 24; } static constexpr std::string_view GetSchema() { return "double dx;double dy;double dtheta"; } - static frc::Twist2d Unpack(std::span data); - static void Pack(std::span data, const frc::Twist2d& value); + static wpi::math::Twist2d Unpack(std::span data); + static void Pack(std::span data, const wpi::math::Twist2d& value); }; -static_assert(wpi::StructSerializable); +static_assert(wpi::util::StructSerializable); diff --git a/wpimath/src/main/native/include/wpi/math/geometry/struct/Twist3dStruct.hpp b/wpimath/src/main/native/include/wpi/math/geometry/struct/Twist3dStruct.hpp index e2607162b4..ce38a60328 100644 --- a/wpimath/src/main/native/include/wpi/math/geometry/struct/Twist3dStruct.hpp +++ b/wpimath/src/main/native/include/wpi/math/geometry/struct/Twist3dStruct.hpp @@ -9,15 +9,15 @@ #include "wpi/util/struct/Struct.hpp" template <> -struct WPILIB_DLLEXPORT wpi::Struct { +struct WPILIB_DLLEXPORT wpi::util::Struct { static constexpr std::string_view GetTypeName() { return "Twist3d"; } static constexpr size_t GetSize() { return 48; } static constexpr std::string_view GetSchema() { return "double dx;double dy;double dz;double rx;double ry;double rz"; } - static frc::Twist3d Unpack(std::span data); - static void Pack(std::span data, const frc::Twist3d& value); + static wpi::math::Twist3d Unpack(std::span data); + static void Pack(std::span data, const wpi::math::Twist3d& value); }; -static_assert(wpi::StructSerializable); +static_assert(wpi::util::StructSerializable); diff --git a/wpimath/src/main/native/include/wpi/math/interpolation/TimeInterpolatableBuffer.hpp b/wpimath/src/main/native/include/wpi/math/interpolation/TimeInterpolatableBuffer.hpp index d7de0020b9..4716a3461e 100644 --- a/wpimath/src/main/native/include/wpi/math/interpolation/TimeInterpolatableBuffer.hpp +++ b/wpimath/src/main/native/include/wpi/math/interpolation/TimeInterpolatableBuffer.hpp @@ -15,7 +15,7 @@ #include "wpi/util/MathExtras.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::math { /** * The TimeInterpolatableBuffer provides an easy way to estimate past @@ -24,7 +24,7 @@ namespace frc { * when vision or other global measurement were recorded is necessary, or for * recording the past angles of mechanisms as measured by encoders. * - * When sampling this buffer, a user-provided function or wpi::Lerp can be + * When sampling this buffer, a user-provided function or wpi::util::Lerp can be * used. For Pose2ds, we use Twists. * * @tparam T The type stored in this buffer. @@ -38,20 +38,20 @@ class TimeInterpolatableBuffer { * @param historySize The history size of the buffer. * @param func The function used to interpolate between values. */ - TimeInterpolatableBuffer(units::second_t historySize, + TimeInterpolatableBuffer(wpi::units::second_t historySize, std::function func) : m_historySize(historySize), m_interpolatingFunc(func) {} /** * Create a new TimeInterpolatableBuffer. By default, the interpolation - * function is wpi::Lerp except for Pose2d, which uses the pose exponential. + * function is wpi::util::Lerp except for Pose2d, which uses the pose exponential. * * @param historySize The history size of the buffer. */ - explicit TimeInterpolatableBuffer(units::second_t historySize) + explicit TimeInterpolatableBuffer(wpi::units::second_t historySize) : m_historySize(historySize), m_interpolatingFunc([](const T& start, const T& end, double t) { - return wpi::Lerp(start, end, t); + return wpi::util::Lerp(start, end, t); }) {} /** @@ -60,7 +60,7 @@ class TimeInterpolatableBuffer { * @param time The timestamp of the sample. * @param sample The sample object. */ - void AddSample(units::second_t time, T sample) { + void AddSample(wpi::units::second_t time, T sample) { // Add the new state into the vector if (m_pastSnapshots.size() == 0 || time > m_pastSnapshots.back().first) { m_pastSnapshots.emplace_back(time, sample); @@ -97,7 +97,7 @@ class TimeInterpolatableBuffer { * * @param time The time at which to sample the buffer. */ - std::optional Sample(units::second_t time) const { + std::optional Sample(wpi::units::second_t time) const { if (m_pastSnapshots.empty()) { return {}; } @@ -137,27 +137,27 @@ class TimeInterpolatableBuffer { * Grant access to the internal sample buffer. Used in Pose Estimation to * replay odometry inputs stored within this buffer. */ - std::vector>& GetInternalBuffer() { + std::vector>& GetInternalBuffer() { return m_pastSnapshots; } /** * Grant access to the internal sample buffer. */ - const std::vector>& GetInternalBuffer() const { + const std::vector>& GetInternalBuffer() const { return m_pastSnapshots; } private: - units::second_t m_historySize; - std::vector> m_pastSnapshots; + wpi::units::second_t m_historySize; + std::vector> m_pastSnapshots; std::function m_interpolatingFunc; }; // Template specialization to ensure that Pose2d uses pose exponential template <> inline TimeInterpolatableBuffer::TimeInterpolatableBuffer( - units::second_t historySize) + wpi::units::second_t historySize) : m_historySize(historySize), m_interpolatingFunc([](const Pose2d& start, const Pose2d& end, double t) { if (t < 0) { @@ -171,4 +171,4 @@ inline TimeInterpolatableBuffer::TimeInterpolatableBuffer( } }) {} -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/kinematics/ChassisSpeeds.hpp b/wpimath/src/main/native/include/wpi/math/kinematics/ChassisSpeeds.hpp index 45bad721b0..05044ea8ee 100644 --- a/wpimath/src/main/native/include/wpi/math/kinematics/ChassisSpeeds.hpp +++ b/wpimath/src/main/native/include/wpi/math/kinematics/ChassisSpeeds.hpp @@ -10,7 +10,7 @@ #include "wpi/units/velocity.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::math { /** * Represents the speed of a robot chassis. Although this struct contains * similar members compared to a Twist2d, they do NOT represent the same thing. @@ -25,17 +25,17 @@ struct WPILIB_DLLEXPORT ChassisSpeeds { /** * Velocity along the x-axis. (Fwd is +) */ - units::meters_per_second_t vx = 0_mps; + wpi::units::meters_per_second_t vx = 0_mps; /** * Velocity along the y-axis. (Left is +) */ - units::meters_per_second_t vy = 0_mps; + wpi::units::meters_per_second_t vy = 0_mps; /** * Represents the angular velocity of the robot frame. (CCW is +) */ - units::radians_per_second_t omega = 0_rad_per_s; + wpi::units::radians_per_second_t omega = 0_rad_per_s; /** * Creates a Twist2d from ChassisSpeeds. @@ -44,7 +44,7 @@ struct WPILIB_DLLEXPORT ChassisSpeeds { * * @return Twist2d. */ - constexpr Twist2d ToTwist2d(units::second_t dt) const { + constexpr Twist2d ToTwist2d(wpi::units::second_t dt) const { return Twist2d{vx * dt, vy * dt, omega * dt}; } @@ -67,7 +67,7 @@ struct WPILIB_DLLEXPORT ChassisSpeeds { * @param dt The duration of the timestep the speeds should be applied for. * @return Discretized ChassisSpeeds. */ - constexpr ChassisSpeeds Discretize(units::second_t dt) const { + constexpr ChassisSpeeds Discretize(wpi::units::second_t dt) const { // Construct the desired pose after a timestep, relative to the current // pose. The desired pose has decoupled translation and rotation. Transform2d desiredTransform{vx * dt, vy * dt, omega * dt}; @@ -94,10 +94,10 @@ struct WPILIB_DLLEXPORT ChassisSpeeds { constexpr ChassisSpeeds ToRobotRelative(const Rotation2d& robotAngle) const { // CW rotation into chassis frame auto rotated = - Translation2d{units::meter_t{vx.value()}, units::meter_t{vy.value()}} + Translation2d{wpi::units::meter_t{vx.value()}, wpi::units::meter_t{vy.value()}} .RotateBy(-robotAngle); - return {units::meters_per_second_t{rotated.X().value()}, - units::meters_per_second_t{rotated.Y().value()}, omega}; + return {wpi::units::meters_per_second_t{rotated.X().value()}, + wpi::units::meters_per_second_t{rotated.Y().value()}, omega}; } /** @@ -114,10 +114,10 @@ struct WPILIB_DLLEXPORT ChassisSpeeds { constexpr ChassisSpeeds ToFieldRelative(const Rotation2d& robotAngle) const { // CCW rotation out of chassis frame auto rotated = - Translation2d{units::meter_t{vx.value()}, units::meter_t{vy.value()}} + Translation2d{wpi::units::meter_t{vx.value()}, wpi::units::meter_t{vy.value()}} .RotateBy(robotAngle); - return {units::meters_per_second_t{rotated.X().value()}, - units::meters_per_second_t{rotated.Y().value()}, omega}; + return {wpi::units::meters_per_second_t{rotated.X().value()}, + wpi::units::meters_per_second_t{rotated.Y().value()}, omega}; } /** @@ -194,7 +194,7 @@ struct WPILIB_DLLEXPORT ChassisSpeeds { */ constexpr bool operator==(const ChassisSpeeds& other) const = default; }; -} // namespace frc +} // namespace wpi::math #include "wpi/math/kinematics/proto/ChassisSpeedsProto.hpp" #include "wpi/math/kinematics/struct/ChassisSpeedsStruct.hpp" diff --git a/wpimath/src/main/native/include/wpi/math/kinematics/DifferentialDriveKinematics.hpp b/wpimath/src/main/native/include/wpi/math/kinematics/DifferentialDriveKinematics.hpp index 1c8af561ac..9a296cdc76 100644 --- a/wpimath/src/main/native/include/wpi/math/kinematics/DifferentialDriveKinematics.hpp +++ b/wpimath/src/main/native/include/wpi/math/kinematics/DifferentialDriveKinematics.hpp @@ -16,7 +16,7 @@ #include "wpi/units/length.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::math { /** * Helper class that converts a chassis velocity (dx and dtheta components) to * left and right wheel velocities for a differential drive. @@ -37,7 +37,7 @@ class WPILIB_DLLEXPORT DifferentialDriveKinematics * empirical value may be larger than the physical measured value due to * scrubbing effects. */ - constexpr explicit DifferentialDriveKinematics(units::meter_t trackwidth) + constexpr explicit DifferentialDriveKinematics(wpi::units::meter_t trackwidth) : trackwidth(trackwidth) { if (!std::is_constant_evaluated()) { wpi::math::MathSharedStore::ReportUsage("DifferentialDriveKinematics", @@ -80,8 +80,8 @@ class WPILIB_DLLEXPORT DifferentialDriveKinematics * @param rightDistance The distance measured by the right encoder. * @return The resulting Twist2d. */ - constexpr Twist2d ToTwist2d(const units::meter_t leftDistance, - const units::meter_t rightDistance) const { + constexpr Twist2d ToTwist2d(const wpi::units::meter_t leftDistance, + const wpi::units::meter_t rightDistance) const { return {(leftDistance + rightDistance) / 2, 0_m, (rightDistance - leftDistance) / trackwidth * 1_rad}; } @@ -99,9 +99,9 @@ class WPILIB_DLLEXPORT DifferentialDriveKinematics } /// Differential drive trackwidth. - units::meter_t trackwidth; + wpi::units::meter_t trackwidth; }; -} // namespace frc +} // namespace wpi::math #include "wpi/math/kinematics/proto/DifferentialDriveKinematicsProto.hpp" #include "wpi/math/kinematics/struct/DifferentialDriveKinematicsStruct.hpp" diff --git a/wpimath/src/main/native/include/wpi/math/kinematics/DifferentialDriveOdometry.hpp b/wpimath/src/main/native/include/wpi/math/kinematics/DifferentialDriveOdometry.hpp index b608551f85..94f695a477 100644 --- a/wpimath/src/main/native/include/wpi/math/kinematics/DifferentialDriveOdometry.hpp +++ b/wpimath/src/main/native/include/wpi/math/kinematics/DifferentialDriveOdometry.hpp @@ -12,7 +12,7 @@ #include "wpi/units/length.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::math { /** * Class for differential drive odometry. Odometry allows you to track the * robot's position on the field over the course of a match using readings from @@ -41,8 +41,8 @@ class WPILIB_DLLEXPORT DifferentialDriveOdometry * @param initialPose The starting position of the robot on the field. */ explicit DifferentialDriveOdometry(const Rotation2d& gyroAngle, - units::meter_t leftDistance, - units::meter_t rightDistance, + wpi::units::meter_t leftDistance, + wpi::units::meter_t rightDistance, const Pose2d& initialPose = Pose2d{}); /** @@ -59,8 +59,8 @@ class WPILIB_DLLEXPORT DifferentialDriveOdometry * @param leftDistance The distance traveled by the left encoder. * @param rightDistance The distance traveled by the right encoder. */ - void ResetPosition(const Rotation2d& gyroAngle, units::meter_t leftDistance, - units::meter_t rightDistance, const Pose2d& pose) { + void ResetPosition(const Rotation2d& gyroAngle, wpi::units::meter_t leftDistance, + wpi::units::meter_t rightDistance, const Pose2d& pose) { Odometry::ResetPosition(gyroAngle, {leftDistance, rightDistance}, pose); } @@ -75,12 +75,12 @@ class WPILIB_DLLEXPORT DifferentialDriveOdometry * @param rightDistance The distance traveled by the right encoder. * @return The new pose of the robot. */ - const Pose2d& Update(const Rotation2d& gyroAngle, units::meter_t leftDistance, - units::meter_t rightDistance) { + const Pose2d& Update(const Rotation2d& gyroAngle, wpi::units::meter_t leftDistance, + wpi::units::meter_t rightDistance) { return Odometry::Update(gyroAngle, {leftDistance, rightDistance}); } private: - DifferentialDriveKinematics m_kinematicsImpl{units::meter_t{1}}; + DifferentialDriveKinematics m_kinematicsImpl{wpi::units::meter_t{1}}; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/kinematics/DifferentialDriveOdometry3d.hpp b/wpimath/src/main/native/include/wpi/math/kinematics/DifferentialDriveOdometry3d.hpp index f1d3d5cf0f..70c1f7a5d0 100644 --- a/wpimath/src/main/native/include/wpi/math/kinematics/DifferentialDriveOdometry3d.hpp +++ b/wpimath/src/main/native/include/wpi/math/kinematics/DifferentialDriveOdometry3d.hpp @@ -12,7 +12,7 @@ #include "wpi/units/length.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::math { /** * Class for differential drive odometry. Odometry allows you to track the * robot's position on the field over the course of a match using readings from @@ -41,8 +41,8 @@ class WPILIB_DLLEXPORT DifferentialDriveOdometry3d * @param initialPose The starting position of the robot on the field. */ explicit DifferentialDriveOdometry3d(const Rotation3d& gyroAngle, - units::meter_t leftDistance, - units::meter_t rightDistance, + wpi::units::meter_t leftDistance, + wpi::units::meter_t rightDistance, const Pose3d& initialPose = Pose3d{}); /** @@ -59,8 +59,8 @@ class WPILIB_DLLEXPORT DifferentialDriveOdometry3d * @param leftDistance The distance traveled by the left encoder. * @param rightDistance The distance traveled by the right encoder. */ - void ResetPosition(const Rotation3d& gyroAngle, units::meter_t leftDistance, - units::meter_t rightDistance, const Pose3d& pose) { + void ResetPosition(const Rotation3d& gyroAngle, wpi::units::meter_t leftDistance, + wpi::units::meter_t rightDistance, const Pose3d& pose) { Odometry3d::ResetPosition(gyroAngle, {leftDistance, rightDistance}, pose); } @@ -75,12 +75,12 @@ class WPILIB_DLLEXPORT DifferentialDriveOdometry3d * @param rightDistance The distance traveled by the right encoder. * @return The new pose of the robot. */ - const Pose3d& Update(const Rotation3d& gyroAngle, units::meter_t leftDistance, - units::meter_t rightDistance) { + const Pose3d& Update(const Rotation3d& gyroAngle, wpi::units::meter_t leftDistance, + wpi::units::meter_t rightDistance) { return Odometry3d::Update(gyroAngle, {leftDistance, rightDistance}); } private: - DifferentialDriveKinematics m_kinematicsImpl{units::meter_t{1}}; + DifferentialDriveKinematics m_kinematicsImpl{wpi::units::meter_t{1}}; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/kinematics/DifferentialDriveWheelPositions.hpp b/wpimath/src/main/native/include/wpi/math/kinematics/DifferentialDriveWheelPositions.hpp index 45fd579985..e5c9e9a643 100644 --- a/wpimath/src/main/native/include/wpi/math/kinematics/DifferentialDriveWheelPositions.hpp +++ b/wpimath/src/main/native/include/wpi/math/kinematics/DifferentialDriveWheelPositions.hpp @@ -8,7 +8,7 @@ #include "wpi/util/MathExtras.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::math { /** * Represents the wheel positions for a differential drive drivetrain. */ @@ -16,12 +16,12 @@ struct WPILIB_DLLEXPORT DifferentialDriveWheelPositions { /** * Distance driven by the left side. */ - units::meter_t left = 0_m; + wpi::units::meter_t left = 0_m; /** * Distance driven by the right side. */ - units::meter_t right = 0_m; + wpi::units::meter_t right = 0_m; /** * Checks equality between this DifferentialDriveWheelPositions and another @@ -35,11 +35,11 @@ struct WPILIB_DLLEXPORT DifferentialDriveWheelPositions { constexpr DifferentialDriveWheelPositions Interpolate( const DifferentialDriveWheelPositions& endValue, double t) const { - return {wpi::Lerp(left, endValue.left, t), - wpi::Lerp(right, endValue.right, t)}; + return {wpi::util::Lerp(left, endValue.left, t), + wpi::util::Lerp(right, endValue.right, t)}; } }; -} // namespace frc +} // namespace wpi::math #include "wpi/math/kinematics/proto/DifferentialDriveWheelPositionsProto.hpp" #include "wpi/math/kinematics/struct/DifferentialDriveWheelPositionsStruct.hpp" diff --git a/wpimath/src/main/native/include/wpi/math/kinematics/DifferentialDriveWheelSpeeds.hpp b/wpimath/src/main/native/include/wpi/math/kinematics/DifferentialDriveWheelSpeeds.hpp index 3c89bc4114..7bd8c340c7 100644 --- a/wpimath/src/main/native/include/wpi/math/kinematics/DifferentialDriveWheelSpeeds.hpp +++ b/wpimath/src/main/native/include/wpi/math/kinematics/DifferentialDriveWheelSpeeds.hpp @@ -8,7 +8,7 @@ #include "wpi/units/velocity.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::math { /** * Represents the wheel speeds for a differential drive drivetrain. */ @@ -16,12 +16,12 @@ struct WPILIB_DLLEXPORT DifferentialDriveWheelSpeeds { /** * Speed of the left side of the robot. */ - units::meters_per_second_t left = 0_mps; + wpi::units::meters_per_second_t left = 0_mps; /** * Speed of the right side of the robot. */ - units::meters_per_second_t right = 0_mps; + wpi::units::meters_per_second_t right = 0_mps; /** * Renormalizes the wheel speeds if either side is above the specified @@ -35,9 +35,9 @@ struct WPILIB_DLLEXPORT DifferentialDriveWheelSpeeds { * * @param attainableMaxSpeed The absolute max speed that a wheel can reach. */ - constexpr void Desaturate(units::meters_per_second_t attainableMaxSpeed) { + constexpr void Desaturate(wpi::units::meters_per_second_t attainableMaxSpeed) { auto realMaxSpeed = - units::math::max(units::math::abs(left), units::math::abs(right)); + wpi::units::math::max(wpi::units::math::abs(left), wpi::units::math::abs(right)); if (realMaxSpeed > attainableMaxSpeed) { left = left / realMaxSpeed * attainableMaxSpeed; @@ -119,7 +119,7 @@ struct WPILIB_DLLEXPORT DifferentialDriveWheelSpeeds { return operator*(1.0 / scalar); } }; -} // namespace frc +} // namespace wpi::math #include "wpi/math/kinematics/proto/DifferentialDriveWheelSpeedsProto.hpp" #include "wpi/math/kinematics/struct/DifferentialDriveWheelSpeedsStruct.hpp" diff --git a/wpimath/src/main/native/include/wpi/math/kinematics/Kinematics.hpp b/wpimath/src/main/native/include/wpi/math/kinematics/Kinematics.hpp index a5f514de9b..091fcbd909 100644 --- a/wpimath/src/main/native/include/wpi/math/kinematics/Kinematics.hpp +++ b/wpimath/src/main/native/include/wpi/math/kinematics/Kinematics.hpp @@ -8,7 +8,7 @@ #include "wpi/math/kinematics/ChassisSpeeds.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::math { /** * Helper class that converts a chassis velocity (dx, dy, and dtheta components) * into individual wheel speeds. Robot code should not use this directly- @@ -75,4 +75,4 @@ class WPILIB_DLLEXPORT Kinematics { const WheelPositions& end, double t) const = 0; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/kinematics/MecanumDriveKinematics.hpp b/wpimath/src/main/native/include/wpi/math/kinematics/MecanumDriveKinematics.hpp index f4f2e7157a..d33ef1b11a 100644 --- a/wpimath/src/main/native/include/wpi/math/kinematics/MecanumDriveKinematics.hpp +++ b/wpimath/src/main/native/include/wpi/math/kinematics/MecanumDriveKinematics.hpp @@ -16,7 +16,7 @@ #include "wpi/math/util/MathShared.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::math { /** * Helper class that converts a chassis velocity (dx, dy, and dtheta components) @@ -197,7 +197,7 @@ class WPILIB_DLLEXPORT MecanumDriveKinematics Translation2d rl, Translation2d rr) const; }; -} // namespace frc +} // namespace wpi::math #include "wpi/math/kinematics/proto/MecanumDriveKinematicsProto.hpp" #include "wpi/math/kinematics/struct/MecanumDriveKinematicsStruct.hpp" diff --git a/wpimath/src/main/native/include/wpi/math/kinematics/MecanumDriveOdometry.hpp b/wpimath/src/main/native/include/wpi/math/kinematics/MecanumDriveOdometry.hpp index 8d01bbbdc6..8d12779e9b 100644 --- a/wpimath/src/main/native/include/wpi/math/kinematics/MecanumDriveOdometry.hpp +++ b/wpimath/src/main/native/include/wpi/math/kinematics/MecanumDriveOdometry.hpp @@ -13,7 +13,7 @@ #include "wpi/util/SymbolExports.hpp" #include "wpi/util/timestamp.h" -namespace frc { +namespace wpi::math { /** * Class for mecanum drive odometry. Odometry allows you to track the robot's @@ -44,4 +44,4 @@ class WPILIB_DLLEXPORT MecanumDriveOdometry MecanumDriveKinematics m_kinematicsImpl; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/kinematics/MecanumDriveOdometry3d.hpp b/wpimath/src/main/native/include/wpi/math/kinematics/MecanumDriveOdometry3d.hpp index d20cf5fc1e..fb2f9c6401 100644 --- a/wpimath/src/main/native/include/wpi/math/kinematics/MecanumDriveOdometry3d.hpp +++ b/wpimath/src/main/native/include/wpi/math/kinematics/MecanumDriveOdometry3d.hpp @@ -13,7 +13,7 @@ #include "wpi/util/SymbolExports.hpp" #include "wpi/util/timestamp.h" -namespace frc { +namespace wpi::math { /** * Class for mecanum drive odometry. Odometry allows you to track the robot's @@ -44,4 +44,4 @@ class WPILIB_DLLEXPORT MecanumDriveOdometry3d MecanumDriveKinematics m_kinematicsImpl; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/kinematics/MecanumDriveWheelPositions.hpp b/wpimath/src/main/native/include/wpi/math/kinematics/MecanumDriveWheelPositions.hpp index 9fd0aa4e29..2cf7c025e2 100644 --- a/wpimath/src/main/native/include/wpi/math/kinematics/MecanumDriveWheelPositions.hpp +++ b/wpimath/src/main/native/include/wpi/math/kinematics/MecanumDriveWheelPositions.hpp @@ -8,7 +8,7 @@ #include "wpi/util/MathExtras.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::math { /** * Represents the wheel positions for a mecanum drive drivetrain. */ @@ -16,22 +16,22 @@ struct WPILIB_DLLEXPORT MecanumDriveWheelPositions { /** * Distance driven by the front-left wheel. */ - units::meter_t frontLeft = 0_m; + wpi::units::meter_t frontLeft = 0_m; /** * Distance driven by the front-right wheel. */ - units::meter_t frontRight = 0_m; + wpi::units::meter_t frontRight = 0_m; /** * Distance driven by the rear-left wheel. */ - units::meter_t rearLeft = 0_m; + wpi::units::meter_t rearLeft = 0_m; /** * Distance driven by the rear-right wheel. */ - units::meter_t rearRight = 0_m; + wpi::units::meter_t rearRight = 0_m; /** * Checks equality between this MecanumDriveWheelPositions and another object. @@ -44,13 +44,13 @@ struct WPILIB_DLLEXPORT MecanumDriveWheelPositions { constexpr MecanumDriveWheelPositions Interpolate( const MecanumDriveWheelPositions& endValue, double t) const { - return {wpi::Lerp(frontLeft, endValue.frontLeft, t), - wpi::Lerp(frontRight, endValue.frontRight, t), - wpi::Lerp(rearLeft, endValue.rearLeft, t), - wpi::Lerp(rearRight, endValue.rearRight, t)}; + return {wpi::util::Lerp(frontLeft, endValue.frontLeft, t), + wpi::util::Lerp(frontRight, endValue.frontRight, t), + wpi::util::Lerp(rearLeft, endValue.rearLeft, t), + wpi::util::Lerp(rearRight, endValue.rearRight, t)}; } }; -} // namespace frc +} // namespace wpi::math #include "wpi/math/kinematics/proto/MecanumDriveWheelPositionsProto.hpp" #include "wpi/math/kinematics/struct/MecanumDriveWheelPositionsStruct.hpp" diff --git a/wpimath/src/main/native/include/wpi/math/kinematics/MecanumDriveWheelSpeeds.hpp b/wpimath/src/main/native/include/wpi/math/kinematics/MecanumDriveWheelSpeeds.hpp index ab908cf68a..bba0bb559d 100644 --- a/wpimath/src/main/native/include/wpi/math/kinematics/MecanumDriveWheelSpeeds.hpp +++ b/wpimath/src/main/native/include/wpi/math/kinematics/MecanumDriveWheelSpeeds.hpp @@ -12,7 +12,7 @@ #include "wpi/units/velocity.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::math { /** * Represents the wheel speeds for a mecanum drive drivetrain. */ @@ -20,22 +20,22 @@ struct WPILIB_DLLEXPORT MecanumDriveWheelSpeeds { /** * Speed of the front-left wheel. */ - units::meters_per_second_t frontLeft = 0_mps; + wpi::units::meters_per_second_t frontLeft = 0_mps; /** * Speed of the front-right wheel. */ - units::meters_per_second_t frontRight = 0_mps; + wpi::units::meters_per_second_t frontRight = 0_mps; /** * Speed of the rear-left wheel. */ - units::meters_per_second_t rearLeft = 0_mps; + wpi::units::meters_per_second_t rearLeft = 0_mps; /** * Speed of the rear-right wheel. */ - units::meters_per_second_t rearRight = 0_mps; + wpi::units::meters_per_second_t rearRight = 0_mps; /** * Renormalizes the wheel speeds if any individual speed is above the @@ -51,13 +51,13 @@ struct WPILIB_DLLEXPORT MecanumDriveWheelSpeeds { * @return Desaturated MecanumDriveWheelSpeeds. */ constexpr MecanumDriveWheelSpeeds Desaturate( - units::meters_per_second_t attainableMaxSpeed) const { - std::array wheelSpeeds{frontLeft, frontRight, + wpi::units::meters_per_second_t attainableMaxSpeed) const { + std::array wheelSpeeds{frontLeft, frontRight, rearLeft, rearRight}; - units::meters_per_second_t realMaxSpeed = units::math::abs( + wpi::units::meters_per_second_t realMaxSpeed = wpi::units::math::abs( *std::max_element(wheelSpeeds.begin(), wheelSpeeds.end(), [](const auto& a, const auto& b) { - return units::math::abs(a) < units::math::abs(b); + return wpi::units::math::abs(a) < wpi::units::math::abs(b); })); if (realMaxSpeed > attainableMaxSpeed) { @@ -143,7 +143,7 @@ struct WPILIB_DLLEXPORT MecanumDriveWheelSpeeds { return operator*(1.0 / scalar); } }; -} // namespace frc +} // namespace wpi::math #include "wpi/math/kinematics/proto/MecanumDriveWheelSpeedsProto.hpp" #include "wpi/math/kinematics/struct/MecanumDriveWheelSpeedsStruct.hpp" diff --git a/wpimath/src/main/native/include/wpi/math/kinematics/Odometry.hpp b/wpimath/src/main/native/include/wpi/math/kinematics/Odometry.hpp index 7093df2d21..f053587eba 100644 --- a/wpimath/src/main/native/include/wpi/math/kinematics/Odometry.hpp +++ b/wpimath/src/main/native/include/wpi/math/kinematics/Odometry.hpp @@ -10,7 +10,7 @@ #include "wpi/math/kinematics/Kinematics.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::math { /** * Class for odometry. Robot code should not use this directly- Instead, use the @@ -139,4 +139,4 @@ class WPILIB_DLLEXPORT Odometry { Rotation2d m_gyroOffset; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/kinematics/Odometry3d.hpp b/wpimath/src/main/native/include/wpi/math/kinematics/Odometry3d.hpp index c6b1b447f5..8450632b4c 100644 --- a/wpimath/src/main/native/include/wpi/math/kinematics/Odometry3d.hpp +++ b/wpimath/src/main/native/include/wpi/math/kinematics/Odometry3d.hpp @@ -13,7 +13,7 @@ #include "wpi/math/kinematics/Kinematics.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::math { /** * Class for odometry. Robot code should not use this directly- Instead, use the @@ -126,9 +126,9 @@ class WPILIB_DLLEXPORT Odometry3d { Twist3d twist{twist2d.dx, twist2d.dy, 0_m, - units::radian_t{angle_difference(0)}, - units::radian_t{angle_difference(1)}, - units::radian_t{angle_difference(2)}}; + wpi::units::radian_t{angle_difference(0)}, + wpi::units::radian_t{angle_difference(1)}, + wpi::units::radian_t{angle_difference(2)}}; auto newPose = m_pose + twist.Exp(); @@ -148,4 +148,4 @@ class WPILIB_DLLEXPORT Odometry3d { Rotation3d m_gyroOffset; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/kinematics/SwerveDriveKinematics.hpp b/wpimath/src/main/native/include/wpi/math/kinematics/SwerveDriveKinematics.hpp index a675cc7adc..34de11995c 100644 --- a/wpimath/src/main/native/include/wpi/math/kinematics/SwerveDriveKinematics.hpp +++ b/wpimath/src/main/native/include/wpi/math/kinematics/SwerveDriveKinematics.hpp @@ -24,7 +24,7 @@ #include "wpi/util/SymbolExports.hpp" #include "wpi/util/array.hpp" -namespace frc { +namespace wpi::math { /** * Helper class that converts a chassis velocity (dx, dy, and dtheta components) @@ -50,8 +50,8 @@ namespace frc { */ template class SwerveDriveKinematics - : public Kinematics, - wpi::array> { + : public Kinematics, + wpi::util::array> { public: /** * Constructs a swerve drive kinematics object. This takes in a variable @@ -67,7 +67,7 @@ class SwerveDriveKinematics template ... ModuleTranslations> requires(sizeof...(ModuleTranslations) == NumModules) explicit SwerveDriveKinematics(ModuleTranslations&&... moduleTranslations) - : m_modules{moduleTranslations...}, m_moduleHeadings(wpi::empty_array) { + : m_modules{moduleTranslations...}, m_moduleHeadings(wpi::util::empty_array) { for (size_t i = 0; i < NumModules; i++) { // clang-format off m_inverseKinematics.template block<2, 3>(i * 2, 0) << @@ -82,8 +82,8 @@ class SwerveDriveKinematics } explicit SwerveDriveKinematics( - const wpi::array& modules) - : m_modules{modules}, m_moduleHeadings(wpi::empty_array) { + const wpi::util::array& modules) + : m_modules{modules}, m_moduleHeadings(wpi::util::empty_array) { for (size_t i = 0; i < NumModules; i++) { // clang-format off m_inverseKinematics.template block<2, 3>(i * 2, 0) << @@ -108,7 +108,7 @@ class SwerveDriveKinematics requires(sizeof...(ModuleHeadings) == NumModules) void ResetHeadings(ModuleHeadings&&... moduleHeadings) { return this->ResetHeadings( - wpi::array{moduleHeadings...}); + wpi::util::array{moduleHeadings...}); } /** @@ -116,7 +116,7 @@ class SwerveDriveKinematics * @param moduleHeadings The swerve module headings. The order of the module * headings should be same as passed into the constructor of this class. */ - void ResetHeadings(wpi::array moduleHeadings) { + void ResetHeadings(wpi::util::array moduleHeadings) { for (size_t i = 0; i < NumModules; i++) { m_moduleHeadings[i] = moduleHeadings[i]; } @@ -144,8 +144,8 @@ class SwerveDriveKinematics * @return An array containing the module states. Use caution because these * module states are not normalized. Sometimes, a user input may cause one of * the module speeds to go above the attainable max velocity. Use the - * DesaturateWheelSpeeds(wpi::array*, - * units::meters_per_second_t) function to rectify this issue. In addition, + * DesaturateWheelSpeeds(wpi::util::array*, + * wpi::units::meters_per_second_t) function to rectify this issue. In addition, * you can leverage the power of C++17 to directly assign the module states to * variables: * @@ -153,10 +153,10 @@ class SwerveDriveKinematics * auto [fl, fr, bl, br] = kinematics.ToSwerveModuleStates(chassisSpeeds); * @endcode */ - wpi::array ToSwerveModuleStates( + wpi::util::array ToSwerveModuleStates( const ChassisSpeeds& chassisSpeeds, const Translation2d& centerOfRotation = Translation2d{}) const { - wpi::array moduleStates(wpi::empty_array); + wpi::util::array moduleStates(wpi::util::empty_array); if (chassisSpeeds.vx == 0_mps && chassisSpeeds.vy == 0_mps && chassisSpeeds.omega == 0_rad_per_s) { @@ -188,10 +188,10 @@ class SwerveDriveKinematics m_inverseKinematics * chassisSpeedsVector; for (size_t i = 0; i < NumModules; i++) { - units::meters_per_second_t x{moduleStateMatrix(i * 2, 0)}; - units::meters_per_second_t y{moduleStateMatrix(i * 2 + 1, 0)}; + wpi::units::meters_per_second_t x{moduleStateMatrix(i * 2, 0)}; + wpi::units::meters_per_second_t y{moduleStateMatrix(i * 2 + 1, 0)}; - auto speed = units::math::hypot(x, y); + auto speed = wpi::units::math::hypot(x, y); auto rotation = speed > 1e-6_mps ? Rotation2d{x.value(), y.value()} : m_moduleHeadings[i]; @@ -202,7 +202,7 @@ class SwerveDriveKinematics return moduleStates; } - wpi::array ToWheelSpeeds( + wpi::util::array ToWheelSpeeds( const ChassisSpeeds& chassisSpeeds) const override { return ToSwerveModuleStates(chassisSpeeds); } @@ -223,7 +223,7 @@ class SwerveDriveKinematics requires(sizeof...(ModuleStates) == NumModules) ChassisSpeeds ToChassisSpeeds(ModuleStates&&... moduleStates) const { return this->ToChassisSpeeds( - wpi::array{moduleStates...}); + wpi::util::array{moduleStates...}); } /** @@ -232,14 +232,14 @@ class SwerveDriveKinematics * the robot's position on the field using data from the real-world speed and * angle of each module on the robot. * - * @param moduleStates The state of the modules as an wpi::array of type + * @param moduleStates The state of the modules as an wpi::util::array of type * SwerveModuleState, NumModules long as measured from respective encoders * and gyros. The order of the swerve module states should be same as passed * into the constructor of this class. * * @return The resulting chassis speed. */ - ChassisSpeeds ToChassisSpeeds(const wpi::array& + ChassisSpeeds ToChassisSpeeds(const wpi::util::array& moduleStates) const override { Matrixd moduleStateMatrix; @@ -253,9 +253,9 @@ class SwerveDriveKinematics Eigen::Vector3d chassisSpeedsVector = m_forwardKinematics.solve(moduleStateMatrix); - return {units::meters_per_second_t{chassisSpeedsVector(0)}, - units::meters_per_second_t{chassisSpeedsVector(1)}, - units::radians_per_second_t{chassisSpeedsVector(2)}}; + return {wpi::units::meters_per_second_t{chassisSpeedsVector(0)}, + wpi::units::meters_per_second_t{chassisSpeedsVector(1)}, + wpi::units::radians_per_second_t{chassisSpeedsVector(2)}}; } /** @@ -275,7 +275,7 @@ class SwerveDriveKinematics requires(sizeof...(ModuleDeltas) == NumModules) Twist2d ToTwist2d(ModuleDeltas&&... moduleDeltas) const { return this->ToTwist2d( - wpi::array{moduleDeltas...}); + wpi::util::array{moduleDeltas...}); } /** @@ -292,7 +292,7 @@ class SwerveDriveKinematics * @return The resulting Twist2d. */ Twist2d ToTwist2d( - wpi::array moduleDeltas) const { + wpi::util::array moduleDeltas) const { Matrixd moduleDeltaMatrix; for (size_t i = 0; i < NumModules; ++i) { @@ -306,16 +306,16 @@ class SwerveDriveKinematics Eigen::Vector3d chassisDeltaVector = m_forwardKinematics.solve(moduleDeltaMatrix); - return {units::meter_t{chassisDeltaVector(0)}, - units::meter_t{chassisDeltaVector(1)}, - units::radian_t{chassisDeltaVector(2)}}; + return {wpi::units::meter_t{chassisDeltaVector(0)}, + wpi::units::meter_t{chassisDeltaVector(1)}, + wpi::units::radian_t{chassisDeltaVector(2)}}; } Twist2d ToTwist2d( - const wpi::array& start, - const wpi::array& end) const override { + const wpi::util::array& start, + const wpi::util::array& end) const override { auto result = - wpi::array(wpi::empty_array); + wpi::util::array(wpi::util::empty_array); for (size_t i = 0; i < NumModules; i++) { result[i] = {end[i].distance - start[i].distance, end[i].angle}; } @@ -343,14 +343,14 @@ class SwerveDriveKinematics * @param attainableMaxSpeed The absolute max speed that a module can reach. */ static void DesaturateWheelSpeeds( - wpi::array* moduleStates, - units::meters_per_second_t attainableMaxSpeed) { + wpi::util::array* moduleStates, + wpi::units::meters_per_second_t attainableMaxSpeed) { auto& states = *moduleStates; auto realMaxSpeed = - units::math::abs(std::max_element(states.begin(), states.end(), + wpi::units::math::abs(std::max_element(states.begin(), states.end(), [](const auto& a, const auto& b) { - return units::math::abs(a.speed) < - units::math::abs(b.speed); + return wpi::units::math::abs(a.speed) < + wpi::units::math::abs(b.speed); }) ->speed); @@ -388,18 +388,18 @@ class SwerveDriveKinematics * reach while rotating */ static void DesaturateWheelSpeeds( - wpi::array* moduleStates, + wpi::util::array* moduleStates, ChassisSpeeds desiredChassisSpeed, - units::meters_per_second_t attainableMaxModuleSpeed, - units::meters_per_second_t attainableMaxRobotTranslationSpeed, - units::radians_per_second_t attainableMaxRobotRotationSpeed) { + wpi::units::meters_per_second_t attainableMaxModuleSpeed, + wpi::units::meters_per_second_t attainableMaxRobotTranslationSpeed, + wpi::units::radians_per_second_t attainableMaxRobotRotationSpeed) { auto& states = *moduleStates; auto realMaxSpeed = - units::math::abs(std::max_element(states.begin(), states.end(), + wpi::units::math::abs(std::max_element(states.begin(), states.end(), [](const auto& a, const auto& b) { - return units::math::abs(a.speed) < - units::math::abs(b.speed); + return wpi::units::math::abs(a.speed) < + wpi::units::math::abs(b.speed); }) ->speed); @@ -410,42 +410,42 @@ class SwerveDriveKinematics } auto translationalK = - units::math::hypot(desiredChassisSpeed.vx, desiredChassisSpeed.vy) / + wpi::units::math::hypot(desiredChassisSpeed.vx, desiredChassisSpeed.vy) / attainableMaxRobotTranslationSpeed; - auto rotationalK = units::math::abs(desiredChassisSpeed.omega) / + auto rotationalK = wpi::units::math::abs(desiredChassisSpeed.omega) / attainableMaxRobotRotationSpeed; - auto k = units::math::max(translationalK, rotationalK); + auto k = wpi::units::math::max(translationalK, rotationalK); - auto scale = units::math::min(k * attainableMaxModuleSpeed / realMaxSpeed, - units::scalar_t{1}); + auto scale = wpi::units::math::min(k * attainableMaxModuleSpeed / realMaxSpeed, + wpi::units::scalar_t{1}); for (auto& module : states) { module.speed = module.speed * scale; } } - wpi::array Interpolate( - const wpi::array& start, - const wpi::array& end, + wpi::util::array Interpolate( + const wpi::util::array& start, + const wpi::util::array& end, double t) const override { auto result = - wpi::array(wpi::empty_array); + wpi::util::array(wpi::util::empty_array); for (size_t i = 0; i < NumModules; ++i) { result[i] = start[i].Interpolate(end[i], t); } return {result}; } - const wpi::array& GetModules() const { + const wpi::util::array& GetModules() const { return m_modules; } private: - wpi::array m_modules; + wpi::util::array m_modules; mutable Matrixd m_inverseKinematics; Eigen::HouseholderQR> m_forwardKinematics; - mutable wpi::array m_moduleHeadings; + mutable wpi::util::array m_moduleHeadings; mutable Translation2d m_previousCoR; }; @@ -457,4 +457,4 @@ SwerveDriveKinematics(ModuleTranslation, ModuleTranslations...) extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT) SwerveDriveKinematics<4>; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/kinematics/SwerveDriveOdometry.hpp b/wpimath/src/main/native/include/wpi/math/kinematics/SwerveDriveOdometry.hpp index 3f0dd423d8..dff4b672de 100644 --- a/wpimath/src/main/native/include/wpi/math/kinematics/SwerveDriveOdometry.hpp +++ b/wpimath/src/main/native/include/wpi/math/kinematics/SwerveDriveOdometry.hpp @@ -16,7 +16,7 @@ #include "wpi/util/SymbolExports.hpp" #include "wpi/util/timestamp.h" -namespace frc { +namespace wpi::math { /** * Class for swerve drive odometry. Odometry allows you to track the robot's @@ -29,8 +29,8 @@ namespace frc { */ template class SwerveDriveOdometry - : public Odometry, - wpi::array> { + : public Odometry, + wpi::util::array> { public: /** * Constructs a SwerveDriveOdometry object. @@ -42,7 +42,7 @@ class SwerveDriveOdometry */ SwerveDriveOdometry( SwerveDriveKinematics kinematics, const Rotation2d& gyroAngle, - const wpi::array& modulePositions, + const wpi::util::array& modulePositions, const Pose2d& initialPose = Pose2d{}) : SwerveDriveOdometry::Odometry(m_kinematicsImpl, gyroAngle, modulePositions, initialPose), @@ -57,4 +57,4 @@ class SwerveDriveOdometry extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT) SwerveDriveOdometry<4>; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/kinematics/SwerveDriveOdometry3d.hpp b/wpimath/src/main/native/include/wpi/math/kinematics/SwerveDriveOdometry3d.hpp index 4f26ddedd8..80b4ee078e 100644 --- a/wpimath/src/main/native/include/wpi/math/kinematics/SwerveDriveOdometry3d.hpp +++ b/wpimath/src/main/native/include/wpi/math/kinematics/SwerveDriveOdometry3d.hpp @@ -17,7 +17,7 @@ #include "wpi/util/SymbolExports.hpp" #include "wpi/util/timestamp.h" -namespace frc { +namespace wpi::math { /** * Class for swerve drive odometry. Odometry allows you to track the robot's @@ -30,8 +30,8 @@ namespace frc { */ template class SwerveDriveOdometry3d - : public Odometry3d, - wpi::array> { + : public Odometry3d, + wpi::util::array> { public: /** * Constructs a SwerveDriveOdometry3d object. @@ -47,7 +47,7 @@ class SwerveDriveOdometry3d #endif // defined(__GNUC__) && !defined(__clang__) SwerveDriveOdometry3d( SwerveDriveKinematics kinematics, const Rotation3d& gyroAngle, - const wpi::array& modulePositions, + const wpi::util::array& modulePositions, const Pose3d& initialPose = Pose3d{}) : SwerveDriveOdometry3d::Odometry3d(m_kinematicsImpl, gyroAngle, modulePositions, initialPose), @@ -65,4 +65,4 @@ class SwerveDriveOdometry3d extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT) SwerveDriveOdometry3d<4>; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/kinematics/SwerveModulePosition.hpp b/wpimath/src/main/native/include/wpi/math/kinematics/SwerveModulePosition.hpp index 6b29b60922..032fab1a51 100644 --- a/wpimath/src/main/native/include/wpi/math/kinematics/SwerveModulePosition.hpp +++ b/wpimath/src/main/native/include/wpi/math/kinematics/SwerveModulePosition.hpp @@ -10,7 +10,7 @@ #include "wpi/util/MathExtras.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::math { /** * Represents the position of one swerve module. */ @@ -18,7 +18,7 @@ struct WPILIB_DLLEXPORT SwerveModulePosition { /** * Distance the wheel of a module has traveled */ - units::meter_t distance = 0_m; + wpi::units::meter_t distance = 0_m; /** * Angle of the module. @@ -32,17 +32,17 @@ struct WPILIB_DLLEXPORT SwerveModulePosition { * @return Whether the two objects are equal. */ constexpr bool operator==(const SwerveModulePosition& other) const { - return units::math::abs(distance - other.distance) < 1E-9_m && + return wpi::units::math::abs(distance - other.distance) < 1E-9_m && angle == other.angle; } constexpr SwerveModulePosition Interpolate( const SwerveModulePosition& endValue, double t) const { - return {wpi::Lerp(distance, endValue.distance, t), - wpi::Lerp(angle, endValue.angle, t)}; + return {wpi::util::Lerp(distance, endValue.distance, t), + wpi::util::Lerp(angle, endValue.angle, t)}; } }; -} // namespace frc +} // namespace wpi::math #include "wpi/math/kinematics/proto/SwerveModulePositionProto.hpp" #include "wpi/math/kinematics/struct/SwerveModulePositionStruct.hpp" diff --git a/wpimath/src/main/native/include/wpi/math/kinematics/SwerveModuleState.hpp b/wpimath/src/main/native/include/wpi/math/kinematics/SwerveModuleState.hpp index ce02db2735..2cb68a6f13 100644 --- a/wpimath/src/main/native/include/wpi/math/kinematics/SwerveModuleState.hpp +++ b/wpimath/src/main/native/include/wpi/math/kinematics/SwerveModuleState.hpp @@ -10,7 +10,7 @@ #include "wpi/units/velocity.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::math { /** * Represents the state of one swerve module. */ @@ -18,7 +18,7 @@ struct WPILIB_DLLEXPORT SwerveModuleState { /** * Speed of the wheel of the module. */ - units::meters_per_second_t speed = 0_mps; + wpi::units::meters_per_second_t speed = 0_mps; /** * Angle of the module. @@ -32,7 +32,7 @@ struct WPILIB_DLLEXPORT SwerveModuleState { * @return Whether the two objects are equal. */ constexpr bool operator==(const SwerveModuleState& other) const { - return units::math::abs(speed - other.speed) < 1E-9_mps && + return wpi::units::math::abs(speed - other.speed) < 1E-9_mps && angle == other.angle; } @@ -46,7 +46,7 @@ struct WPILIB_DLLEXPORT SwerveModuleState { */ constexpr void Optimize(const Rotation2d& currentAngle) { auto delta = angle - currentAngle; - if (units::math::abs(delta.Degrees()) > 90_deg) { + if (wpi::units::math::abs(delta.Degrees()) > 90_deg) { speed *= -1; angle = angle + Rotation2d{180_deg}; } @@ -65,7 +65,7 @@ struct WPILIB_DLLEXPORT SwerveModuleState { constexpr static SwerveModuleState Optimize( const SwerveModuleState& desiredState, const Rotation2d& currentAngle) { auto delta = desiredState.angle - currentAngle; - if (units::math::abs(delta.Degrees()) > 90_deg) { + if (wpi::units::math::abs(delta.Degrees()) > 90_deg) { return {-desiredState.speed, desiredState.angle + Rotation2d{180_deg}}; } else { return {desiredState.speed, desiredState.angle}; @@ -83,7 +83,7 @@ struct WPILIB_DLLEXPORT SwerveModuleState { speed *= (angle - currentAngle).Cos(); } }; -} // namespace frc +} // namespace wpi::math #include "wpi/math/kinematics/proto/SwerveModuleStateProto.hpp" #include "wpi/math/kinematics/struct/SwerveModuleStateStruct.hpp" diff --git a/wpimath/src/main/native/include/wpi/math/kinematics/proto/ChassisSpeedsProto.hpp b/wpimath/src/main/native/include/wpi/math/kinematics/proto/ChassisSpeedsProto.hpp index b8c53907e4..0e50b1c8bb 100644 --- a/wpimath/src/main/native/include/wpi/math/kinematics/proto/ChassisSpeedsProto.hpp +++ b/wpimath/src/main/native/include/wpi/math/kinematics/proto/ChassisSpeedsProto.hpp @@ -10,10 +10,10 @@ #include "wpimath/protobuf/kinematics.npb.h" template <> -struct WPILIB_DLLEXPORT wpi::Protobuf { +struct WPILIB_DLLEXPORT wpi::util::Protobuf { using MessageStruct = wpi_proto_ProtobufChassisSpeeds; - using InputStream = wpi::ProtoInputStream; - using OutputStream = wpi::ProtoOutputStream; - static std::optional Unpack(InputStream& stream); - static bool Pack(OutputStream& stream, const frc::ChassisSpeeds& value); + using InputStream = wpi::util::ProtoInputStream; + using OutputStream = wpi::util::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const wpi::math::ChassisSpeeds& value); }; diff --git a/wpimath/src/main/native/include/wpi/math/kinematics/proto/DifferentialDriveKinematicsProto.hpp b/wpimath/src/main/native/include/wpi/math/kinematics/proto/DifferentialDriveKinematicsProto.hpp index 0dd48a504f..3972bf65ab 100644 --- a/wpimath/src/main/native/include/wpi/math/kinematics/proto/DifferentialDriveKinematicsProto.hpp +++ b/wpimath/src/main/native/include/wpi/math/kinematics/proto/DifferentialDriveKinematicsProto.hpp @@ -10,12 +10,12 @@ #include "wpimath/protobuf/kinematics.npb.h" template <> -struct WPILIB_DLLEXPORT wpi::Protobuf { +struct WPILIB_DLLEXPORT wpi::util::Protobuf { using MessageStruct = wpi_proto_ProtobufDifferentialDriveKinematics; - using InputStream = wpi::ProtoInputStream; - using OutputStream = wpi::ProtoOutputStream; - static std::optional Unpack( + using InputStream = wpi::util::ProtoInputStream; + using OutputStream = wpi::util::ProtoOutputStream; + static std::optional Unpack( InputStream& stream); static bool Pack(OutputStream& stream, - const frc::DifferentialDriveKinematics& value); + const wpi::math::DifferentialDriveKinematics& value); }; diff --git a/wpimath/src/main/native/include/wpi/math/kinematics/proto/DifferentialDriveWheelPositionsProto.hpp b/wpimath/src/main/native/include/wpi/math/kinematics/proto/DifferentialDriveWheelPositionsProto.hpp index 1cc4af0da4..d574c6a1d9 100644 --- a/wpimath/src/main/native/include/wpi/math/kinematics/proto/DifferentialDriveWheelPositionsProto.hpp +++ b/wpimath/src/main/native/include/wpi/math/kinematics/proto/DifferentialDriveWheelPositionsProto.hpp @@ -10,14 +10,14 @@ #include "wpimath/protobuf/kinematics.npb.h" template <> -struct WPILIB_DLLEXPORT wpi::Protobuf { +struct WPILIB_DLLEXPORT wpi::util::Protobuf { using MessageStruct = wpi_proto_ProtobufDifferentialDriveWheelPositions; using InputStream = - wpi::ProtoInputStream; + wpi::util::ProtoInputStream; using OutputStream = - wpi::ProtoOutputStream; - static std::optional Unpack( + wpi::util::ProtoOutputStream; + static std::optional Unpack( InputStream& stream); static bool Pack(OutputStream& stream, - const frc::DifferentialDriveWheelPositions& value); + const wpi::math::DifferentialDriveWheelPositions& value); }; diff --git a/wpimath/src/main/native/include/wpi/math/kinematics/proto/DifferentialDriveWheelSpeedsProto.hpp b/wpimath/src/main/native/include/wpi/math/kinematics/proto/DifferentialDriveWheelSpeedsProto.hpp index 3396a3abe2..782c2f628e 100644 --- a/wpimath/src/main/native/include/wpi/math/kinematics/proto/DifferentialDriveWheelSpeedsProto.hpp +++ b/wpimath/src/main/native/include/wpi/math/kinematics/proto/DifferentialDriveWheelSpeedsProto.hpp @@ -10,13 +10,13 @@ #include "wpimath/protobuf/kinematics.npb.h" template <> -struct WPILIB_DLLEXPORT wpi::Protobuf { +struct WPILIB_DLLEXPORT wpi::util::Protobuf { using MessageStruct = wpi_proto_ProtobufDifferentialDriveWheelSpeeds; - using InputStream = wpi::ProtoInputStream; + using InputStream = wpi::util::ProtoInputStream; using OutputStream = - wpi::ProtoOutputStream; - static std::optional Unpack( + wpi::util::ProtoOutputStream; + static std::optional Unpack( InputStream& stream); static bool Pack(OutputStream& stream, - const frc::DifferentialDriveWheelSpeeds& value); + const wpi::math::DifferentialDriveWheelSpeeds& value); }; diff --git a/wpimath/src/main/native/include/wpi/math/kinematics/proto/MecanumDriveKinematicsProto.hpp b/wpimath/src/main/native/include/wpi/math/kinematics/proto/MecanumDriveKinematicsProto.hpp index 33c6d550c5..9a5ad2da6e 100644 --- a/wpimath/src/main/native/include/wpi/math/kinematics/proto/MecanumDriveKinematicsProto.hpp +++ b/wpimath/src/main/native/include/wpi/math/kinematics/proto/MecanumDriveKinematicsProto.hpp @@ -10,11 +10,11 @@ #include "wpimath/protobuf/kinematics.npb.h" template <> -struct WPILIB_DLLEXPORT wpi::Protobuf { +struct WPILIB_DLLEXPORT wpi::util::Protobuf { using MessageStruct = wpi_proto_ProtobufMecanumDriveKinematics; - using InputStream = wpi::ProtoInputStream; - using OutputStream = wpi::ProtoOutputStream; - static std::optional Unpack(InputStream& stream); + using InputStream = wpi::util::ProtoInputStream; + using OutputStream = wpi::util::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); static bool Pack(OutputStream& stream, - const frc::MecanumDriveKinematics& value); + const wpi::math::MecanumDriveKinematics& value); }; diff --git a/wpimath/src/main/native/include/wpi/math/kinematics/proto/MecanumDriveWheelPositionsProto.hpp b/wpimath/src/main/native/include/wpi/math/kinematics/proto/MecanumDriveWheelPositionsProto.hpp index 7ed4ca0ebc..ac2bdeb01c 100644 --- a/wpimath/src/main/native/include/wpi/math/kinematics/proto/MecanumDriveWheelPositionsProto.hpp +++ b/wpimath/src/main/native/include/wpi/math/kinematics/proto/MecanumDriveWheelPositionsProto.hpp @@ -10,12 +10,12 @@ #include "wpimath/protobuf/kinematics.npb.h" template <> -struct WPILIB_DLLEXPORT wpi::Protobuf { +struct WPILIB_DLLEXPORT wpi::util::Protobuf { using MessageStruct = wpi_proto_ProtobufMecanumDriveWheelPositions; - using InputStream = wpi::ProtoInputStream; - using OutputStream = wpi::ProtoOutputStream; - static std::optional Unpack( + using InputStream = wpi::util::ProtoInputStream; + using OutputStream = wpi::util::ProtoOutputStream; + static std::optional Unpack( InputStream& stream); static bool Pack(OutputStream& stream, - const frc::MecanumDriveWheelPositions& value); + const wpi::math::MecanumDriveWheelPositions& value); }; diff --git a/wpimath/src/main/native/include/wpi/math/kinematics/proto/MecanumDriveWheelSpeedsProto.hpp b/wpimath/src/main/native/include/wpi/math/kinematics/proto/MecanumDriveWheelSpeedsProto.hpp index 167394c588..2d610ac4d0 100644 --- a/wpimath/src/main/native/include/wpi/math/kinematics/proto/MecanumDriveWheelSpeedsProto.hpp +++ b/wpimath/src/main/native/include/wpi/math/kinematics/proto/MecanumDriveWheelSpeedsProto.hpp @@ -10,12 +10,12 @@ #include "wpimath/protobuf/kinematics.npb.h" template <> -struct WPILIB_DLLEXPORT wpi::Protobuf { +struct WPILIB_DLLEXPORT wpi::util::Protobuf { using MessageStruct = wpi_proto_ProtobufMecanumDriveWheelSpeeds; - using InputStream = wpi::ProtoInputStream; - using OutputStream = wpi::ProtoOutputStream; - static std::optional Unpack( + using InputStream = wpi::util::ProtoInputStream; + using OutputStream = wpi::util::ProtoOutputStream; + static std::optional Unpack( InputStream& stream); static bool Pack(OutputStream& stream, - const frc::MecanumDriveWheelSpeeds& value); + const wpi::math::MecanumDriveWheelSpeeds& value); }; diff --git a/wpimath/src/main/native/include/wpi/math/kinematics/proto/SwerveDriveKinematicsProto.hpp b/wpimath/src/main/native/include/wpi/math/kinematics/proto/SwerveDriveKinematicsProto.hpp index 79058313e1..c5242c0aea 100644 --- a/wpimath/src/main/native/include/wpi/math/kinematics/proto/SwerveDriveKinematicsProto.hpp +++ b/wpimath/src/main/native/include/wpi/math/kinematics/proto/SwerveDriveKinematicsProto.hpp @@ -14,30 +14,30 @@ #include "wpimath/protobuf/kinematics.npb.h" template -struct wpi::Protobuf> { +struct wpi::util::Protobuf> { using MessageStruct = wpi_proto_ProtobufSwerveDriveKinematics; using InputStream = - wpi::ProtoInputStream>; + wpi::util::ProtoInputStream>; using OutputStream = - wpi::ProtoOutputStream>; + wpi::util::ProtoOutputStream>; - static std::optional> Unpack( + static std::optional> Unpack( InputStream& stream) { - wpi::WpiArrayUnpackCallback modules; + wpi::util::WpiArrayUnpackCallback modules; wpi_proto_ProtobufSwerveDriveKinematics msg{ .modules = modules.Callback(), }; - modules.SetLimits(wpi::DecodeLimits::Fail); + modules.SetLimits(wpi::util::DecodeLimits::Fail); if (!stream.Decode(msg)) { return {}; } - return frc::SwerveDriveKinematics{modules.Array()}; + return wpi::math::SwerveDriveKinematics{modules.Array()}; } static bool Pack(OutputStream& stream, - const frc::SwerveDriveKinematics& value) { - wpi::PackCallback modules{value.GetModules()}; + const wpi::math::SwerveDriveKinematics& value) { + wpi::util::PackCallback modules{value.GetModules()}; wpi_proto_ProtobufSwerveDriveKinematics msg{ .modules = modules.Callback(), }; diff --git a/wpimath/src/main/native/include/wpi/math/kinematics/proto/SwerveModulePositionProto.hpp b/wpimath/src/main/native/include/wpi/math/kinematics/proto/SwerveModulePositionProto.hpp index d44b71cc33..23bbec0f89 100644 --- a/wpimath/src/main/native/include/wpi/math/kinematics/proto/SwerveModulePositionProto.hpp +++ b/wpimath/src/main/native/include/wpi/math/kinematics/proto/SwerveModulePositionProto.hpp @@ -10,11 +10,11 @@ #include "wpimath/protobuf/kinematics.npb.h" template <> -struct WPILIB_DLLEXPORT wpi::Protobuf { +struct WPILIB_DLLEXPORT wpi::util::Protobuf { using MessageStruct = wpi_proto_ProtobufSwerveModulePosition; - using InputStream = wpi::ProtoInputStream; - using OutputStream = wpi::ProtoOutputStream; - static std::optional Unpack(InputStream& stream); + using InputStream = wpi::util::ProtoInputStream; + using OutputStream = wpi::util::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); static bool Pack(OutputStream& stream, - const frc::SwerveModulePosition& value); + const wpi::math::SwerveModulePosition& value); }; diff --git a/wpimath/src/main/native/include/wpi/math/kinematics/proto/SwerveModuleStateProto.hpp b/wpimath/src/main/native/include/wpi/math/kinematics/proto/SwerveModuleStateProto.hpp index 6da75cdf4e..cf4b97c828 100644 --- a/wpimath/src/main/native/include/wpi/math/kinematics/proto/SwerveModuleStateProto.hpp +++ b/wpimath/src/main/native/include/wpi/math/kinematics/proto/SwerveModuleStateProto.hpp @@ -10,10 +10,10 @@ #include "wpimath/protobuf/kinematics.npb.h" template <> -struct WPILIB_DLLEXPORT wpi::Protobuf { +struct WPILIB_DLLEXPORT wpi::util::Protobuf { using MessageStruct = wpi_proto_ProtobufSwerveModuleState; - using InputStream = wpi::ProtoInputStream; - using OutputStream = wpi::ProtoOutputStream; - static std::optional Unpack(InputStream& stream); - static bool Pack(OutputStream& stream, const frc::SwerveModuleState& value); + using InputStream = wpi::util::ProtoInputStream; + using OutputStream = wpi::util::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const wpi::math::SwerveModuleState& value); }; diff --git a/wpimath/src/main/native/include/wpi/math/kinematics/struct/ChassisSpeedsStruct.hpp b/wpimath/src/main/native/include/wpi/math/kinematics/struct/ChassisSpeedsStruct.hpp index f0114220f3..872a8a5acd 100644 --- a/wpimath/src/main/native/include/wpi/math/kinematics/struct/ChassisSpeedsStruct.hpp +++ b/wpimath/src/main/native/include/wpi/math/kinematics/struct/ChassisSpeedsStruct.hpp @@ -9,15 +9,15 @@ #include "wpi/util/struct/Struct.hpp" template <> -struct WPILIB_DLLEXPORT wpi::Struct { +struct WPILIB_DLLEXPORT wpi::util::Struct { static constexpr std::string_view GetTypeName() { return "ChassisSpeeds"; } static constexpr size_t GetSize() { return 24; } static constexpr std::string_view GetSchema() { return "double vx;double vy;double omega"; } - static frc::ChassisSpeeds Unpack(std::span data); - static void Pack(std::span data, const frc::ChassisSpeeds& value); + static wpi::math::ChassisSpeeds Unpack(std::span data); + static void Pack(std::span data, const wpi::math::ChassisSpeeds& value); }; -static_assert(wpi::StructSerializable); +static_assert(wpi::util::StructSerializable); diff --git a/wpimath/src/main/native/include/wpi/math/kinematics/struct/DifferentialDriveKinematicsStruct.hpp b/wpimath/src/main/native/include/wpi/math/kinematics/struct/DifferentialDriveKinematicsStruct.hpp index 03b1167860..040d7141cd 100644 --- a/wpimath/src/main/native/include/wpi/math/kinematics/struct/DifferentialDriveKinematicsStruct.hpp +++ b/wpimath/src/main/native/include/wpi/math/kinematics/struct/DifferentialDriveKinematicsStruct.hpp @@ -9,16 +9,16 @@ #include "wpi/util/struct/Struct.hpp" template <> -struct WPILIB_DLLEXPORT wpi::Struct { +struct WPILIB_DLLEXPORT wpi::util::Struct { static constexpr std::string_view GetTypeName() { return "DifferentialDriveKinematics"; } static constexpr size_t GetSize() { return 8; } static constexpr std::string_view GetSchema() { return "double trackwidth"; } - static frc::DifferentialDriveKinematics Unpack(std::span data); + static wpi::math::DifferentialDriveKinematics Unpack(std::span data); static void Pack(std::span data, - const frc::DifferentialDriveKinematics& value); + const wpi::math::DifferentialDriveKinematics& value); }; -static_assert(wpi::StructSerializable); +static_assert(wpi::util::StructSerializable); diff --git a/wpimath/src/main/native/include/wpi/math/kinematics/struct/DifferentialDriveWheelPositionsStruct.hpp b/wpimath/src/main/native/include/wpi/math/kinematics/struct/DifferentialDriveWheelPositionsStruct.hpp index f99d7381ad..241eab0bb1 100644 --- a/wpimath/src/main/native/include/wpi/math/kinematics/struct/DifferentialDriveWheelPositionsStruct.hpp +++ b/wpimath/src/main/native/include/wpi/math/kinematics/struct/DifferentialDriveWheelPositionsStruct.hpp @@ -9,7 +9,7 @@ #include "wpi/util/struct/Struct.hpp" template <> -struct WPILIB_DLLEXPORT wpi::Struct { +struct WPILIB_DLLEXPORT wpi::util::Struct { static constexpr std::string_view GetTypeName() { return "DifferentialDriveWheelPositions"; } @@ -18,10 +18,10 @@ struct WPILIB_DLLEXPORT wpi::Struct { return "double left;double right"; } - static frc::DifferentialDriveWheelPositions Unpack( + static wpi::math::DifferentialDriveWheelPositions Unpack( std::span data); static void Pack(std::span data, - const frc::DifferentialDriveWheelPositions& value); + const wpi::math::DifferentialDriveWheelPositions& value); }; -static_assert(wpi::StructSerializable); +static_assert(wpi::util::StructSerializable); diff --git a/wpimath/src/main/native/include/wpi/math/kinematics/struct/DifferentialDriveWheelSpeedsStruct.hpp b/wpimath/src/main/native/include/wpi/math/kinematics/struct/DifferentialDriveWheelSpeedsStruct.hpp index 45f83f0265..3185b28170 100644 --- a/wpimath/src/main/native/include/wpi/math/kinematics/struct/DifferentialDriveWheelSpeedsStruct.hpp +++ b/wpimath/src/main/native/include/wpi/math/kinematics/struct/DifferentialDriveWheelSpeedsStruct.hpp @@ -9,7 +9,7 @@ #include "wpi/util/struct/Struct.hpp" template <> -struct WPILIB_DLLEXPORT wpi::Struct { +struct WPILIB_DLLEXPORT wpi::util::Struct { static constexpr std::string_view GetTypeName() { return "DifferentialDriveWheelSpeeds"; } @@ -18,10 +18,10 @@ struct WPILIB_DLLEXPORT wpi::Struct { return "double left;double right"; } - static frc::DifferentialDriveWheelSpeeds Unpack( + static wpi::math::DifferentialDriveWheelSpeeds Unpack( std::span data); static void Pack(std::span data, - const frc::DifferentialDriveWheelSpeeds& value); + const wpi::math::DifferentialDriveWheelSpeeds& value); }; -static_assert(wpi::StructSerializable); +static_assert(wpi::util::StructSerializable); diff --git a/wpimath/src/main/native/include/wpi/math/kinematics/struct/MecanumDriveKinematicsStruct.hpp b/wpimath/src/main/native/include/wpi/math/kinematics/struct/MecanumDriveKinematicsStruct.hpp index a4db523874..f445401235 100644 --- a/wpimath/src/main/native/include/wpi/math/kinematics/struct/MecanumDriveKinematicsStruct.hpp +++ b/wpimath/src/main/native/include/wpi/math/kinematics/struct/MecanumDriveKinematicsStruct.hpp @@ -9,26 +9,26 @@ #include "wpi/util/struct/Struct.hpp" template <> -struct WPILIB_DLLEXPORT wpi::Struct { +struct WPILIB_DLLEXPORT wpi::util::Struct { static constexpr std::string_view GetTypeName() { return "MecanumDriveKinematics"; } static constexpr size_t GetSize() { - return 4 * wpi::GetStructSize(); + return 4 * wpi::util::GetStructSize(); } static constexpr std::string_view GetSchema() { return "Translation2d front_left;Translation2d front_right;Translation2d " "rear_left;Translation2d rear_right"; } - static frc::MecanumDriveKinematics Unpack(std::span data); + static wpi::math::MecanumDriveKinematics Unpack(std::span data); static void Pack(std::span data, - const frc::MecanumDriveKinematics& value); + const wpi::math::MecanumDriveKinematics& value); static void ForEachNested( std::invocable auto fn) { - wpi::ForEachStructSchema(fn); + wpi::util::ForEachStructSchema(fn); } }; -static_assert(wpi::StructSerializable); -static_assert(wpi::HasNestedStruct); +static_assert(wpi::util::StructSerializable); +static_assert(wpi::util::HasNestedStruct); diff --git a/wpimath/src/main/native/include/wpi/math/kinematics/struct/MecanumDriveWheelPositionsStruct.hpp b/wpimath/src/main/native/include/wpi/math/kinematics/struct/MecanumDriveWheelPositionsStruct.hpp index 81b1b55ea8..c39c47cd8d 100644 --- a/wpimath/src/main/native/include/wpi/math/kinematics/struct/MecanumDriveWheelPositionsStruct.hpp +++ b/wpimath/src/main/native/include/wpi/math/kinematics/struct/MecanumDriveWheelPositionsStruct.hpp @@ -9,7 +9,7 @@ #include "wpi/util/struct/Struct.hpp" template <> -struct WPILIB_DLLEXPORT wpi::Struct { +struct WPILIB_DLLEXPORT wpi::util::Struct { static constexpr std::string_view GetTypeName() { return "MecanumDriveWheelPositions"; } @@ -19,9 +19,9 @@ struct WPILIB_DLLEXPORT wpi::Struct { "rear_right"; } - static frc::MecanumDriveWheelPositions Unpack(std::span data); + static wpi::math::MecanumDriveWheelPositions Unpack(std::span data); static void Pack(std::span data, - const frc::MecanumDriveWheelPositions& value); + const wpi::math::MecanumDriveWheelPositions& value); }; -static_assert(wpi::StructSerializable); +static_assert(wpi::util::StructSerializable); diff --git a/wpimath/src/main/native/include/wpi/math/kinematics/struct/MecanumDriveWheelSpeedsStruct.hpp b/wpimath/src/main/native/include/wpi/math/kinematics/struct/MecanumDriveWheelSpeedsStruct.hpp index de7678022e..ed0d86fa8a 100644 --- a/wpimath/src/main/native/include/wpi/math/kinematics/struct/MecanumDriveWheelSpeedsStruct.hpp +++ b/wpimath/src/main/native/include/wpi/math/kinematics/struct/MecanumDriveWheelSpeedsStruct.hpp @@ -9,7 +9,7 @@ #include "wpi/util/struct/Struct.hpp" template <> -struct WPILIB_DLLEXPORT wpi::Struct { +struct WPILIB_DLLEXPORT wpi::util::Struct { static constexpr std::string_view GetTypeName() { return "MecanumDriveWheelSpeeds"; } @@ -19,9 +19,9 @@ struct WPILIB_DLLEXPORT wpi::Struct { "double rear_right"; } - static frc::MecanumDriveWheelSpeeds Unpack(std::span data); + static wpi::math::MecanumDriveWheelSpeeds Unpack(std::span data); static void Pack(std::span data, - const frc::MecanumDriveWheelSpeeds& value); + const wpi::math::MecanumDriveWheelSpeeds& value); }; -static_assert(wpi::StructSerializable); +static_assert(wpi::util::StructSerializable); diff --git a/wpimath/src/main/native/include/wpi/math/kinematics/struct/SwerveDriveKinematicsStruct.hpp b/wpimath/src/main/native/include/wpi/math/kinematics/struct/SwerveDriveKinematicsStruct.hpp index 45bc12fd74..72e0b9eec8 100644 --- a/wpimath/src/main/native/include/wpi/math/kinematics/struct/SwerveDriveKinematicsStruct.hpp +++ b/wpimath/src/main/native/include/wpi/math/kinematics/struct/SwerveDriveKinematicsStruct.hpp @@ -11,39 +11,39 @@ #include "wpi/util/struct/Struct.hpp" template -struct wpi::Struct> { - static constexpr ct_string kTypeName = wpi::Concat( - "SwerveDriveKinematics__"_ct_string, wpi::NumToCtString()); +struct wpi::util::Struct> { + static constexpr ct_string kTypeName = wpi::util::Concat( + "SwerveDriveKinematics__"_ct_string, wpi::util::NumToCtString()); static constexpr std::string_view GetTypeName() { return kTypeName; } static constexpr size_t GetSize() { - return NumModules * wpi::Struct::GetSize(); + return NumModules * wpi::util::Struct::GetSize(); } static constexpr ct_string kSchema = - wpi::Concat("Translation2d modules["_ct_string, - wpi::NumToCtString(), "]"_ct_string); + wpi::util::Concat("Translation2d modules["_ct_string, + wpi::util::NumToCtString(), "]"_ct_string); static constexpr std::string_view GetSchema() { return kSchema; } - static frc::SwerveDriveKinematics Unpack( + static wpi::math::SwerveDriveKinematics Unpack( std::span data) { constexpr size_t kModulesOff = 0; - return frc::SwerveDriveKinematics{ - wpi::UnpackStructArray( + return wpi::math::SwerveDriveKinematics{ + wpi::util::UnpackStructArray( data)}; } static void Pack(std::span data, - const frc::SwerveDriveKinematics& value) { + const wpi::math::SwerveDriveKinematics& value) { constexpr size_t kModulesOff = 0; - wpi::PackStructArray(data, value.GetModules()); + wpi::util::PackStructArray(data, value.GetModules()); } static void ForEachNested( std::invocable auto fn) { - wpi::ForEachStructSchema(fn); + wpi::util::ForEachStructSchema(fn); } }; -static_assert(wpi::StructSerializable>); -static_assert(wpi::HasNestedStruct>); -static_assert(wpi::StructSerializable>); -static_assert(wpi::HasNestedStruct>); +static_assert(wpi::util::StructSerializable>); +static_assert(wpi::util::HasNestedStruct>); +static_assert(wpi::util::StructSerializable>); +static_assert(wpi::util::HasNestedStruct>); diff --git a/wpimath/src/main/native/include/wpi/math/kinematics/struct/SwerveModulePositionStruct.hpp b/wpimath/src/main/native/include/wpi/math/kinematics/struct/SwerveModulePositionStruct.hpp index 344100d182..962582a530 100644 --- a/wpimath/src/main/native/include/wpi/math/kinematics/struct/SwerveModulePositionStruct.hpp +++ b/wpimath/src/main/native/include/wpi/math/kinematics/struct/SwerveModulePositionStruct.hpp @@ -9,25 +9,25 @@ #include "wpi/util/struct/Struct.hpp" template <> -struct WPILIB_DLLEXPORT wpi::Struct { +struct WPILIB_DLLEXPORT wpi::util::Struct { static constexpr std::string_view GetTypeName() { return "SwerveModulePosition"; } static constexpr size_t GetSize() { - return 8 + wpi::GetStructSize(); + return 8 + wpi::util::GetStructSize(); } static constexpr std::string_view GetSchema() { return "double distance;Rotation2d angle"; } - static frc::SwerveModulePosition Unpack(std::span data); + static wpi::math::SwerveModulePosition Unpack(std::span data); static void Pack(std::span data, - const frc::SwerveModulePosition& value); + const wpi::math::SwerveModulePosition& value); static void ForEachNested( std::invocable auto fn) { - wpi::ForEachStructSchema(fn); + wpi::util::ForEachStructSchema(fn); } }; -static_assert(wpi::StructSerializable); -static_assert(wpi::HasNestedStruct); +static_assert(wpi::util::StructSerializable); +static_assert(wpi::util::HasNestedStruct); diff --git a/wpimath/src/main/native/include/wpi/math/kinematics/struct/SwerveModuleStateStruct.hpp b/wpimath/src/main/native/include/wpi/math/kinematics/struct/SwerveModuleStateStruct.hpp index c9f626181f..93f16aea89 100644 --- a/wpimath/src/main/native/include/wpi/math/kinematics/struct/SwerveModuleStateStruct.hpp +++ b/wpimath/src/main/native/include/wpi/math/kinematics/struct/SwerveModuleStateStruct.hpp @@ -9,25 +9,25 @@ #include "wpi/util/struct/Struct.hpp" template <> -struct WPILIB_DLLEXPORT wpi::Struct { +struct WPILIB_DLLEXPORT wpi::util::Struct { static constexpr std::string_view GetTypeName() { return "SwerveModuleState"; } static constexpr size_t GetSize() { - return 8 + wpi::GetStructSize(); + return 8 + wpi::util::GetStructSize(); } static constexpr std::string_view GetSchema() { return "double speed;Rotation2d angle"; } - static frc::SwerveModuleState Unpack(std::span data); + static wpi::math::SwerveModuleState Unpack(std::span data); static void Pack(std::span data, - const frc::SwerveModuleState& value); + const wpi::math::SwerveModuleState& value); static void ForEachNested( std::invocable auto fn) { - wpi::ForEachStructSchema(fn); + wpi::util::ForEachStructSchema(fn); } }; -static_assert(wpi::StructSerializable); -static_assert(wpi::HasNestedStruct); +static_assert(wpi::util::StructSerializable); +static_assert(wpi::util::HasNestedStruct); diff --git a/wpimath/src/main/native/include/wpi/math/linalg/DARE.hpp b/wpimath/src/main/native/include/wpi/math/linalg/DARE.hpp index 6db59d8fe0..1d6af51401 100644 --- a/wpimath/src/main/native/include/wpi/math/linalg/DARE.hpp +++ b/wpimath/src/main/native/include/wpi/math/linalg/DARE.hpp @@ -13,7 +13,7 @@ #include "wpi/math/util/StateSpaceUtil.hpp" #include "wpi/util/expected" -namespace frc { +namespace wpi::math { /** * Errors the DARE solver can encounter. @@ -166,7 +166,7 @@ Eigen::Matrix DARE( * @return Solution to the DARE on success, or DAREError on failure. */ template -wpi::expected, DAREError> DARE( +wpi::util::expected, DAREError> DARE( const Eigen::Matrix& A, const Eigen::Matrix& B, const Eigen::Matrix& Q, @@ -175,20 +175,20 @@ wpi::expected, DAREError> DARE( if (checkPreconditions) { // Require R be symmetric if ((R - R.transpose()).norm() > 1e-10) { - return wpi::unexpected{DAREError::RNotSymmetric}; + return wpi::util::unexpected{DAREError::RNotSymmetric}; } } // Require R be positive definite auto R_llt = R.llt(); if (R_llt.info() != Eigen::Success) { - return wpi::unexpected{DAREError::RNotPositiveDefinite}; + return wpi::util::unexpected{DAREError::RNotPositiveDefinite}; } if (checkPreconditions) { // Require Q be symmetric if ((Q - Q.transpose()).norm() > 1e-10) { - return wpi::unexpected{DAREError::QNotSymmetric}; + return wpi::util::unexpected{DAREError::QNotSymmetric}; } // Require Q be positive semidefinite @@ -203,12 +203,12 @@ wpi::expected, DAREError> DARE( auto Q_ldlt = Q.ldlt(); if (Q_ldlt.info() != Eigen::Success || (Q_ldlt.vectorD().array() < 0.0).any()) { - return wpi::unexpected{DAREError::QNotPositiveSemidefinite}; + return wpi::util::unexpected{DAREError::QNotPositiveSemidefinite}; } // Require (A, B) pair be stabilizable if (!IsStabilizable(A, B)) { - return wpi::unexpected{DAREError::ABNotStabilizable}; + return wpi::util::unexpected{DAREError::ABNotStabilizable}; } // Require (A, C) pair be detectable where Q = CᵀC @@ -221,7 +221,7 @@ wpi::expected, DAREError> DARE( Q_ldlt.transpositionsP(); if (!IsDetectable(A, C)) { - return wpi::unexpected{DAREError::ACNotDetectable}; + return wpi::util::unexpected{DAREError::ACNotDetectable}; } } @@ -281,7 +281,7 @@ J = Σ [uₖ] [0 R][uₖ] ΔT @return Solution to the DARE on success, or DAREError on failure. */ template -wpi::expected, DAREError> DARE( +wpi::util::expected, DAREError> DARE( const Eigen::Matrix& A, const Eigen::Matrix& B, const Eigen::Matrix& Q, @@ -291,14 +291,14 @@ wpi::expected, DAREError> DARE( if (checkPreconditions) { // Require R be symmetric if ((R - R.transpose()).norm() > 1e-10) { - return wpi::unexpected{DAREError::RNotSymmetric}; + return wpi::util::unexpected{DAREError::RNotSymmetric}; } } // Require R be positive definite auto R_llt = R.llt(); if (R_llt.info() != Eigen::Success) { - return wpi::unexpected{DAREError::RNotPositiveDefinite}; + return wpi::util::unexpected{DAREError::RNotPositiveDefinite}; } // This is a change of variables to make the DARE that includes Q, R, and N @@ -320,7 +320,7 @@ wpi::expected, DAREError> DARE( if (checkPreconditions) { // Require Q be symmetric if ((Q_2 - Q_2.transpose()).norm() > 1e-10) { - return wpi::unexpected{DAREError::QNotSymmetric}; + return wpi::util::unexpected{DAREError::QNotSymmetric}; } // Require Q be positive semidefinite @@ -335,12 +335,12 @@ wpi::expected, DAREError> DARE( auto Q_ldlt = Q_2.ldlt(); if (Q_ldlt.info() != Eigen::Success || (Q_ldlt.vectorD().array() < 0.0).any()) { - return wpi::unexpected{DAREError::QNotPositiveSemidefinite}; + return wpi::util::unexpected{DAREError::QNotPositiveSemidefinite}; } // Require (A, B) pair be stabilizable if (!IsStabilizable(A_2, B)) { - return wpi::unexpected{DAREError::ABNotStabilizable}; + return wpi::util::unexpected{DAREError::ABNotStabilizable}; } // Require (A, C) pair be detectable where Q = CᵀC @@ -353,11 +353,11 @@ wpi::expected, DAREError> DARE( Q_ldlt.transpositionsP(); if (!IsDetectable(A_2, C)) { - return wpi::unexpected{DAREError::ACNotDetectable}; + return wpi::util::unexpected{DAREError::ACNotDetectable}; } } return detail::DARE(A_2, B, Q_2, R_llt); } -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/linalg/EigenCore.hpp b/wpimath/src/main/native/include/wpi/math/linalg/EigenCore.hpp index 1604a0de7c..8590df718f 100644 --- a/wpimath/src/main/native/include/wpi/math/linalg/EigenCore.hpp +++ b/wpimath/src/main/native/include/wpi/math/linalg/EigenCore.hpp @@ -6,7 +6,7 @@ #include -namespace frc { +namespace wpi::math { template using Vectord = Eigen::Vector; @@ -20,4 +20,4 @@ template using Matrixd = Eigen::Matrix; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/linalg/ct_matrix.hpp b/wpimath/src/main/native/include/wpi/math/linalg/ct_matrix.hpp index ffa684738a..fed5154cda 100644 --- a/wpimath/src/main/native/include/wpi/math/linalg/ct_matrix.hpp +++ b/wpimath/src/main/native/include/wpi/math/linalg/ct_matrix.hpp @@ -11,7 +11,7 @@ #include #include -namespace frc { +namespace wpi::math { template concept EigenMatrixLike = std::derived_from>; @@ -386,4 +386,4 @@ using ct_matrix3d = ct_matrix; using ct_vector2d = ct_vector; using ct_vector3d = ct_vector; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/linalg/proto/MatrixProto.hpp b/wpimath/src/main/native/include/wpi/math/linalg/proto/MatrixProto.hpp index fd3d2c8bda..238e8d266b 100644 --- a/wpimath/src/main/native/include/wpi/math/linalg/proto/MatrixProto.hpp +++ b/wpimath/src/main/native/include/wpi/math/linalg/proto/MatrixProto.hpp @@ -15,22 +15,22 @@ template requires(Cols != 1) -struct wpi::Protobuf> { +struct wpi::util::Protobuf> { using MessageStruct = wpi_proto_ProtobufMatrix; - using InputStream = wpi::ProtoInputStream< - frc::Matrixd>; - using OutputStream = wpi::ProtoOutputStream< - frc::Matrixd>; + using InputStream = wpi::util::ProtoInputStream< + wpi::math::Matrixd>; + using OutputStream = wpi::util::ProtoOutputStream< + wpi::math::Matrixd>; - static std::optional> + static std::optional> Unpack(InputStream& stream) { constexpr bool isSmall = Rows * Cols * sizeof(double) < 256; using UnpackType = - std::conditional_t, - wpi::StdVectorUnpackCallback>; + std::conditional_t, + wpi::util::StdVectorUnpackCallback>; UnpackType data; data.Vec().reserve(Rows * Cols); - data.SetLimits(wpi::DecodeLimits::Fail); + data.SetLimits(wpi::util::DecodeLimits::Fail); wpi_proto_ProtobufMatrix msg; msg.data = data.Callback(); if (!stream.Decode(msg)) { @@ -47,7 +47,7 @@ struct wpi::Protobuf> { return {}; } - frc::Matrixd mat; + wpi::math::Matrixd mat; for (int i = 0; i < Rows * Cols; i++) { mat(i) = items[i]; } @@ -57,10 +57,10 @@ struct wpi::Protobuf> { static bool Pack( OutputStream& stream, - const frc::Matrixd& value) { + const wpi::math::Matrixd& value) { std::span dataSpan{value.data(), static_cast(Rows * Cols)}; - wpi::PackCallback data{dataSpan}; + wpi::util::PackCallback data{dataSpan}; wpi_proto_ProtobufMatrix msg{ .num_rows = Rows, .num_cols = Cols, diff --git a/wpimath/src/main/native/include/wpi/math/linalg/proto/VectorProto.hpp b/wpimath/src/main/native/include/wpi/math/linalg/proto/VectorProto.hpp index c39bef2391..14592e31a2 100644 --- a/wpimath/src/main/native/include/wpi/math/linalg/proto/VectorProto.hpp +++ b/wpimath/src/main/native/include/wpi/math/linalg/proto/VectorProto.hpp @@ -14,22 +14,22 @@ #include "wpimath/protobuf/wpimath.npb.h" template -struct wpi::Protobuf> { +struct wpi::util::Protobuf> { using MessageStruct = wpi_proto_ProtobufVector; using InputStream = - wpi::ProtoInputStream>; + wpi::util::ProtoInputStream>; using OutputStream = - wpi::ProtoOutputStream>; + wpi::util::ProtoOutputStream>; - static std::optional> Unpack( + static std::optional> Unpack( InputStream& stream) { constexpr bool isSmall = Size * sizeof(double) < 256; using UnpackType = - std::conditional_t, - wpi::StdVectorUnpackCallback>; + std::conditional_t, + wpi::util::StdVectorUnpackCallback>; UnpackType rows; rows.Vec().reserve(Size); - rows.SetLimits(wpi::DecodeLimits::Fail); + rows.SetLimits(wpi::util::DecodeLimits::Fail); wpi_proto_ProtobufVector msg{ .rows = rows.Callback(), }; @@ -43,7 +43,7 @@ struct wpi::Protobuf> { return {}; } - frc::Matrixd mat; + wpi::math::Matrixd mat; for (int i = 0; i < Size; i++) { mat(i) = items[i]; } @@ -53,9 +53,9 @@ struct wpi::Protobuf> { static bool Pack( OutputStream& stream, - const frc::Matrixd& value) { + const wpi::math::Matrixd& value) { std::span rowsSpan{value.data(), static_cast(Size)}; - wpi::PackCallback rows{rowsSpan}; + wpi::util::PackCallback rows{rowsSpan}; wpi_proto_ProtobufVector msg{ .rows = rows.Callback(), }; diff --git a/wpimath/src/main/native/include/wpi/math/linalg/struct/StructProto.hpp b/wpimath/src/main/native/include/wpi/math/linalg/struct/StructProto.hpp index eb6cadfde8..d2748a1f59 100644 --- a/wpimath/src/main/native/include/wpi/math/linalg/struct/StructProto.hpp +++ b/wpimath/src/main/native/include/wpi/math/linalg/struct/StructProto.hpp @@ -12,23 +12,23 @@ template requires(Cols != 1) -struct wpi::Struct> { +struct wpi::util::Struct> { static constexpr ct_string kTypeName = - wpi::Concat("Matrix__"_ct_string, wpi::NumToCtString(), - "_"_ct_string, wpi::NumToCtString()); + wpi::util::Concat("Matrix__"_ct_string, wpi::util::NumToCtString(), + "_"_ct_string, wpi::util::NumToCtString()); static constexpr std::string_view GetTypeName() { return kTypeName; } static constexpr size_t GetSize() { return Rows * Cols * 8; } static constexpr ct_string kSchema = - wpi::Concat("double data["_ct_string, wpi::NumToCtString(), + wpi::util::Concat("double data["_ct_string, wpi::util::NumToCtString(), "]"_ct_string); static constexpr std::string_view GetSchema() { return kSchema; } - static frc::Matrixd Unpack( + static wpi::math::Matrixd Unpack( std::span data) { constexpr size_t kDataOff = 0; - wpi::array mat_data = - wpi::UnpackStructArray(data); - frc::Matrixd mat; + wpi::util::array mat_data = + wpi::util::UnpackStructArray(data); + wpi::math::Matrixd mat; for (int i = 0; i < Rows * Cols; i++) { mat(i) = mat_data[i]; } @@ -37,15 +37,15 @@ struct wpi::Struct> { static void Pack( std::span data, - const frc::Matrixd& value) { + const wpi::math::Matrixd& value) { constexpr size_t kDataOff = 0; - wpi::array mat_data(wpi::empty_array); + wpi::util::array mat_data(wpi::util::empty_array); for (int i = 0; i < Rows * Cols; i++) { mat_data[i] = value(i); } - wpi::PackStructArray(data, mat_data); + wpi::util::PackStructArray(data, mat_data); } }; -static_assert(wpi::StructSerializable>); -static_assert(wpi::StructSerializable>); +static_assert(wpi::util::StructSerializable>); +static_assert(wpi::util::StructSerializable>); diff --git a/wpimath/src/main/native/include/wpi/math/linalg/struct/VectorStruct.hpp b/wpimath/src/main/native/include/wpi/math/linalg/struct/VectorStruct.hpp index dc72505b0a..f27900fe8d 100644 --- a/wpimath/src/main/native/include/wpi/math/linalg/struct/VectorStruct.hpp +++ b/wpimath/src/main/native/include/wpi/math/linalg/struct/VectorStruct.hpp @@ -11,21 +11,21 @@ #include "wpi/util/struct/Struct.hpp" template -struct wpi::Struct> { +struct wpi::util::Struct> { static constexpr ct_string kTypeName = - wpi::Concat("Vector__"_ct_string, wpi::NumToCtString()); + wpi::util::Concat("Vector__"_ct_string, wpi::util::NumToCtString()); static constexpr std::string_view GetTypeName() { return kTypeName; } static constexpr size_t GetSize() { return Size * 8; } - static constexpr ct_string kSchema = wpi::Concat( - "double data["_ct_string, wpi::NumToCtString(), "]"_ct_string); + static constexpr ct_string kSchema = wpi::util::Concat( + "double data["_ct_string, wpi::util::NumToCtString(), "]"_ct_string); static constexpr std::string_view GetSchema() { return kSchema; } - static frc::Matrixd Unpack( + static wpi::math::Matrixd Unpack( std::span data) { constexpr size_t kDataOff = 0; - wpi::array vec_data = - wpi::UnpackStructArray(data); - frc::Matrixd vec; + wpi::util::array vec_data = + wpi::util::UnpackStructArray(data); + wpi::math::Matrixd vec; for (int i = 0; i < Size; i++) { vec(i) = vec_data[i]; } @@ -34,15 +34,15 @@ struct wpi::Struct> { static void Pack( std::span data, - const frc::Matrixd& value) { + const wpi::math::Matrixd& value) { constexpr size_t kDataOff = 0; - wpi::array vec_data(wpi::empty_array); + wpi::util::array vec_data(wpi::util::empty_array); for (int i = 0; i < Size; i++) { vec_data[i] = value(i); } - wpi::PackStructArray(data, vec_data); + wpi::util::PackStructArray(data, vec_data); } }; -static_assert(wpi::StructSerializable>); -static_assert(wpi::StructSerializable>); +static_assert(wpi::util::StructSerializable>); +static_assert(wpi::util::StructSerializable>); diff --git a/wpimath/src/main/native/include/wpi/math/optimization/SimulatedAnnealing.hpp b/wpimath/src/main/native/include/wpi/math/optimization/SimulatedAnnealing.hpp index 0a16dd963a..9eb66ffce1 100644 --- a/wpimath/src/main/native/include/wpi/math/optimization/SimulatedAnnealing.hpp +++ b/wpimath/src/main/native/include/wpi/math/optimization/SimulatedAnnealing.hpp @@ -9,7 +9,7 @@ #include #include -namespace frc { +namespace wpi::math { /** * An implementation of the Simulated Annealing stochastic nonlinear @@ -98,4 +98,4 @@ class SimulatedAnnealing { std::function m_cost; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/path/TravelingSalesman.hpp b/wpimath/src/main/native/include/wpi/math/path/TravelingSalesman.hpp index 180b65d949..6870c8f414 100644 --- a/wpimath/src/main/native/include/wpi/math/path/TravelingSalesman.hpp +++ b/wpimath/src/main/native/include/wpi/math/path/TravelingSalesman.hpp @@ -15,7 +15,7 @@ #include "wpi/math/optimization/SimulatedAnnealing.hpp" #include "wpi/util/array.hpp" -namespace frc { +namespace wpi::math { /** * Given a list of poses, this class finds the shortest possible route that @@ -55,7 +55,7 @@ class TravelingSalesman { * @return The optimized path as an array of Pose2ds. */ template - wpi::array Solve(const wpi::array& poses, + wpi::util::array Solve(const wpi::util::array& poses, int iterations) { SimulatedAnnealing> solver{ 1, &Neighbor, [&](const Vectord& state) { @@ -76,7 +76,7 @@ class TravelingSalesman { auto indices = solver.Solve(initial, iterations); - wpi::array solution{wpi::empty_array}; + wpi::util::array solution{wpi::util::empty_array}; for (size_t i = 0; i < poses.size(); ++i) { solution[i] = poses[static_cast(indices[i])]; } @@ -137,7 +137,7 @@ class TravelingSalesman { // Default cost is distance between poses std::function m_cost = [](const Pose2d& a, const Pose2d& b) -> double { - return units::math::hypot(a.X() - b.X(), a.Y() - b.Y()).value(); + return wpi::units::math::hypot(a.X() - b.X(), a.Y() - b.Y()).value(); }; /** @@ -175,4 +175,4 @@ class TravelingSalesman { } }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/spline/CubicHermiteSpline.hpp b/wpimath/src/main/native/include/wpi/math/spline/CubicHermiteSpline.hpp index 471b984b1e..53a9620fe0 100644 --- a/wpimath/src/main/native/include/wpi/math/spline/CubicHermiteSpline.hpp +++ b/wpimath/src/main/native/include/wpi/math/spline/CubicHermiteSpline.hpp @@ -9,7 +9,7 @@ #include "wpi/util/SymbolExports.hpp" #include "wpi/util/array.hpp" -namespace frc { +namespace wpi::math { /** * Represents a hermite spline of degree 3. */ @@ -29,10 +29,10 @@ class WPILIB_DLLEXPORT CubicHermiteSpline : public Spline<3> { * @param yFinalControlVector The control vector for the final point in * the y dimension. */ - CubicHermiteSpline(wpi::array xInitialControlVector, - wpi::array xFinalControlVector, - wpi::array yInitialControlVector, - wpi::array yFinalControlVector) + CubicHermiteSpline(wpi::util::array xInitialControlVector, + wpi::util::array xFinalControlVector, + wpi::util::array yInitialControlVector, + wpi::util::array yFinalControlVector) : m_initialControlVector{xInitialControlVector, yInitialControlVector}, m_finalControlVector{xFinalControlVector, yFinalControlVector} { const auto hermite = MakeHermiteBasis(); @@ -137,14 +137,14 @@ class WPILIB_DLLEXPORT CubicHermiteSpline : public Spline<3> { * @return The control vector matrix for a dimension. */ static constexpr Eigen::Vector4d ControlVectorFromArrays( - wpi::array initialVector, wpi::array finalVector) { + wpi::util::array initialVector, wpi::util::array finalVector) { return Eigen::Vector4d{{initialVector[0]}, {initialVector[1]}, {finalVector[0]}, {finalVector[1]}}; } }; -} // namespace frc +} // namespace wpi::math #include "wpi/math/spline/proto/CubicHermiteSplineProto.hpp" #include "wpi/math/spline/struct/CubicHermiteSplineStruct.hpp" diff --git a/wpimath/src/main/native/include/wpi/math/spline/QuinticHermiteSpline.hpp b/wpimath/src/main/native/include/wpi/math/spline/QuinticHermiteSpline.hpp index c33d358eec..b1f2f62c9b 100644 --- a/wpimath/src/main/native/include/wpi/math/spline/QuinticHermiteSpline.hpp +++ b/wpimath/src/main/native/include/wpi/math/spline/QuinticHermiteSpline.hpp @@ -9,7 +9,7 @@ #include "wpi/util/SymbolExports.hpp" #include "wpi/util/array.hpp" -namespace frc { +namespace wpi::math { /** * Represents a hermite spline of degree 5. */ @@ -29,10 +29,10 @@ class WPILIB_DLLEXPORT QuinticHermiteSpline : public Spline<5> { * @param yFinalControlVector The control vector for the final point in * the y dimension. */ - QuinticHermiteSpline(wpi::array xInitialControlVector, - wpi::array xFinalControlVector, - wpi::array yInitialControlVector, - wpi::array yFinalControlVector) + QuinticHermiteSpline(wpi::util::array xInitialControlVector, + wpi::util::array xFinalControlVector, + wpi::util::array yInitialControlVector, + wpi::util::array yFinalControlVector) : m_initialControlVector{xInitialControlVector, yInitialControlVector}, m_finalControlVector{xFinalControlVector, yFinalControlVector} { const auto hermite = MakeHermiteBasis(); @@ -145,13 +145,13 @@ class WPILIB_DLLEXPORT QuinticHermiteSpline : public Spline<5> { * @return The control vector matrix for a dimension. */ static constexpr Vectord<6> ControlVectorFromArrays( - wpi::array initialVector, wpi::array finalVector) { + wpi::util::array initialVector, wpi::util::array finalVector) { return Vectord<6>{{initialVector[0]}, {initialVector[1]}, {initialVector[2]}, {finalVector[0]}, {finalVector[1]}, {finalVector[2]}}; } }; -} // namespace frc +} // namespace wpi::math #include "wpi/math/spline/proto/QuinticHermiteSplineProto.hpp" #include "wpi/math/spline/struct/QuinticHermiteSplineStruct.hpp" diff --git a/wpimath/src/main/native/include/wpi/math/spline/Spline.hpp b/wpimath/src/main/native/include/wpi/math/spline/Spline.hpp index 12a6d37756..e1fb805f04 100644 --- a/wpimath/src/main/native/include/wpi/math/spline/Spline.hpp +++ b/wpimath/src/main/native/include/wpi/math/spline/Spline.hpp @@ -15,7 +15,7 @@ #include "wpi/units/length.hpp" #include "wpi/util/array.hpp" -namespace frc { +namespace wpi::math { /** * Represents a two-dimensional parametric spline that interpolates between two @@ -26,7 +26,7 @@ namespace frc { template class Spline { public: - using PoseWithCurvature = std::pair; + using PoseWithCurvature = std::pair; constexpr Spline() = default; @@ -47,10 +47,10 @@ class Spline { */ struct ControlVector { /// The x components of the control vector. - wpi::array x; + wpi::util::array x; /// The y components of the control vector. - wpi::array y; + wpi::util::array y; }; /** @@ -100,7 +100,7 @@ class Spline { return PoseWithCurvature{ {FromVector(combined.template block<2, 1>(0, 0)), Rotation2d{dx, dy}}, - units::curvature_t{curvature}}; + wpi::units::curvature_t{curvature}}; } /** @@ -143,8 +143,8 @@ class Spline { * @return The Translation2d. */ static constexpr Translation2d FromVector(const Eigen::Vector2d& vector) { - return Translation2d{units::meter_t{vector(0)}, units::meter_t{vector(1)}}; + return Translation2d{wpi::units::meter_t{vector(0)}, wpi::units::meter_t{vector(1)}}; } }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/spline/SplineHelper.hpp b/wpimath/src/main/native/include/wpi/math/spline/SplineHelper.hpp index 1e577d7a16..b8b06ea0de 100644 --- a/wpimath/src/main/native/include/wpi/math/spline/SplineHelper.hpp +++ b/wpimath/src/main/native/include/wpi/math/spline/SplineHelper.hpp @@ -12,7 +12,7 @@ #include "wpi/util/SymbolExports.hpp" #include "wpi/util/array.hpp" -namespace frc { +namespace wpi::math { /** * Helper class that is used to generate cubic and quintic splines from user * provided waypoints. @@ -28,7 +28,7 @@ class WPILIB_DLLEXPORT SplineHelper { * @param end The ending pose. * @return 2 cubic control vectors. */ - static wpi::array::ControlVector, 2> + static wpi::util::array::ControlVector, 2> CubicControlVectorsFromWaypoints( const Pose2d& start, const std::vector& interiorWaypoints, const Pose2d& end) { @@ -97,17 +97,17 @@ class WPILIB_DLLEXPORT SplineHelper { const Spline<3>::ControlVector& end) { std::vector splines; - wpi::array xInitial = start.x; - wpi::array yInitial = start.y; - wpi::array xFinal = end.x; - wpi::array yFinal = end.y; + wpi::util::array xInitial = start.x; + wpi::util::array yInitial = start.y; + wpi::util::array xFinal = end.x; + wpi::util::array yFinal = end.y; if (waypoints.size() > 1) { waypoints.emplace(waypoints.begin(), - Translation2d{units::meter_t{xInitial[0]}, - units::meter_t{yInitial[0]}}); + Translation2d{wpi::units::meter_t{xInitial[0]}, + wpi::units::meter_t{yInitial[0]}}); waypoints.emplace_back( - Translation2d{units::meter_t{xFinal[0]}, units::meter_t{yFinal[0]}}); + Translation2d{wpi::units::meter_t{xFinal[0]}, wpi::units::meter_t{yFinal[0]}}); // Populate tridiagonal system for clamped cubic /* See: @@ -186,8 +186,8 @@ class WPILIB_DLLEXPORT SplineHelper { const double yDeriv = (3 * (yFinal[0] - yInitial[0]) - yFinal[1] - yInitial[1]) / 4.0; - wpi::array midXControlVector{waypoints[0].X().value(), xDeriv}; - wpi::array midYControlVector{waypoints[0].Y().value(), yDeriv}; + wpi::util::array midXControlVector{waypoints[0].X().value(), xDeriv}; + wpi::util::array midYControlVector{waypoints[0].Y().value(), yDeriv}; splines.emplace_back(xInitial, midXControlVector, yInitial, midYControlVector); @@ -265,8 +265,8 @@ class WPILIB_DLLEXPORT SplineHelper { const auto& bFinal = b.GetFinalControlVector(); // Create cubic splines with the same control vectors. - auto Trim = [](const wpi::array& a) { - return wpi::array{a[0], a[1]}; + auto Trim = [](const wpi::util::array& a) { + return wpi::util::array{a[0], a[1]}; }; CubicHermiteSpline ca{Trim(aInitial.x), Trim(aFinal.x), Trim(aInitial.y), Trim(aFinal.y)}; @@ -274,8 +274,8 @@ class WPILIB_DLLEXPORT SplineHelper { Trim(bFinal.y)}; // Calculate the second derivatives at the knot points. - frc::Vectord<4> bases{1.0, 1.0, 1.0, 1.0}; - frc::Vectord<6> combinedA = ca.Coefficients() * bases; + wpi::math::Vectord<4> bases{1.0, 1.0, 1.0, 1.0}; + wpi::math::Vectord<6> combinedA = ca.Coefficients() * bases; double ddxA = combinedA(4); double ddyA = combinedA(5); @@ -365,4 +365,4 @@ class WPILIB_DLLEXPORT SplineHelper { } } }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/spline/SplineParameterizer.hpp b/wpimath/src/main/native/include/wpi/math/spline/SplineParameterizer.hpp index 124ee32357..7adab5952b 100644 --- a/wpimath/src/main/native/include/wpi/math/spline/SplineParameterizer.hpp +++ b/wpimath/src/main/native/include/wpi/math/spline/SplineParameterizer.hpp @@ -40,14 +40,14 @@ #include "wpi/units/math.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::math { /** * Class used to parameterize a spline by its arc length. */ class WPILIB_DLLEXPORT SplineParameterizer { public: - using PoseWithCurvature = std::pair; + using PoseWithCurvature = std::pair; struct MalformedSplineException : public std::runtime_error { explicit MalformedSplineException(const char* what_arg) @@ -107,9 +107,9 @@ class WPILIB_DLLEXPORT SplineParameterizer { const auto twist = (end.value().first - start.value().first).Log(); - if (units::math::abs(twist.dy) > kMaxDy || - units::math::abs(twist.dx) > kMaxDx || - units::math::abs(twist.dtheta) > kMaxDtheta) { + if (wpi::units::math::abs(twist.dy) > kMaxDy || + wpi::units::math::abs(twist.dx) > kMaxDx || + wpi::units::math::abs(twist.dtheta) > kMaxDtheta) { stack.emplace(StackContents{(current.t0 + current.t1) / 2, current.t1}); stack.emplace(StackContents{current.t0, (current.t0 + current.t1) / 2}); } else { @@ -126,9 +126,9 @@ class WPILIB_DLLEXPORT SplineParameterizer { private: // Constraints for spline parameterization. - static inline constexpr units::meter_t kMaxDx = 5_in; - static inline constexpr units::meter_t kMaxDy = 0.05_in; - static inline constexpr units::radian_t kMaxDtheta = 0.0872_rad; + static inline constexpr wpi::units::meter_t kMaxDx = 5_in; + static inline constexpr wpi::units::meter_t kMaxDy = 0.05_in; + static inline constexpr wpi::units::radian_t kMaxDtheta = 0.0872_rad; struct StackContents { double t0; @@ -147,4 +147,4 @@ class WPILIB_DLLEXPORT SplineParameterizer { friend class CubicHermiteSplineTest; friend class QuinticHermiteSplineTest; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/spline/proto/CubicHermiteSplineProto.hpp b/wpimath/src/main/native/include/wpi/math/spline/proto/CubicHermiteSplineProto.hpp index 35950ecd24..b75ebfcbf7 100644 --- a/wpimath/src/main/native/include/wpi/math/spline/proto/CubicHermiteSplineProto.hpp +++ b/wpimath/src/main/native/include/wpi/math/spline/proto/CubicHermiteSplineProto.hpp @@ -10,10 +10,10 @@ #include "wpimath/protobuf/spline.npb.h" template <> -struct WPILIB_DLLEXPORT wpi::Protobuf { +struct WPILIB_DLLEXPORT wpi::util::Protobuf { using MessageStruct = wpi_proto_ProtobufCubicHermiteSpline; - using InputStream = wpi::ProtoInputStream; - using OutputStream = wpi::ProtoOutputStream; - static std::optional Unpack(InputStream& stream); - static bool Pack(OutputStream& stream, const frc::CubicHermiteSpline& value); + using InputStream = wpi::util::ProtoInputStream; + using OutputStream = wpi::util::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const wpi::math::CubicHermiteSpline& value); }; diff --git a/wpimath/src/main/native/include/wpi/math/spline/proto/QuinticHermiteSplineProto.hpp b/wpimath/src/main/native/include/wpi/math/spline/proto/QuinticHermiteSplineProto.hpp index 4f189437e6..5b9a42fbad 100644 --- a/wpimath/src/main/native/include/wpi/math/spline/proto/QuinticHermiteSplineProto.hpp +++ b/wpimath/src/main/native/include/wpi/math/spline/proto/QuinticHermiteSplineProto.hpp @@ -10,11 +10,11 @@ #include "wpimath/protobuf/spline.npb.h" template <> -struct WPILIB_DLLEXPORT wpi::Protobuf { +struct WPILIB_DLLEXPORT wpi::util::Protobuf { using MessageStruct = wpi_proto_ProtobufQuinticHermiteSpline; - using InputStream = wpi::ProtoInputStream; - using OutputStream = wpi::ProtoOutputStream; - static std::optional Unpack(InputStream& stream); + using InputStream = wpi::util::ProtoInputStream; + using OutputStream = wpi::util::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); static bool Pack(OutputStream& stream, - const frc::QuinticHermiteSpline& value); + const wpi::math::QuinticHermiteSpline& value); }; diff --git a/wpimath/src/main/native/include/wpi/math/spline/struct/CubicHermiteSplineStruct.hpp b/wpimath/src/main/native/include/wpi/math/spline/struct/CubicHermiteSplineStruct.hpp index fc7b5f65a6..cadcda7e48 100644 --- a/wpimath/src/main/native/include/wpi/math/spline/struct/CubicHermiteSplineStruct.hpp +++ b/wpimath/src/main/native/include/wpi/math/spline/struct/CubicHermiteSplineStruct.hpp @@ -9,7 +9,7 @@ #include "wpi/util/struct/Struct.hpp" template <> -struct WPILIB_DLLEXPORT wpi::Struct { +struct WPILIB_DLLEXPORT wpi::util::Struct { static constexpr std::string_view GetTypeName() { return "CubicHermiteSpline"; } @@ -19,9 +19,9 @@ struct WPILIB_DLLEXPORT wpi::Struct { "yFinal[2]"; } - static frc::CubicHermiteSpline Unpack(std::span data); + static wpi::math::CubicHermiteSpline Unpack(std::span data); static void Pack(std::span data, - const frc::CubicHermiteSpline& value); + const wpi::math::CubicHermiteSpline& value); }; -static_assert(wpi::StructSerializable); +static_assert(wpi::util::StructSerializable); diff --git a/wpimath/src/main/native/include/wpi/math/spline/struct/QuinticHermiteSplineStruct.hpp b/wpimath/src/main/native/include/wpi/math/spline/struct/QuinticHermiteSplineStruct.hpp index c650cada04..86e6d98846 100644 --- a/wpimath/src/main/native/include/wpi/math/spline/struct/QuinticHermiteSplineStruct.hpp +++ b/wpimath/src/main/native/include/wpi/math/spline/struct/QuinticHermiteSplineStruct.hpp @@ -9,7 +9,7 @@ #include "wpi/util/struct/Struct.hpp" template <> -struct WPILIB_DLLEXPORT wpi::Struct { +struct WPILIB_DLLEXPORT wpi::util::Struct { static constexpr std::string_view GetTypeName() { return "QuinticHermiteSpline"; } @@ -19,9 +19,9 @@ struct WPILIB_DLLEXPORT wpi::Struct { "yFinal[3]"; } - static frc::QuinticHermiteSpline Unpack(std::span data); + static wpi::math::QuinticHermiteSpline Unpack(std::span data); static void Pack(std::span data, - const frc::QuinticHermiteSpline& value); + const wpi::math::QuinticHermiteSpline& value); }; -static_assert(wpi::StructSerializable); +static_assert(wpi::util::StructSerializable); diff --git a/wpimath/src/main/native/include/wpi/math/system/Discretization.hpp b/wpimath/src/main/native/include/wpi/math/system/Discretization.hpp index 77d7cd6f87..7b59f481e8 100644 --- a/wpimath/src/main/native/include/wpi/math/system/Discretization.hpp +++ b/wpimath/src/main/native/include/wpi/math/system/Discretization.hpp @@ -9,7 +9,7 @@ #include "wpi/math/linalg/EigenCore.hpp" #include "wpi/units/time.hpp" -namespace frc { +namespace wpi::math { /** * Discretizes the given continuous A matrix. @@ -20,7 +20,7 @@ namespace frc { * @param discA Storage for discrete system matrix. */ template -void DiscretizeA(const Matrixd& contA, units::second_t dt, +void DiscretizeA(const Matrixd& contA, wpi::units::second_t dt, Matrixd* discA) { // A_d = eᴬᵀ *discA = (contA * dt.value()).exp(); @@ -39,7 +39,7 @@ void DiscretizeA(const Matrixd& contA, units::second_t dt, */ template void DiscretizeAB(const Matrixd& contA, - const Matrixd& contB, units::second_t dt, + const Matrixd& contB, wpi::units::second_t dt, Matrixd* discA, Matrixd* discB) { // M = [A B] @@ -69,7 +69,7 @@ void DiscretizeAB(const Matrixd& contA, */ template void DiscretizeAQ(const Matrixd& contA, - const Matrixd& contQ, units::second_t dt, + const Matrixd& contQ, wpi::units::second_t dt, Matrixd* discA, Matrixd* discQ) { // Make continuous Q symmetric if it isn't already @@ -111,9 +111,9 @@ void DiscretizeAQ(const Matrixd& contA, */ template Matrixd DiscretizeR(const Matrixd& R, - units::second_t dt) { + wpi::units::second_t dt) { // R_d = 1/T R return R / dt.value(); } -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/system/LinearSystem.hpp b/wpimath/src/main/native/include/wpi/math/system/LinearSystem.hpp index ac3761b83a..b6988e4737 100644 --- a/wpimath/src/main/native/include/wpi/math/system/LinearSystem.hpp +++ b/wpimath/src/main/native/include/wpi/math/system/LinearSystem.hpp @@ -17,7 +17,7 @@ #include "wpi/util/Algorithm.hpp" #include "wpi/util/SmallVector.hpp" -namespace frc { +namespace wpi::math { /** * A plant defined using state-space notation. @@ -161,7 +161,7 @@ class LinearSystem { * @param dt Timestep for model update. */ StateVector CalculateX(const StateVector& x, const InputVector& clampedU, - units::second_t dt) const { + wpi::units::second_t dt) const { Matrixd discA; Matrixd discB; DiscretizeAB(m_A, m_B, dt, &discA, &discB); @@ -205,7 +205,7 @@ class LinearSystem { "More outputs requested than available. This is usually due " "to model implementation errors."); - wpi::for_each( + wpi::util::for_each( [](size_t i, const auto& elem) { if (elem < 0 || elem >= Outputs) { throw std::domain_error( @@ -216,7 +216,7 @@ class LinearSystem { outputIndices...); // Sort and deduplicate output indices - wpi::SmallVector outputIndicesArray{outputIndices...}; + wpi::util::SmallVector outputIndicesArray{outputIndices...}; std::sort(outputIndicesArray.begin(), outputIndicesArray.end()); auto last = std::unique(outputIndicesArray.begin(), outputIndicesArray.end()); @@ -255,4 +255,4 @@ class LinearSystem { Matrixd m_D; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/system/LinearSystemLoop.hpp b/wpimath/src/main/native/include/wpi/math/system/LinearSystemLoop.hpp index 2656d3ce39..25991f48e1 100644 --- a/wpimath/src/main/native/include/wpi/math/system/LinearSystemLoop.hpp +++ b/wpimath/src/main/native/include/wpi/math/system/LinearSystemLoop.hpp @@ -15,7 +15,7 @@ #include "wpi/units/voltage.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::math { /** * Combines a controller, feedforward, and observer for controlling a mechanism @@ -57,11 +57,11 @@ class LinearSystemLoop { LinearSystemLoop(LinearSystem& plant, LinearQuadraticRegulator& controller, KalmanFilter& observer, - units::volt_t maxVoltage, units::second_t dt) + wpi::units::volt_t maxVoltage, wpi::units::second_t dt) : LinearSystemLoop( plant, controller, observer, [=](const InputVector& u) { - return frc::DesaturateInputVector(u, maxVoltage.value()); + return wpi::math::DesaturateInputVector(u, maxVoltage.value()); }, dt) {} @@ -81,7 +81,7 @@ class LinearSystemLoop { LinearQuadraticRegulator& controller, KalmanFilter& observer, std::function clampFunction, - units::second_t dt) + wpi::units::second_t dt) : LinearSystemLoop( controller, LinearPlantInversionFeedforward{plant, dt}, @@ -101,10 +101,10 @@ class LinearSystemLoop { LinearSystemLoop( LinearQuadraticRegulator& controller, const LinearPlantInversionFeedforward& feedforward, - KalmanFilter& observer, units::volt_t maxVoltage) + KalmanFilter& observer, wpi::units::volt_t maxVoltage) : LinearSystemLoop( controller, feedforward, observer, [=](const InputVector& u) { - return frc::DesaturateInputVector(u, maxVoltage.value()); + return wpi::math::DesaturateInputVector(u, maxVoltage.value()); }) {} /** @@ -251,7 +251,7 @@ class LinearSystemLoop { * * @param dt Timestep for model update. */ - void Predict(units::second_t dt) { + void Predict(wpi::units::second_t dt) { InputVector u = ClampInput(m_controller->Calculate(m_observer->Xhat(), m_nextR) + m_feedforward.Calculate(m_nextR)); @@ -290,4 +290,4 @@ extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT) extern template class EXPORT_TEMPLATE_DECLARE(WPILIB_DLLEXPORT) LinearSystemLoop<2, 1, 1>; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/system/NumericalIntegration.hpp b/wpimath/src/main/native/include/wpi/math/system/NumericalIntegration.hpp index 18ac5f60e9..bd1e7fd887 100644 --- a/wpimath/src/main/native/include/wpi/math/system/NumericalIntegration.hpp +++ b/wpimath/src/main/native/include/wpi/math/system/NumericalIntegration.hpp @@ -10,7 +10,7 @@ #include "wpi/units/time.hpp" -namespace frc { +namespace wpi::math { /** * Performs 4th order Runge-Kutta integration of dx/dt = f(x) for dt. @@ -20,7 +20,7 @@ namespace frc { * @param dt The time over which to integrate. */ template -T RK4(F&& f, T x, units::second_t dt) { +T RK4(F&& f, T x, wpi::units::second_t dt) { const auto h = dt.value(); T k1 = f(x); @@ -40,7 +40,7 @@ T RK4(F&& f, T x, units::second_t dt) { * @param dt The time over which to integrate. */ template -T RK4(F&& f, T x, U u, units::second_t dt) { +T RK4(F&& f, T x, U u, wpi::units::second_t dt) { const auto h = dt.value(); T k1 = f(x, u); @@ -60,7 +60,7 @@ T RK4(F&& f, T x, U u, units::second_t dt) { * @param dt The time over which to integrate. */ template -T RK4(F&& f, units::second_t t, T y, units::second_t dt) { +T RK4(F&& f, wpi::units::second_t t, T y, wpi::units::second_t dt) { const auto h = dt.to(); T k1 = f(t, y); @@ -83,7 +83,7 @@ T RK4(F&& f, units::second_t t, T y, units::second_t dt) { * number like 1e-6. */ template -T RKDP(F&& f, T x, U u, units::second_t dt, double maxError = 1e-6) { +T RKDP(F&& f, T x, U u, wpi::units::second_t dt, double maxError = 1e-6) { // See https://en.wikipedia.org/wiki/Dormand%E2%80%93Prince_method for the // Butcher tableau the following arrays came from. @@ -166,7 +166,7 @@ T RKDP(F&& f, T x, U u, units::second_t dt, double maxError = 1e-6) { * number like 1e-6. */ template -T RKDP(F&& f, units::second_t t, T y, units::second_t dt, +T RKDP(F&& f, wpi::units::second_t t, T y, wpi::units::second_t dt, double maxError = 1e-6) { // See https://en.wikipedia.org/wiki/Dormand%E2%80%93Prince_method for the // Butcher tableau the following arrays came from. @@ -208,18 +208,18 @@ T RKDP(F&& f, units::second_t t, T y, units::second_t dt, // clang-format off T k1 = f(t, y); - T k2 = f(t + units::second_t{h} * c[0], y + h * (A[0][0] * k1)); - T k3 = f(t + units::second_t{h} * c[1], y + h * (A[1][0] * k1 + A[1][1] * k2)); - T k4 = f(t + units::second_t{h} * c[2], y + h * (A[2][0] * k1 + A[2][1] * k2 + A[2][2] * k3)); - T k5 = f(t + units::second_t{h} * c[3], y + h * (A[3][0] * k1 + A[3][1] * k2 + A[3][2] * k3 + A[3][3] * k4)); - T k6 = f(t + units::second_t{h} * c[4], y + h * (A[4][0] * k1 + A[4][1] * k2 + A[4][2] * k3 + A[4][3] * k4 + A[4][4] * k5)); + T k2 = f(t + wpi::units::second_t{h} * c[0], y + h * (A[0][0] * k1)); + T k3 = f(t + wpi::units::second_t{h} * c[1], y + h * (A[1][0] * k1 + A[1][1] * k2)); + T k4 = f(t + wpi::units::second_t{h} * c[2], y + h * (A[2][0] * k1 + A[2][1] * k2 + A[2][2] * k3)); + T k5 = f(t + wpi::units::second_t{h} * c[3], y + h * (A[3][0] * k1 + A[3][1] * k2 + A[3][2] * k3 + A[3][3] * k4)); + T k6 = f(t + wpi::units::second_t{h} * c[4], y + h * (A[4][0] * k1 + A[4][1] * k2 + A[4][2] * k3 + A[4][3] * k4 + A[4][4] * k5)); // clang-format on // Since the final row of A and the array b1 have the same coefficients // and k7 has no effect on newY, we can reuse the calculation. newY = y + h * (A[5][0] * k1 + A[5][1] * k2 + A[5][2] * k3 + A[5][3] * k4 + A[5][4] * k5 + A[5][5] * k6); - T k7 = f(t + units::second_t{h} * c[5], newY); + T k7 = f(t + wpi::units::second_t{h} * c[5], newY); truncationError = (h * ((b1[0] - b2[0]) * k1 + (b1[1] - b2[1]) * k2 + (b1[2] - b2[2]) * k3 + (b1[3] - b2[3]) * k4 + @@ -237,4 +237,4 @@ T RKDP(F&& f, units::second_t t, T y, units::second_t dt, return y; } -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/system/NumericalJacobian.hpp b/wpimath/src/main/native/include/wpi/math/system/NumericalJacobian.hpp index 409c18d488..547d380a91 100644 --- a/wpimath/src/main/native/include/wpi/math/system/NumericalJacobian.hpp +++ b/wpimath/src/main/native/include/wpi/math/system/NumericalJacobian.hpp @@ -6,7 +6,7 @@ #include "wpi/math/linalg/EigenCore.hpp" -namespace frc { +namespace wpi::math { /** * Returns numerical Jacobian with respect to x for f(x). @@ -138,4 +138,4 @@ auto NumericalJacobianU(F&& f, const Eigen::VectorXd& x, [&](const Eigen::VectorXd& u) { return f(x, u, args...); }, u); } -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/system/plant/DCMotor.hpp b/wpimath/src/main/native/include/wpi/math/system/plant/DCMotor.hpp index a8bedb2e34..27e0c757b6 100644 --- a/wpimath/src/main/native/include/wpi/math/system/plant/DCMotor.hpp +++ b/wpimath/src/main/native/include/wpi/math/system/plant/DCMotor.hpp @@ -11,7 +11,7 @@ #include "wpi/units/voltage.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::math { /** * Holds the constants for a DC motor. @@ -19,29 +19,29 @@ namespace frc { class WPILIB_DLLEXPORT DCMotor { public: using radians_per_second_per_volt_t = - units::unit_t>>; + wpi::units::unit_t>>; using newton_meters_per_ampere_t = - units::unit_t>>; + wpi::units::unit_t>>; /// Voltage at which the motor constants were measured. - units::volt_t nominalVoltage; + wpi::units::volt_t nominalVoltage; /// Torque when stalled. - units::newton_meter_t stallTorque; + wpi::units::newton_meter_t stallTorque; /// Current draw when stalled. - units::ampere_t stallCurrent; + wpi::units::ampere_t stallCurrent; /// Current draw under no load. - units::ampere_t freeCurrent; + wpi::units::ampere_t freeCurrent; /// Angular velocity under no load. - units::radians_per_second_t freeSpeed; + wpi::units::radians_per_second_t freeSpeed; /// Motor internal resistance. - units::ohm_t R; + wpi::units::ohm_t R; /// Motor velocity constant. radians_per_second_per_volt_t Kv; @@ -59,10 +59,10 @@ class WPILIB_DLLEXPORT DCMotor { * @param freeSpeed Angular velocity under no load. * @param numMotors Number of motors in a gearbox. */ - constexpr DCMotor(units::volt_t nominalVoltage, - units::newton_meter_t stallTorque, - units::ampere_t stallCurrent, units::ampere_t freeCurrent, - units::radians_per_second_t freeSpeed, int numMotors = 1) + constexpr DCMotor(wpi::units::volt_t nominalVoltage, + wpi::units::newton_meter_t stallTorque, + wpi::units::ampere_t stallCurrent, wpi::units::ampere_t freeCurrent, + wpi::units::radians_per_second_t freeSpeed, int numMotors = 1) : nominalVoltage(nominalVoltage), stallTorque(stallTorque * numMotors), stallCurrent(stallCurrent * numMotors), @@ -78,8 +78,8 @@ class WPILIB_DLLEXPORT DCMotor { * @param speed The current angular velocity of the motor. * @param inputVoltage The voltage being applied to the motor. */ - constexpr units::ampere_t Current(units::radians_per_second_t speed, - units::volt_t inputVoltage) const { + constexpr wpi::units::ampere_t Current(wpi::units::radians_per_second_t speed, + wpi::units::volt_t inputVoltage) const { return -1.0 / Kv / R * speed + 1.0 / R * inputVoltage; } @@ -88,7 +88,7 @@ class WPILIB_DLLEXPORT DCMotor { * * @param torque The torque produced by the motor. */ - constexpr units::ampere_t Current(units::newton_meter_t torque) const { + constexpr wpi::units::ampere_t Current(wpi::units::newton_meter_t torque) const { return torque / Kt; } @@ -97,7 +97,7 @@ class WPILIB_DLLEXPORT DCMotor { * * @param current The current drawn by the motor. */ - constexpr units::newton_meter_t Torque(units::ampere_t current) const { + constexpr wpi::units::newton_meter_t Torque(wpi::units::ampere_t current) const { return current * Kt; } @@ -108,8 +108,8 @@ class WPILIB_DLLEXPORT DCMotor { * @param torque The torque produced by the motor. * @param speed The current angular velocity of the motor. */ - constexpr units::volt_t Voltage(units::newton_meter_t torque, - units::radians_per_second_t speed) const { + constexpr wpi::units::volt_t Voltage(wpi::units::newton_meter_t torque, + wpi::units::radians_per_second_t speed) const { return 1.0 / Kv * speed + 1.0 / Kt * R * torque; } @@ -120,8 +120,8 @@ class WPILIB_DLLEXPORT DCMotor { * @param torque The torque produced by the motor. * @param inputVoltage The input voltage provided to the motor. */ - constexpr units::radians_per_second_t Speed( - units::newton_meter_t torque, units::volt_t inputVoltage) const { + constexpr wpi::units::radians_per_second_t Speed( + wpi::units::newton_meter_t torque, wpi::units::volt_t inputVoltage) const { return inputVoltage * Kv - 1.0 / Kt * torque * R * Kv; } @@ -280,7 +280,7 @@ class WPILIB_DLLEXPORT DCMotor { } }; -} // namespace frc +} // namespace wpi::math #include "wpi/math/system/plant/proto/DCMotorProto.hpp" #include "wpi/math/system/plant/struct/DCMotorStruct.hpp" diff --git a/wpimath/src/main/native/include/wpi/math/system/plant/LinearSystemId.hpp b/wpimath/src/main/native/include/wpi/math/system/plant/LinearSystemId.hpp index e6ab5f70c5..97946cdb80 100644 --- a/wpimath/src/main/native/include/wpi/math/system/plant/LinearSystemId.hpp +++ b/wpimath/src/main/native/include/wpi/math/system/plant/LinearSystemId.hpp @@ -20,20 +20,20 @@ #include "wpi/units/voltage.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::math { /** * Linear system ID utility functions. */ class WPILIB_DLLEXPORT LinearSystemId { public: template - using Velocity_t = units::unit_t< - units::compound_unit>>; + using Velocity_t = wpi::units::unit_t< + wpi::units::compound_unit>>; template - using Acceleration_t = units::unit_t>, - units::inverse>>; + using Acceleration_t = wpi::units::unit_t>, + wpi::units::inverse>>; /** * Create a state-space model of the elevator system. The states of the system @@ -47,8 +47,8 @@ class WPILIB_DLLEXPORT LinearSystemId { * @throws std::domain_error if mass <= 0, radius <= 0, or gearing <= 0. */ static constexpr LinearSystem<2, 1, 2> ElevatorSystem(DCMotor motor, - units::kilogram_t mass, - units::meter_t radius, + wpi::units::kilogram_t mass, + wpi::units::meter_t radius, double gearing) { if (mass <= 0_kg) { throw std::domain_error("mass must be greater than zero."); @@ -63,7 +63,7 @@ class WPILIB_DLLEXPORT LinearSystemId { Matrixd<2, 2> A{ {0.0, 1.0}, {0.0, (-gcem::pow(gearing, 2) * motor.Kt / - (motor.R * units::math::pow<2>(radius) * mass * motor.Kv)) + (motor.R * wpi::units::math::pow<2>(radius) * mass * motor.Kv)) .value()}}; Matrixd<2, 1> B{{0.0}, {(gearing * motor.Kt / (motor.R * radius * mass)).value()}}; @@ -84,7 +84,7 @@ class WPILIB_DLLEXPORT LinearSystemId { * @throws std::domain_error if J <= 0 or gearing <= 0. */ static constexpr LinearSystem<2, 1, 2> SingleJointedArmSystem( - DCMotor motor, units::kilogram_square_meter_t J, double gearing) { + DCMotor motor, wpi::units::kilogram_square_meter_t J, double gearing) { if (J <= 0_kg_sq_m) { throw std::domain_error("J must be greater than zero."); } @@ -125,8 +125,8 @@ class WPILIB_DLLEXPORT LinearSystemId { * href="https://github.com/wpilibsuite/allwpilib/tree/main/sysid">https://github.com/wpilibsuite/allwpilib/tree/main/sysid */ template - requires std::same_as || - std::same_as + requires std::same_as || + std::same_as static constexpr LinearSystem<1, 1, 1> IdentifyVelocitySystem( decltype(1_V / Velocity_t(1)) kV, decltype(1_V / Acceleration_t(1)) kA) { @@ -168,8 +168,8 @@ class WPILIB_DLLEXPORT LinearSystemId { * href="https://github.com/wpilibsuite/allwpilib/tree/main/sysid">https://github.com/wpilibsuite/allwpilib/tree/main/sysid */ template - requires std::same_as || - std::same_as + requires std::same_as || + std::same_as static constexpr LinearSystem<2, 1, 2> IdentifyPositionSystem( decltype(1_V / Velocity_t(1)) kV, decltype(1_V / Acceleration_t(1)) kA) { @@ -274,7 +274,7 @@ class WPILIB_DLLEXPORT LinearSystemId { static constexpr LinearSystem<2, 2, 2> IdentifyDrivetrainSystem( decltype(1_V / 1_mps) kVLinear, decltype(1_V / 1_mps_sq) kALinear, decltype(1_V / 1_rad_per_s) kVAngular, - decltype(1_V / 1_rad_per_s_sq) kAAngular, units::meter_t trackwidth) { + decltype(1_V / 1_rad_per_s_sq) kAAngular, wpi::units::meter_t trackwidth) { if (kVLinear <= decltype(kVLinear){0}) { throw std::domain_error("Kv,linear must be greater than zero."); } @@ -318,7 +318,7 @@ class WPILIB_DLLEXPORT LinearSystemId { * @throws std::domain_error if J <= 0 or gearing <= 0. */ static constexpr LinearSystem<1, 1, 1> FlywheelSystem( - DCMotor motor, units::kilogram_square_meter_t J, double gearing) { + DCMotor motor, wpi::units::kilogram_square_meter_t J, double gearing) { if (J <= 0_kg_sq_m) { throw std::domain_error("J must be greater than zero."); } @@ -349,7 +349,7 @@ class WPILIB_DLLEXPORT LinearSystemId { * href="https://github.com/wpilibsuite/allwpilib/tree/main/sysid">https://github.com/wpilibsuite/allwpilib/tree/main/sysid */ static constexpr LinearSystem<2, 1, 2> DCMotorSystem( - DCMotor motor, units::kilogram_square_meter_t J, double gearing) { + DCMotor motor, wpi::units::kilogram_square_meter_t J, double gearing) { if (J <= 0_kg_sq_m) { throw std::domain_error("J must be greater than zero."); } @@ -390,8 +390,8 @@ class WPILIB_DLLEXPORT LinearSystemId { * @throws std::domain_error if kV < 0 or kA <= 0. */ template - requires std::same_as || - std::same_as + requires std::same_as || + std::same_as static constexpr LinearSystem<2, 1, 2> DCMotorSystem( decltype(1_V / Velocity_t(1)) kV, decltype(1_V / Acceleration_t(1)) kA) { @@ -426,8 +426,8 @@ class WPILIB_DLLEXPORT LinearSystemId { * gearing <= 0. */ static constexpr LinearSystem<2, 2, 2> DrivetrainVelocitySystem( - const DCMotor& motor, units::kilogram_t mass, units::meter_t r, - units::meter_t rb, units::kilogram_square_meter_t J, double gearing) { + const DCMotor& motor, wpi::units::kilogram_t mass, wpi::units::meter_t r, + wpi::units::meter_t rb, wpi::units::kilogram_square_meter_t J, double gearing) { if (mass <= 0_kg) { throw std::domain_error("mass must be greater than zero."); } @@ -445,17 +445,17 @@ class WPILIB_DLLEXPORT LinearSystemId { } auto C1 = -gcem::pow(gearing, 2) * motor.Kt / - (motor.Kv * motor.R * units::math::pow<2>(r)); + (motor.Kv * motor.R * wpi::units::math::pow<2>(r)); auto C2 = gearing * motor.Kt / (motor.R * r); - Matrixd<2, 2> A{{((1 / mass + units::math::pow<2>(rb) / J) * C1).value(), - ((1 / mass - units::math::pow<2>(rb) / J) * C1).value()}, - {((1 / mass - units::math::pow<2>(rb) / J) * C1).value(), - ((1 / mass + units::math::pow<2>(rb) / J) * C1).value()}}; - Matrixd<2, 2> B{{((1 / mass + units::math::pow<2>(rb) / J) * C2).value(), - ((1 / mass - units::math::pow<2>(rb) / J) * C2).value()}, - {((1 / mass - units::math::pow<2>(rb) / J) * C2).value(), - ((1 / mass + units::math::pow<2>(rb) / J) * C2).value()}}; + Matrixd<2, 2> A{{((1 / mass + wpi::units::math::pow<2>(rb) / J) * C1).value(), + ((1 / mass - wpi::units::math::pow<2>(rb) / J) * C1).value()}, + {((1 / mass - wpi::units::math::pow<2>(rb) / J) * C1).value(), + ((1 / mass + wpi::units::math::pow<2>(rb) / J) * C1).value()}}; + Matrixd<2, 2> B{{((1 / mass + wpi::units::math::pow<2>(rb) / J) * C2).value(), + ((1 / mass - wpi::units::math::pow<2>(rb) / J) * C2).value()}, + {((1 / mass - wpi::units::math::pow<2>(rb) / J) * C2).value(), + ((1 / mass + wpi::units::math::pow<2>(rb) / J) * C2).value()}}; Matrixd<2, 2> C{{1.0, 0.0}, {0.0, 1.0}}; Matrixd<2, 2> D{{0.0, 0.0}, {0.0, 0.0}}; @@ -463,4 +463,4 @@ class WPILIB_DLLEXPORT LinearSystemId { } }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/system/plant/proto/DCMotorProto.hpp b/wpimath/src/main/native/include/wpi/math/system/plant/proto/DCMotorProto.hpp index 33ae790a8c..658e08502a 100644 --- a/wpimath/src/main/native/include/wpi/math/system/plant/proto/DCMotorProto.hpp +++ b/wpimath/src/main/native/include/wpi/math/system/plant/proto/DCMotorProto.hpp @@ -10,10 +10,10 @@ #include "wpimath/protobuf/plant.npb.h" template <> -struct WPILIB_DLLEXPORT wpi::Protobuf { +struct WPILIB_DLLEXPORT wpi::util::Protobuf { using MessageStruct = wpi_proto_ProtobufDCMotor; - using InputStream = wpi::ProtoInputStream; - using OutputStream = wpi::ProtoOutputStream; - static std::optional Unpack(InputStream& stream); - static bool Pack(OutputStream& stream, const frc::DCMotor& value); + using InputStream = wpi::util::ProtoInputStream; + using OutputStream = wpi::util::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const wpi::math::DCMotor& value); }; diff --git a/wpimath/src/main/native/include/wpi/math/system/plant/struct/DCMotorStruct.hpp b/wpimath/src/main/native/include/wpi/math/system/plant/struct/DCMotorStruct.hpp index 417c21e2cb..9a502dab81 100644 --- a/wpimath/src/main/native/include/wpi/math/system/plant/struct/DCMotorStruct.hpp +++ b/wpimath/src/main/native/include/wpi/math/system/plant/struct/DCMotorStruct.hpp @@ -9,7 +9,7 @@ #include "wpi/util/struct/Struct.hpp" template <> -struct WPILIB_DLLEXPORT wpi::Struct { +struct WPILIB_DLLEXPORT wpi::util::Struct { static constexpr std::string_view GetTypeName() { return "DCMotor"; } static constexpr size_t GetSize() { return 40; } static constexpr std::string_view GetSchema() { @@ -18,8 +18,8 @@ struct WPILIB_DLLEXPORT wpi::Struct { "free_current;double free_speed"; } - static frc::DCMotor Unpack(std::span data); - static void Pack(std::span data, const frc::DCMotor& value); + static wpi::math::DCMotor Unpack(std::span data); + static void Pack(std::span data, const wpi::math::DCMotor& value); }; -static_assert(wpi::StructSerializable); +static_assert(wpi::util::StructSerializable); diff --git a/wpimath/src/main/native/include/wpi/math/system/proto/LinearSystemProto.hpp b/wpimath/src/main/native/include/wpi/math/system/proto/LinearSystemProto.hpp index cc74931c66..4248371c20 100644 --- a/wpimath/src/main/native/include/wpi/math/system/proto/LinearSystemProto.hpp +++ b/wpimath/src/main/native/include/wpi/math/system/proto/LinearSystemProto.hpp @@ -16,23 +16,23 @@ #include "wpimath/protobuf/system.npb.h" template -struct wpi::Protobuf> { +struct wpi::util::Protobuf> { using MessageStruct = wpi_proto_ProtobufLinearSystem; using InputStream = - wpi::ProtoInputStream>; + wpi::util::ProtoInputStream>; using OutputStream = - wpi::ProtoOutputStream>; + wpi::util::ProtoOutputStream>; - static std::optional> Unpack( + static std::optional> Unpack( InputStream& stream) { - wpi::UnpackCallback> a; - a.SetLimits(wpi::DecodeLimits::Fail); - wpi::UnpackCallback> b; - a.SetLimits(wpi::DecodeLimits::Fail); - wpi::UnpackCallback> c; - a.SetLimits(wpi::DecodeLimits::Fail); - wpi::UnpackCallback> d; - a.SetLimits(wpi::DecodeLimits::Fail); + wpi::util::UnpackCallback> a; + a.SetLimits(wpi::util::DecodeLimits::Fail); + wpi::util::UnpackCallback> b; + a.SetLimits(wpi::util::DecodeLimits::Fail); + wpi::util::UnpackCallback> c; + a.SetLimits(wpi::util::DecodeLimits::Fail); + wpi::util::UnpackCallback> d; + a.SetLimits(wpi::util::DecodeLimits::Fail); wpi_proto_ProtobufLinearSystem msg; msg.a = a.Callback(); @@ -58,7 +58,7 @@ struct wpi::Protobuf> { return {}; } - return frc::LinearSystem{ + return wpi::math::LinearSystem{ std::move(ai[0]), std::move(bi[0]), std::move(ci[0]), @@ -67,11 +67,11 @@ struct wpi::Protobuf> { } static bool Pack(OutputStream& stream, - const frc::LinearSystem& value) { - wpi::PackCallback a{&value.A()}; - wpi::PackCallback b{&value.B()}; - wpi::PackCallback c{&value.C()}; - wpi::PackCallback d{&value.D()}; + const wpi::math::LinearSystem& value) { + wpi::util::PackCallback a{&value.A()}; + wpi::util::PackCallback b{&value.B()}; + wpi::util::PackCallback c{&value.C()}; + wpi::util::PackCallback d{&value.D()}; wpi_proto_ProtobufLinearSystem msg{ .num_states = States, diff --git a/wpimath/src/main/native/include/wpi/math/system/struct/LinearSystemStruct.hpp b/wpimath/src/main/native/include/wpi/math/system/struct/LinearSystemStruct.hpp index ffeff892f9..f0cc59325b 100644 --- a/wpimath/src/main/native/include/wpi/math/system/struct/LinearSystemStruct.hpp +++ b/wpimath/src/main/native/include/wpi/math/system/struct/LinearSystemStruct.hpp @@ -12,66 +12,66 @@ #include "wpi/util/struct/Struct.hpp" template -struct wpi::Struct> { +struct wpi::util::Struct> { static constexpr ct_string kTypeName = - wpi::Concat("LinearSystem__"_ct_string, wpi::NumToCtString(), - "_"_ct_string, wpi::NumToCtString(), "_"_ct_string, - wpi::NumToCtString()); + wpi::util::Concat("LinearSystem__"_ct_string, wpi::util::NumToCtString(), + "_"_ct_string, wpi::util::NumToCtString(), "_"_ct_string, + wpi::util::NumToCtString()); static constexpr std::string_view GetTypeName() { return kTypeName; } static constexpr size_t GetSize() { - return wpi::Struct>::GetSize() + - wpi::Struct>::GetSize() + - wpi::Struct>::GetSize() + - wpi::Struct>::GetSize(); + return wpi::util::Struct>::GetSize() + + wpi::util::Struct>::GetSize() + + wpi::util::Struct>::GetSize() + + wpi::util::Struct>::GetSize(); } - static constexpr ct_string kSchema = wpi::Concat( - wpi::Struct>::kTypeName, " a;"_ct_string, - wpi::Struct>::kTypeName, " b;"_ct_string, - wpi::Struct>::kTypeName, " c;"_ct_string, - wpi::Struct>::kTypeName, " d"_ct_string); + static constexpr ct_string kSchema = wpi::util::Concat( + wpi::util::Struct>::kTypeName, " a;"_ct_string, + wpi::util::Struct>::kTypeName, " b;"_ct_string, + wpi::util::Struct>::kTypeName, " c;"_ct_string, + wpi::util::Struct>::kTypeName, " d"_ct_string); static constexpr std::string_view GetSchema() { return kSchema; } - static frc::LinearSystem Unpack( + static wpi::math::LinearSystem Unpack( std::span data) { constexpr size_t kAOff = 0; constexpr size_t kBOff = - kAOff + wpi::GetStructSize>(); + kAOff + wpi::util::GetStructSize>(); constexpr size_t kCOff = - kBOff + wpi::GetStructSize>(); + kBOff + wpi::util::GetStructSize>(); constexpr size_t kDOff = - kCOff + wpi::GetStructSize>(); - return frc::LinearSystem{ - wpi::UnpackStruct, kAOff>(data), - wpi::UnpackStruct, kBOff>(data), - wpi::UnpackStruct, kCOff>(data), - wpi::UnpackStruct, kDOff>(data)}; + kCOff + wpi::util::GetStructSize>(); + return wpi::math::LinearSystem{ + wpi::util::UnpackStruct, kAOff>(data), + wpi::util::UnpackStruct, kBOff>(data), + wpi::util::UnpackStruct, kCOff>(data), + wpi::util::UnpackStruct, kDOff>(data)}; } static void Pack(std::span data, - const frc::LinearSystem& value) { + const wpi::math::LinearSystem& value) { constexpr size_t kAOff = 0; constexpr size_t kBOff = - kAOff + wpi::GetStructSize>(); + kAOff + wpi::util::GetStructSize>(); constexpr size_t kCOff = - kBOff + wpi::GetStructSize>(); + kBOff + wpi::util::GetStructSize>(); constexpr size_t kDOff = - kCOff + wpi::GetStructSize>(); - wpi::PackStruct(data, value.A()); - wpi::PackStruct(data, value.B()); - wpi::PackStruct(data, value.C()); - wpi::PackStruct(data, value.D()); + kCOff + wpi::util::GetStructSize>(); + wpi::util::PackStruct(data, value.A()); + wpi::util::PackStruct(data, value.B()); + wpi::util::PackStruct(data, value.C()); + wpi::util::PackStruct(data, value.D()); } static void ForEachNested( std::invocable auto fn) { - wpi::ForEachStructSchema>(fn); - wpi::ForEachStructSchema>(fn); - wpi::ForEachStructSchema>(fn); - wpi::ForEachStructSchema>(fn); + wpi::util::ForEachStructSchema>(fn); + wpi::util::ForEachStructSchema>(fn); + wpi::util::ForEachStructSchema>(fn); + wpi::util::ForEachStructSchema>(fn); } }; -static_assert(wpi::StructSerializable>); -static_assert(wpi::HasNestedStruct>); -static_assert(wpi::StructSerializable>); -static_assert(wpi::HasNestedStruct>); +static_assert(wpi::util::StructSerializable>); +static_assert(wpi::util::HasNestedStruct>); +static_assert(wpi::util::StructSerializable>); +static_assert(wpi::util::HasNestedStruct>); diff --git a/wpimath/src/main/native/include/wpi/math/trajectory/ExponentialProfile.hpp b/wpimath/src/main/native/include/wpi/math/trajectory/ExponentialProfile.hpp index 6bd5a846b0..680eb8cd89 100644 --- a/wpimath/src/main/native/include/wpi/math/trajectory/ExponentialProfile.hpp +++ b/wpimath/src/main/native/include/wpi/math/trajectory/ExponentialProfile.hpp @@ -7,7 +7,7 @@ #include "wpi/units/math.hpp" #include "wpi/units/time.hpp" -namespace frc { +namespace wpi::math { /** * A Exponential-shaped velocity profile. @@ -40,20 +40,20 @@ namespace frc { template class ExponentialProfile { public: - using Distance_t = units::unit_t; + using Distance_t = wpi::units::unit_t; using Velocity = - units::compound_unit>; - using Velocity_t = units::unit_t; + wpi::units::compound_unit>; + using Velocity_t = wpi::units::unit_t; using Acceleration = - units::compound_unit>; - using Input_t = units::unit_t; - using A_t = units::unit_t>; + wpi::units::compound_unit>; + using Input_t = wpi::units::unit_t; + using A_t = wpi::units::unit_t>; using B_t = - units::unit_t>>; - using KV = units::compound_unit>; - using kV_t = units::unit_t; - using KA = units::compound_unit>; - using kA_t = units::unit_t; + wpi::units::unit_t>>; + using KV = wpi::units::compound_unit>; + using kV_t = wpi::units::unit_t; + using KA = wpi::units::compound_unit>; + using kA_t = wpi::units::unit_t; /** * Profile timing. @@ -61,10 +61,10 @@ class ExponentialProfile { class ProfileTiming { public: /// Profile inflection time. - units::second_t inflectionTime; + wpi::units::second_t inflectionTime; /// Total profile time. - units::second_t totalTime; + wpi::units::second_t totalTime; /** * Decides if the profile is finished by time t. @@ -72,7 +72,7 @@ class ExponentialProfile { * @param t The time since the beginning of the profile. * @return if the profile is finished at time t. */ - constexpr bool IsFinished(const units::second_t& t) const { + constexpr bool IsFinished(const wpi::units::second_t& t) const { return t >= totalTime; } }; @@ -154,7 +154,7 @@ class ExponentialProfile { * @param goal The desired state when the profile is complete. * @return The position and velocity of the profile at time t. */ - constexpr State Calculate(const units::second_t& t, const State& current, + constexpr State Calculate(const wpi::units::second_t& t, const State& current, const State& goal) const { auto direction = ShouldFlipInput(current, goal) ? -1 : 1; auto u = direction * m_constraints.maxInput; @@ -198,7 +198,7 @@ class ExponentialProfile { * @param goal The desired state when the profile is complete. * @return The total duration of this profile. */ - constexpr units::second_t TimeLeftUntil(const State& current, + constexpr wpi::units::second_t TimeLeftUntil(const State& current, const State& goal) const { auto timing = CalculateProfileTiming(current, goal); @@ -265,9 +265,9 @@ class ExponentialProfile { const State& goal, const Input_t& input) const { auto u = input; - auto u_dir = units::math::abs(u) / u; + auto u_dir = wpi::units::math::abs(u) / u; - units::second_t inflectionT_forward; + wpi::units::second_t inflectionT_forward; // We need to handle 5 cases here: // @@ -281,17 +281,17 @@ class ExponentialProfile { // velocity For cases 2 and 4, we want to add epsilon to the inflection // point velocity. For case 5, we have reached inflection point velocity. auto epsilon = Velocity_t(1e-9); - if (units::math::abs(u_dir * m_constraints.MaxVelocity() - + if (wpi::units::math::abs(u_dir * m_constraints.MaxVelocity() - inflectionPoint.velocity) < epsilon) { auto solvableV = inflectionPoint.velocity; - units::second_t t_to_solvable_v; + wpi::units::second_t t_to_solvable_v; Distance_t x_at_solvable_v; - if (units::math::abs(current.velocity - inflectionPoint.velocity) < + if (wpi::units::math::abs(current.velocity - inflectionPoint.velocity) < epsilon) { t_to_solvable_v = 0_s; x_at_solvable_v = current.position; } else { - if (units::math::abs(current.velocity) > m_constraints.MaxVelocity()) { + if (wpi::units::math::abs(current.velocity) > m_constraints.MaxVelocity()) { solvableV += u_dir * epsilon; } else { solvableV -= u_dir * epsilon; @@ -327,7 +327,7 @@ class ExponentialProfile { * @param initial The initial state. * @return The distance travelled by this profile. */ - constexpr Distance_t ComputeDistanceFromTime(const units::second_t& time, + constexpr Distance_t ComputeDistanceFromTime(const wpi::units::second_t& time, const Input_t& input, const State& initial) const { auto A = m_constraints.A; @@ -336,7 +336,7 @@ class ExponentialProfile { return initial.position + (-B * u * time + - (initial.velocity + B * u / A) * (units::math::exp(A * time) - 1)) / + (initial.velocity + B * u / A) * (wpi::units::math::exp(A * time) - 1)) / A; } @@ -350,14 +350,14 @@ class ExponentialProfile { * @param initial The initial state. * @return The distance travelled by this profile. */ - constexpr Velocity_t ComputeVelocityFromTime(const units::second_t& time, + constexpr Velocity_t ComputeVelocityFromTime(const wpi::units::second_t& time, const Input_t& input, const State& initial) const { auto A = m_constraints.A; auto B = m_constraints.B; auto u = input; - return (initial.velocity + B * u / A) * units::math::exp(A * time) - + return (initial.velocity + B * u / A) * wpi::units::math::exp(A * time) - B * u / A; } @@ -371,14 +371,14 @@ class ExponentialProfile { * @param initial The initial velocity. * @return The time required to reach the goal velocity. */ - constexpr units::second_t ComputeTimeFromVelocity( + constexpr wpi::units::second_t ComputeTimeFromVelocity( const Velocity_t& velocity, const Input_t& input, const Velocity_t& initial) const { auto A = m_constraints.A; auto B = m_constraints.B; auto u = input; - return units::math::log((A * velocity + B * u) / (A * initial + B * u)) / A; + return wpi::units::math::log((A * velocity + B * u) / (A * initial + B * u)) / A; } /** @@ -400,7 +400,7 @@ class ExponentialProfile { return initial.position + (velocity - initial.velocity) / A - B * u / (A * A) * - units::math::log((A * velocity + B * u) / + wpi::units::math::log((A * velocity + B * u) / (A * initial.velocity + B * u)); } @@ -421,7 +421,7 @@ class ExponentialProfile { auto B = m_constraints.B; auto u = input; - auto u_dir = u / units::math::abs(u); + auto u_dir = u / wpi::units::math::abs(u); auto position_delta = goal.position - current.position; auto velocity_delta = goal.velocity - current.velocity; @@ -430,7 +430,7 @@ class ExponentialProfile { auto power = -A / B / u * (A * position_delta - velocity_delta); auto a = -A * A; - auto c = B * B * u * u + scalar * units::math::exp(power); + auto c = B * B * u * u + scalar * wpi::units::math::exp(power); if (-1e-9 < c.value() && c.value() < 0) { // numeric instability - the heuristic gets it right but c is around @@ -438,7 +438,7 @@ class ExponentialProfile { return Velocity_t(0); } - return u_dir * units::math::sqrt(-c / a); + return u_dir * wpi::units::math::sqrt(-c / a); } /** @@ -480,4 +480,4 @@ class ExponentialProfile { Constraints m_constraints; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/trajectory/Trajectory.hpp b/wpimath/src/main/native/include/wpi/math/trajectory/Trajectory.hpp index db9f48141e..b9f1f78fbc 100644 --- a/wpimath/src/main/native/include/wpi/math/trajectory/Trajectory.hpp +++ b/wpimath/src/main/native/include/wpi/math/trajectory/Trajectory.hpp @@ -19,7 +19,7 @@ #include "wpi/util/SymbolExports.hpp" #include "wpi/util/json_fwd.hpp" -namespace frc { +namespace wpi::math { /** * Represents a time-parameterized trajectory. The trajectory contains of * various States that represent the pose, curvature, time elapsed, velocity, @@ -32,19 +32,19 @@ class WPILIB_DLLEXPORT Trajectory { */ struct WPILIB_DLLEXPORT State { /// The time elapsed since the beginning of the trajectory. - units::second_t t = 0_s; + wpi::units::second_t t = 0_s; /// The speed at that point of the trajectory. - units::meters_per_second_t velocity = 0_mps; + wpi::units::meters_per_second_t velocity = 0_mps; /// The acceleration at that point of the trajectory. - units::meters_per_second_squared_t acceleration = 0_mps_sq; + wpi::units::meters_per_second_squared_t acceleration = 0_mps_sq; /// The pose at that point of the trajectory. Pose2d pose; /// The curvature at that point of the trajectory. - units::curvature_t curvature{0.0}; + wpi::units::curvature_t curvature{0.0}; /** * Checks equality between this State and another object. @@ -61,7 +61,7 @@ class WPILIB_DLLEXPORT Trajectory { */ constexpr State Interpolate(State endValue, double i) const { // Find the new [t] value. - const auto newT = wpi::Lerp(t, endValue.t, i); + const auto newT = wpi::util::Lerp(t, endValue.t, i); // Find the delta time between the current state and the interpolated // state. @@ -75,16 +75,16 @@ class WPILIB_DLLEXPORT Trajectory { // Check whether the robot is reversing at this stage. const auto reversing = velocity < 0_mps || - (units::math::abs(velocity) < 1E-9_mps && acceleration < 0_mps_sq); + (wpi::units::math::abs(velocity) < 1E-9_mps && acceleration < 0_mps_sq); // Calculate the new velocity. // v = v_0 + at - const units::meters_per_second_t newV = + const wpi::units::meters_per_second_t newV = velocity + (acceleration * deltaT); // Calculate the change in position. // delta_s = v_0 t + 0.5at² - const units::meter_t newS = + const wpi::units::meter_t newS = (velocity * deltaT + 0.5 * acceleration * deltaT * deltaT) * (reversing ? -1.0 : 1.0); @@ -96,8 +96,8 @@ class WPILIB_DLLEXPORT Trajectory { newS / endValue.pose.Translation().Distance(pose.Translation()); return {newT, newV, acceleration, - wpi::Lerp(pose, endValue.pose, interpolationFrac), - wpi::Lerp(curvature, endValue.curvature, interpolationFrac)}; + wpi::util::Lerp(pose, endValue.pose, interpolationFrac), + wpi::util::Lerp(curvature, endValue.curvature, interpolationFrac)}; } }; @@ -121,7 +121,7 @@ class WPILIB_DLLEXPORT Trajectory { * Returns the overall duration of the trajectory. * @return The duration of the trajectory. */ - units::second_t TotalTime() const { return m_totalTime; } + wpi::units::second_t TotalTime() const { return m_totalTime; } /** * Return the states of the trajectory. @@ -137,7 +137,7 @@ class WPILIB_DLLEXPORT Trajectory { * @return The state at that point in time. * @throws std::runtime_error if the trajectory has no states. */ - State Sample(units::second_t t) const { + State Sample(wpi::units::second_t t) const { if (m_states.empty()) { throw std::runtime_error( "Trajectory cannot be sampled if it has no states."); @@ -165,7 +165,7 @@ class WPILIB_DLLEXPORT Trajectory { // want. // If the difference in states is negligible, then we are spot on! - if (units::math::abs(sample->t - prevSample->t) < 1E-9_s) { + if (wpi::units::math::abs(sample->t - prevSample->t) < 1E-9_s) { return *sample; } // Interpolate between the two states for the state that we want. @@ -260,16 +260,16 @@ class WPILIB_DLLEXPORT Trajectory { private: std::vector m_states; - units::second_t m_totalTime = 0_s; + wpi::units::second_t m_totalTime = 0_s; }; WPILIB_DLLEXPORT -void to_json(wpi::json& json, const Trajectory::State& state); +void to_json(wpi::util::json& json, const Trajectory::State& state); WPILIB_DLLEXPORT -void from_json(const wpi::json& json, Trajectory::State& state); +void from_json(const wpi::util::json& json, Trajectory::State& state); -} // namespace frc +} // namespace wpi::math #include "wpi/math/trajectory/proto/TrajectoryProto.hpp" #include "wpi/math/trajectory/proto/TrajectoryStateProto.hpp" diff --git a/wpimath/src/main/native/include/wpi/math/trajectory/TrajectoryConfig.hpp b/wpimath/src/main/native/include/wpi/math/trajectory/TrajectoryConfig.hpp index 6662ad97cf..ca59dfd39b 100644 --- a/wpimath/src/main/native/include/wpi/math/trajectory/TrajectoryConfig.hpp +++ b/wpimath/src/main/native/include/wpi/math/trajectory/TrajectoryConfig.hpp @@ -20,7 +20,7 @@ #include "wpi/units/velocity.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::math { /** * Represents the configuration for generating a trajectory. This class stores * the start velocity, end velocity, max velocity, max acceleration, custom @@ -38,8 +38,8 @@ class WPILIB_DLLEXPORT TrajectoryConfig { * @param maxVelocity The max velocity of the trajectory. * @param maxAcceleration The max acceleration of the trajectory. */ - TrajectoryConfig(units::meters_per_second_t maxVelocity, - units::meters_per_second_squared_t maxAcceleration) + TrajectoryConfig(wpi::units::meters_per_second_t maxVelocity, + wpi::units::meters_per_second_squared_t maxAcceleration) : m_maxVelocity(maxVelocity), m_maxAcceleration(maxAcceleration) {} TrajectoryConfig(const TrajectoryConfig&) = delete; @@ -52,7 +52,7 @@ class WPILIB_DLLEXPORT TrajectoryConfig { * Sets the start velocity of the trajectory. * @param startVelocity The start velocity of the trajectory. */ - void SetStartVelocity(units::meters_per_second_t startVelocity) { + void SetStartVelocity(wpi::units::meters_per_second_t startVelocity) { m_startVelocity = startVelocity; } @@ -60,7 +60,7 @@ class WPILIB_DLLEXPORT TrajectoryConfig { * Sets the end velocity of the trajectory. * @param endVelocity The end velocity of the trajectory. */ - void SetEndVelocity(units::meters_per_second_t endVelocity) { + void SetEndVelocity(wpi::units::meters_per_second_t endVelocity) { m_endVelocity = endVelocity; } @@ -115,25 +115,25 @@ class WPILIB_DLLEXPORT TrajectoryConfig { * Returns the starting velocity of the trajectory. * @return The starting velocity of the trajectory. */ - units::meters_per_second_t StartVelocity() const { return m_startVelocity; } + wpi::units::meters_per_second_t StartVelocity() const { return m_startVelocity; } /** * Returns the ending velocity of the trajectory. * @return The ending velocity of the trajectory. */ - units::meters_per_second_t EndVelocity() const { return m_endVelocity; } + wpi::units::meters_per_second_t EndVelocity() const { return m_endVelocity; } /** * Returns the maximum velocity of the trajectory. * @return The maximum velocity of the trajectory. */ - units::meters_per_second_t MaxVelocity() const { return m_maxVelocity; } + wpi::units::meters_per_second_t MaxVelocity() const { return m_maxVelocity; } /** * Returns the maximum acceleration of the trajectory. * @return The maximum acceleration of the trajectory. */ - units::meters_per_second_squared_t MaxAcceleration() const { + wpi::units::meters_per_second_squared_t MaxAcceleration() const { return m_maxAcceleration; } @@ -153,11 +153,11 @@ class WPILIB_DLLEXPORT TrajectoryConfig { bool IsReversed() const { return m_reversed; } private: - units::meters_per_second_t m_startVelocity = 0_mps; - units::meters_per_second_t m_endVelocity = 0_mps; - units::meters_per_second_t m_maxVelocity; - units::meters_per_second_squared_t m_maxAcceleration; + wpi::units::meters_per_second_t m_startVelocity = 0_mps; + wpi::units::meters_per_second_t m_endVelocity = 0_mps; + wpi::units::meters_per_second_t m_maxVelocity; + wpi::units::meters_per_second_squared_t m_maxAcceleration; std::vector> m_constraints; bool m_reversed = false; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/trajectory/TrajectoryGenerator.hpp b/wpimath/src/main/native/include/wpi/math/trajectory/TrajectoryGenerator.hpp index 446eb6e5ed..5e7ea6ead3 100644 --- a/wpimath/src/main/native/include/wpi/math/trajectory/TrajectoryGenerator.hpp +++ b/wpimath/src/main/native/include/wpi/math/trajectory/TrajectoryGenerator.hpp @@ -16,13 +16,13 @@ #include "wpi/math/trajectory/constraint/TrajectoryConstraint.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::math { /** * Helper class used to generate trajectories with various constraints. */ class WPILIB_DLLEXPORT TrajectoryGenerator { public: - using PoseWithCurvature = std::pair; + using PoseWithCurvature = std::pair; /** * Generates a trajectory from the given control vectors and config. This @@ -126,4 +126,4 @@ class WPILIB_DLLEXPORT TrajectoryGenerator { static const Trajectory kDoNothingTrajectory; static std::function s_errorFunc; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/trajectory/TrajectoryParameterizer.hpp b/wpimath/src/main/native/include/wpi/math/trajectory/TrajectoryParameterizer.hpp index 6adfd4785e..3633154d86 100644 --- a/wpimath/src/main/native/include/wpi/math/trajectory/TrajectoryParameterizer.hpp +++ b/wpimath/src/main/native/include/wpi/math/trajectory/TrajectoryParameterizer.hpp @@ -36,13 +36,13 @@ #include "wpi/math/trajectory/constraint/TrajectoryConstraint.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::math { /** * Class used to parameterize a trajectory by time. */ class WPILIB_DLLEXPORT TrajectoryParameterizer { public: - using PoseWithCurvature = std::pair; + using PoseWithCurvature = std::pair; /** * Parameterize the trajectory by time. This is where the velocity profile is @@ -66,10 +66,10 @@ class WPILIB_DLLEXPORT TrajectoryParameterizer { static Trajectory TimeParameterizeTrajectory( const std::vector& points, const std::vector>& constraints, - units::meters_per_second_t startVelocity, - units::meters_per_second_t endVelocity, - units::meters_per_second_t maxVelocity, - units::meters_per_second_squared_t maxAcceleration, bool reversed); + wpi::units::meters_per_second_t startVelocity, + wpi::units::meters_per_second_t endVelocity, + wpi::units::meters_per_second_t maxVelocity, + wpi::units::meters_per_second_squared_t maxAcceleration, bool reversed); private: constexpr static double kEpsilon = 1E-6; @@ -80,11 +80,11 @@ class WPILIB_DLLEXPORT TrajectoryParameterizer { * the trajectory, max velocity, min acceleration and max acceleration. */ struct ConstrainedState { - PoseWithCurvature pose = {Pose2d{}, units::curvature_t{0.0}}; - units::meter_t distance = 0_m; - units::meters_per_second_t maxVelocity = 0_mps; - units::meters_per_second_squared_t minAcceleration = 0_mps_sq; - units::meters_per_second_squared_t maxAcceleration = 0_mps_sq; + PoseWithCurvature pose = {Pose2d{}, wpi::units::curvature_t{0.0}}; + wpi::units::meter_t distance = 0_m; + wpi::units::meters_per_second_t maxVelocity = 0_mps; + wpi::units::meters_per_second_squared_t minAcceleration = 0_mps_sq; + wpi::units::meters_per_second_squared_t maxAcceleration = 0_mps_sq; }; /** @@ -102,4 +102,4 @@ class WPILIB_DLLEXPORT TrajectoryParameterizer { const std::vector>& constraints, ConstrainedState* state); }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/trajectory/TrapezoidProfile.hpp b/wpimath/src/main/native/include/wpi/math/trajectory/TrapezoidProfile.hpp index 69bb5bc647..f9bab77972 100644 --- a/wpimath/src/main/native/include/wpi/math/trajectory/TrapezoidProfile.hpp +++ b/wpimath/src/main/native/include/wpi/math/trajectory/TrapezoidProfile.hpp @@ -10,7 +10,7 @@ #include "wpi/units/math.hpp" #include "wpi/units/time.hpp" -namespace frc { +namespace wpi::math { /** * A trapezoid-shaped velocity profile. @@ -45,13 +45,13 @@ namespace frc { template class TrapezoidProfile { public: - using Distance_t = units::unit_t; + using Distance_t = wpi::units::unit_t; using Velocity = - units::compound_unit>; - using Velocity_t = units::unit_t; + wpi::units::compound_unit>; + using Velocity_t = wpi::units::unit_t; using Acceleration = - units::compound_unit>; - using Acceleration_t = units::unit_t; + wpi::units::compound_unit>; + using Acceleration_t = wpi::units::unit_t; /** * Profile constraints. @@ -129,24 +129,24 @@ class TrapezoidProfile { * @param goal The desired state when the profile is complete. * @return The position and velocity of the profile at time t. */ - constexpr State Calculate(units::second_t t, State current, State goal) { + constexpr State Calculate(wpi::units::second_t t, State current, State goal) { m_direction = ShouldFlipAcceleration(current, goal) ? -1 : 1; m_current = Direct(current); goal = Direct(goal); - if (units::math::abs(m_current.velocity) > m_constraints.maxVelocity) { + if (wpi::units::math::abs(m_current.velocity) > m_constraints.maxVelocity) { m_current.velocity = - units::math::copysign(m_constraints.maxVelocity, m_current.velocity); + wpi::units::math::copysign(m_constraints.maxVelocity, m_current.velocity); } // Deal with a possibly truncated motion profile (with nonzero initial or // final velocity) by calculating the parameters as if the profile began and // ended at zero velocity - units::second_t cutoffBegin = + wpi::units::second_t cutoffBegin = m_current.velocity / m_constraints.maxAcceleration; Distance_t cutoffDistBegin = cutoffBegin * cutoffBegin * m_constraints.maxAcceleration / 2.0; - units::second_t cutoffEnd = goal.velocity / m_constraints.maxAcceleration; + wpi::units::second_t cutoffEnd = goal.velocity / m_constraints.maxAcceleration; Distance_t cutoffDistEnd = cutoffEnd * cutoffEnd * m_constraints.maxAcceleration / 2.0; @@ -155,7 +155,7 @@ class TrapezoidProfile { Distance_t fullTrapezoidDist = cutoffDistBegin + (goal.position - m_current.position) + cutoffDistEnd; - units::second_t accelerationTime = + wpi::units::second_t accelerationTime = m_constraints.maxVelocity / m_constraints.maxAcceleration; Distance_t fullSpeedDist = @@ -165,7 +165,7 @@ class TrapezoidProfile { // Handle the case where the profile never reaches full speed if (fullSpeedDist < Distance_t{0}) { accelerationTime = - units::math::sqrt(fullTrapezoidDist / m_constraints.maxAcceleration); + wpi::units::math::sqrt(fullTrapezoidDist / m_constraints.maxAcceleration); fullSpeedDist = Distance_t{0}; } @@ -187,7 +187,7 @@ class TrapezoidProfile { } else if (t <= m_endDecel) { result.velocity = goal.velocity + (m_endDecel - t) * m_constraints.maxAcceleration; - units::second_t timeLeft = m_endDecel - t; + wpi::units::second_t timeLeft = m_endDecel - t; result.position = goal.position - (goal.velocity + timeLeft * m_constraints.maxAcceleration / 2.0) * @@ -206,12 +206,12 @@ class TrapezoidProfile { * @return The time left until a target distance in the profile is reached, or * zero if no goal was set. */ - constexpr units::second_t TimeLeftUntil(Distance_t target) const { + constexpr wpi::units::second_t TimeLeftUntil(Distance_t target) const { Distance_t position = m_current.position * m_direction; Velocity_t velocity = m_current.velocity * m_direction; - units::second_t endAccel = m_endAccel * m_direction; - units::second_t endFullSpeed = m_endFullSpeed * m_direction - endAccel; + wpi::units::second_t endAccel = m_endAccel * m_direction; + wpi::units::second_t endFullSpeed = m_endFullSpeed * m_direction - endAccel; if (target < position) { endAccel *= -1.0; @@ -219,13 +219,13 @@ class TrapezoidProfile { velocity *= -1.0; } - endAccel = units::math::max(endAccel, 0_s); - endFullSpeed = units::math::max(endFullSpeed, 0_s); + endAccel = wpi::units::math::max(endAccel, 0_s); + endFullSpeed = wpi::units::math::max(endFullSpeed, 0_s); const Acceleration_t acceleration = m_constraints.maxAcceleration; const Acceleration_t deceleration = -m_constraints.maxAcceleration; - Distance_t distToTarget = units::math::abs(target - position); + Distance_t distToTarget = wpi::units::math::abs(target - position); if (distToTarget < Distance_t{1e-6}) { return 0_s; @@ -236,8 +236,8 @@ class TrapezoidProfile { Velocity_t decelVelocity; if (endAccel > 0_s) { - decelVelocity = units::math::sqrt( - units::math::abs(velocity * velocity + 2 * acceleration * accelDist)); + decelVelocity = wpi::units::math::sqrt( + wpi::units::math::abs(velocity * velocity + 2 * acceleration * accelDist)); } else { decelVelocity = velocity; } @@ -256,18 +256,18 @@ class TrapezoidProfile { decelDist = distToTarget - fullSpeedDist - accelDist; } - units::second_t accelTime = - (-velocity + units::math::sqrt(units::math::abs( + wpi::units::second_t accelTime = + (-velocity + wpi::units::math::sqrt(wpi::units::math::abs( velocity * velocity + 2 * acceleration * accelDist))) / acceleration; - units::second_t decelTime = + wpi::units::second_t decelTime = (-decelVelocity + - units::math::sqrt(units::math::abs(decelVelocity * decelVelocity + + wpi::units::math::sqrt(wpi::units::math::abs(decelVelocity * decelVelocity + 2 * deceleration * decelDist))) / deceleration; - units::second_t fullSpeedTime = fullSpeedDist / m_constraints.maxVelocity; + wpi::units::second_t fullSpeedTime = fullSpeedDist / m_constraints.maxVelocity; return accelTime + fullSpeedTime + decelTime; } @@ -278,7 +278,7 @@ class TrapezoidProfile { * @return The total time the profile takes to reach the goal, or zero if no * goal was set. */ - constexpr units::second_t TotalTime() const { return m_endDecel; } + constexpr wpi::units::second_t TotalTime() const { return m_endDecel; } /** * Returns true if the profile has reached the goal. @@ -289,7 +289,7 @@ class TrapezoidProfile { * @param t The time since the beginning of the profile. * @return True if the profile has reached the goal. */ - constexpr bool IsFinished(units::second_t t) const { + constexpr bool IsFinished(wpi::units::second_t t) const { return t >= TotalTime(); } @@ -321,9 +321,9 @@ class TrapezoidProfile { Constraints m_constraints; State m_current; - units::second_t m_endAccel = 0_s; - units::second_t m_endFullSpeed = 0_s; - units::second_t m_endDecel = 0_s; + wpi::units::second_t m_endAccel = 0_s; + wpi::units::second_t m_endFullSpeed = 0_s; + wpi::units::second_t m_endDecel = 0_s; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/trajectory/constraint/CentripetalAccelerationConstraint.hpp b/wpimath/src/main/native/include/wpi/math/trajectory/constraint/CentripetalAccelerationConstraint.hpp index 3dbf3a8d22..ed4eacd980 100644 --- a/wpimath/src/main/native/include/wpi/math/trajectory/constraint/CentripetalAccelerationConstraint.hpp +++ b/wpimath/src/main/native/include/wpi/math/trajectory/constraint/CentripetalAccelerationConstraint.hpp @@ -11,7 +11,7 @@ #include "wpi/units/velocity.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::math { /** * A constraint on the maximum absolute centripetal acceleration allowed when @@ -26,12 +26,12 @@ class WPILIB_DLLEXPORT CentripetalAccelerationConstraint : public TrajectoryConstraint { public: constexpr explicit CentripetalAccelerationConstraint( - units::meters_per_second_squared_t maxCentripetalAcceleration) + wpi::units::meters_per_second_squared_t maxCentripetalAcceleration) : m_maxCentripetalAcceleration(maxCentripetalAcceleration) {} - constexpr units::meters_per_second_t MaxVelocity( - const Pose2d& pose, units::curvature_t curvature, - units::meters_per_second_t velocity) const override { + constexpr wpi::units::meters_per_second_t MaxVelocity( + const Pose2d& pose, wpi::units::curvature_t curvature, + wpi::units::meters_per_second_t velocity) const override { // ac = v²/r // k (curvature) = 1/r @@ -42,19 +42,19 @@ class WPILIB_DLLEXPORT CentripetalAccelerationConstraint // We have to multiply by 1_rad here to get the units to cancel out nicely. // The units library defines a unit for radians although it is technically // unitless. - return units::math::sqrt(m_maxCentripetalAcceleration / - units::math::abs(curvature) * 1_rad); + return wpi::units::math::sqrt(m_maxCentripetalAcceleration / + wpi::units::math::abs(curvature) * 1_rad); } constexpr MinMax MinMaxAcceleration( - const Pose2d& pose, units::curvature_t curvature, - units::meters_per_second_t speed) const override { + const Pose2d& pose, wpi::units::curvature_t curvature, + wpi::units::meters_per_second_t speed) const override { // The acceleration of the robot has no impact on the centripetal // acceleration of the robot. return {}; } private: - units::meters_per_second_squared_t m_maxCentripetalAcceleration; + wpi::units::meters_per_second_squared_t m_maxCentripetalAcceleration; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/trajectory/constraint/DifferentialDriveKinematicsConstraint.hpp b/wpimath/src/main/native/include/wpi/math/trajectory/constraint/DifferentialDriveKinematicsConstraint.hpp index 38f03bc8ee..83d4c67283 100644 --- a/wpimath/src/main/native/include/wpi/math/trajectory/constraint/DifferentialDriveKinematicsConstraint.hpp +++ b/wpimath/src/main/native/include/wpi/math/trajectory/constraint/DifferentialDriveKinematicsConstraint.hpp @@ -11,7 +11,7 @@ #include "wpi/units/velocity.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::math { /** * A class that enforces constraints on the differential drive kinematics. * This can be used to ensure that the trajectory is constructed so that the @@ -23,12 +23,12 @@ class WPILIB_DLLEXPORT DifferentialDriveKinematicsConstraint public: constexpr DifferentialDriveKinematicsConstraint( DifferentialDriveKinematics kinematics, - units::meters_per_second_t maxSpeed) + wpi::units::meters_per_second_t maxSpeed) : m_kinematics(std::move(kinematics)), m_maxSpeed(maxSpeed) {} - constexpr units::meters_per_second_t MaxVelocity( - const Pose2d& pose, units::curvature_t curvature, - units::meters_per_second_t velocity) const override { + constexpr wpi::units::meters_per_second_t MaxVelocity( + const Pose2d& pose, wpi::units::curvature_t curvature, + wpi::units::meters_per_second_t velocity) const override { auto wheelSpeeds = m_kinematics.ToWheelSpeeds({velocity, 0_mps, velocity * curvature}); wheelSpeeds.Desaturate(m_maxSpeed); @@ -37,13 +37,13 @@ class WPILIB_DLLEXPORT DifferentialDriveKinematicsConstraint } constexpr MinMax MinMaxAcceleration( - const Pose2d& pose, units::curvature_t curvature, - units::meters_per_second_t speed) const override { + const Pose2d& pose, wpi::units::curvature_t curvature, + wpi::units::meters_per_second_t speed) const override { return {}; } private: DifferentialDriveKinematics m_kinematics; - units::meters_per_second_t m_maxSpeed; + wpi::units::meters_per_second_t m_maxSpeed; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/trajectory/constraint/DifferentialDriveVoltageConstraint.hpp b/wpimath/src/main/native/include/wpi/math/trajectory/constraint/DifferentialDriveVoltageConstraint.hpp index cf0c23a182..e70208867e 100644 --- a/wpimath/src/main/native/include/wpi/math/trajectory/constraint/DifferentialDriveVoltageConstraint.hpp +++ b/wpimath/src/main/native/include/wpi/math/trajectory/constraint/DifferentialDriveVoltageConstraint.hpp @@ -17,7 +17,7 @@ #include "wpi/util/MathExtras.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::math { /** * A class that enforces constraints on differential drive voltage expenditure * based on the motor dynamics and the drive kinematics. Ensures that the @@ -38,21 +38,21 @@ class WPILIB_DLLEXPORT DifferentialDriveVoltageConstraint * voltage (12V) to account for "voltage sag" due to current draw. */ constexpr DifferentialDriveVoltageConstraint( - const SimpleMotorFeedforward& feedforward, - DifferentialDriveKinematics kinematics, units::volt_t maxVoltage) + const SimpleMotorFeedforward& feedforward, + DifferentialDriveKinematics kinematics, wpi::units::volt_t maxVoltage) : m_feedforward(feedforward), m_kinematics(std::move(kinematics)), m_maxVoltage(maxVoltage) {} - constexpr units::meters_per_second_t MaxVelocity( - const Pose2d& pose, units::curvature_t curvature, - units::meters_per_second_t velocity) const override { - return units::meters_per_second_t{std::numeric_limits::max()}; + constexpr wpi::units::meters_per_second_t MaxVelocity( + const Pose2d& pose, wpi::units::curvature_t curvature, + wpi::units::meters_per_second_t velocity) const override { + return wpi::units::meters_per_second_t{std::numeric_limits::max()}; } constexpr MinMax MinMaxAcceleration( - const Pose2d& pose, units::curvature_t curvature, - units::meters_per_second_t speed) const override { + const Pose2d& pose, wpi::units::curvature_t curvature, + wpi::units::meters_per_second_t speed) const override { auto wheelSpeeds = m_kinematics.ToWheelSpeeds({speed, 0_mps, speed * curvature}); @@ -83,25 +83,25 @@ class WPILIB_DLLEXPORT DifferentialDriveVoltageConstraint // case, as it breaks the signum function. Both max and min acceleration // are *reduced in magnitude* in this case. - units::meters_per_second_squared_t maxChassisAcceleration; - units::meters_per_second_squared_t minChassisAcceleration; + wpi::units::meters_per_second_squared_t maxChassisAcceleration; + wpi::units::meters_per_second_squared_t minChassisAcceleration; if (speed == 0_mps) { maxChassisAcceleration = maxWheelAcceleration / - (1 + m_kinematics.trackwidth * units::math::abs(curvature) / (2_rad)); + (1 + m_kinematics.trackwidth * wpi::units::math::abs(curvature) / (2_rad)); minChassisAcceleration = minWheelAcceleration / - (1 + m_kinematics.trackwidth * units::math::abs(curvature) / (2_rad)); + (1 + m_kinematics.trackwidth * wpi::units::math::abs(curvature) / (2_rad)); } else { maxChassisAcceleration = maxWheelAcceleration / - (1 + m_kinematics.trackwidth * units::math::abs(curvature) * - wpi::sgn(speed) / (2_rad)); + (1 + m_kinematics.trackwidth * wpi::units::math::abs(curvature) * + wpi::util::sgn(speed) / (2_rad)); minChassisAcceleration = minWheelAcceleration / - (1 - m_kinematics.trackwidth * units::math::abs(curvature) * - wpi::sgn(speed) / (2_rad)); + (1 - m_kinematics.trackwidth * wpi::units::math::abs(curvature) * + wpi::util::sgn(speed) / (2_rad)); } // When turning about a point inside of the wheelbase (i.e. radius less than @@ -110,7 +110,7 @@ class WPILIB_DLLEXPORT DifferentialDriveVoltageConstraint // wheel when this happens. We can accurately account for this by simply // negating the inner wheel. - if ((m_kinematics.trackwidth / 2) > 1_rad / units::math::abs(curvature)) { + if ((m_kinematics.trackwidth / 2) > 1_rad / wpi::units::math::abs(curvature)) { if (speed > 0_mps) { minChassisAcceleration = -minChassisAcceleration; } else if (speed < 0_mps) { @@ -122,8 +122,8 @@ class WPILIB_DLLEXPORT DifferentialDriveVoltageConstraint } private: - SimpleMotorFeedforward m_feedforward; + SimpleMotorFeedforward m_feedforward; DifferentialDriveKinematics m_kinematics; - units::volt_t m_maxVoltage; + wpi::units::volt_t m_maxVoltage; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/trajectory/constraint/EllipticalRegionConstraint.hpp b/wpimath/src/main/native/include/wpi/math/trajectory/constraint/EllipticalRegionConstraint.hpp index 61e3b2d38b..084711b75b 100644 --- a/wpimath/src/main/native/include/wpi/math/trajectory/constraint/EllipticalRegionConstraint.hpp +++ b/wpimath/src/main/native/include/wpi/math/trajectory/constraint/EllipticalRegionConstraint.hpp @@ -13,7 +13,7 @@ #include "wpi/math/trajectory/constraint/TrajectoryConstraint.hpp" #include "wpi/units/length.hpp" -namespace frc { +namespace wpi::math { /** * Enforces a particular constraint only within an elliptical region. @@ -34,8 +34,8 @@ class EllipticalRegionConstraint : public TrajectoryConstraint { */ [[deprecated("Use constructor taking Ellipse2d instead.")]] constexpr EllipticalRegionConstraint(const Translation2d& center, - units::meter_t xWidth, - units::meter_t yWidth, + wpi::units::meter_t xWidth, + wpi::units::meter_t yWidth, const Rotation2d& rotation, const Constraint& constraint) : m_ellipse{Pose2d{center, rotation}, xWidth / 2.0, yWidth / 2.0}, @@ -52,20 +52,20 @@ class EllipticalRegionConstraint : public TrajectoryConstraint { const Constraint& constraint) : m_ellipse{ellipse}, m_constraint{constraint} {} - constexpr units::meters_per_second_t MaxVelocity( - const Pose2d& pose, units::curvature_t curvature, - units::meters_per_second_t velocity) const override { + constexpr wpi::units::meters_per_second_t MaxVelocity( + const Pose2d& pose, wpi::units::curvature_t curvature, + wpi::units::meters_per_second_t velocity) const override { if (m_ellipse.Contains(pose.Translation())) { return m_constraint.MaxVelocity(pose, curvature, velocity); } else { - return units::meters_per_second_t{ + return wpi::units::meters_per_second_t{ std::numeric_limits::infinity()}; } } constexpr MinMax MinMaxAcceleration( - const Pose2d& pose, units::curvature_t curvature, - units::meters_per_second_t speed) const override { + const Pose2d& pose, wpi::units::curvature_t curvature, + wpi::units::meters_per_second_t speed) const override { if (m_ellipse.Contains(pose.Translation())) { return m_constraint.MinMaxAcceleration(pose, curvature, speed); } else { @@ -78,4 +78,4 @@ class EllipticalRegionConstraint : public TrajectoryConstraint { Constraint m_constraint; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/trajectory/constraint/MaxVelocityConstraint.hpp b/wpimath/src/main/native/include/wpi/math/trajectory/constraint/MaxVelocityConstraint.hpp index 37e71cff78..3e8b1ee14b 100644 --- a/wpimath/src/main/native/include/wpi/math/trajectory/constraint/MaxVelocityConstraint.hpp +++ b/wpimath/src/main/native/include/wpi/math/trajectory/constraint/MaxVelocityConstraint.hpp @@ -9,7 +9,7 @@ #include "wpi/units/velocity.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::math { /** * Represents a constraint that enforces a max velocity. This can be composed @@ -24,23 +24,23 @@ class WPILIB_DLLEXPORT MaxVelocityConstraint : public TrajectoryConstraint { * @param maxVelocity The max velocity. */ constexpr explicit MaxVelocityConstraint( - units::meters_per_second_t maxVelocity) - : m_maxVelocity(units::math::abs(maxVelocity)) {} + wpi::units::meters_per_second_t maxVelocity) + : m_maxVelocity(wpi::units::math::abs(maxVelocity)) {} - constexpr units::meters_per_second_t MaxVelocity( - const Pose2d& pose, units::curvature_t curvature, - units::meters_per_second_t velocity) const override { + constexpr wpi::units::meters_per_second_t MaxVelocity( + const Pose2d& pose, wpi::units::curvature_t curvature, + wpi::units::meters_per_second_t velocity) const override { return m_maxVelocity; } constexpr MinMax MinMaxAcceleration( - const Pose2d& pose, units::curvature_t curvature, - units::meters_per_second_t speed) const override { + const Pose2d& pose, wpi::units::curvature_t curvature, + wpi::units::meters_per_second_t speed) const override { return {}; } private: - units::meters_per_second_t m_maxVelocity; + wpi::units::meters_per_second_t m_maxVelocity; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/trajectory/constraint/MecanumDriveKinematicsConstraint.hpp b/wpimath/src/main/native/include/wpi/math/trajectory/constraint/MecanumDriveKinematicsConstraint.hpp index 5f191e4ece..12de9c43f9 100644 --- a/wpimath/src/main/native/include/wpi/math/trajectory/constraint/MecanumDriveKinematicsConstraint.hpp +++ b/wpimath/src/main/native/include/wpi/math/trajectory/constraint/MecanumDriveKinematicsConstraint.hpp @@ -12,7 +12,7 @@ #include "wpi/units/velocity.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::math { /** * A class that enforces constraints on the mecanum drive kinematics. * This can be used to ensure that the trajectory is constructed so that the @@ -23,12 +23,12 @@ class WPILIB_DLLEXPORT MecanumDriveKinematicsConstraint : public TrajectoryConstraint { public: MecanumDriveKinematicsConstraint(const MecanumDriveKinematics& kinematics, - units::meters_per_second_t maxSpeed) + wpi::units::meters_per_second_t maxSpeed) : m_kinematics(kinematics), m_maxSpeed(maxSpeed) {} - units::meters_per_second_t MaxVelocity( - const Pose2d& pose, units::curvature_t curvature, - units::meters_per_second_t velocity) const override { + wpi::units::meters_per_second_t MaxVelocity( + const Pose2d& pose, wpi::units::curvature_t curvature, + wpi::units::meters_per_second_t velocity) const override { auto xVelocity = velocity * pose.Rotation().Cos(); auto yVelocity = velocity * pose.Rotation().Sin(); auto wheelSpeeds = @@ -37,16 +37,16 @@ class WPILIB_DLLEXPORT MecanumDriveKinematicsConstraint auto normSpeeds = m_kinematics.ToChassisSpeeds(wheelSpeeds); - return units::math::hypot(normSpeeds.vx, normSpeeds.vy); + return wpi::units::math::hypot(normSpeeds.vx, normSpeeds.vy); } - MinMax MinMaxAcceleration(const Pose2d& pose, units::curvature_t curvature, - units::meters_per_second_t speed) const override { + MinMax MinMaxAcceleration(const Pose2d& pose, wpi::units::curvature_t curvature, + wpi::units::meters_per_second_t speed) const override { return {}; } private: MecanumDriveKinematics m_kinematics; - units::meters_per_second_t m_maxSpeed; + wpi::units::meters_per_second_t m_maxSpeed; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/trajectory/constraint/RectangularRegionConstraint.hpp b/wpimath/src/main/native/include/wpi/math/trajectory/constraint/RectangularRegionConstraint.hpp index 78e374c329..cc65cee1ba 100644 --- a/wpimath/src/main/native/include/wpi/math/trajectory/constraint/RectangularRegionConstraint.hpp +++ b/wpimath/src/main/native/include/wpi/math/trajectory/constraint/RectangularRegionConstraint.hpp @@ -11,7 +11,7 @@ #include "wpi/math/geometry/Translation2d.hpp" #include "wpi/math/trajectory/constraint/TrajectoryConstraint.hpp" -namespace frc { +namespace wpi::math { /** * Enforces a particular constraint only within a rectangular region. @@ -47,20 +47,20 @@ class RectangularRegionConstraint : public TrajectoryConstraint { const Constraint& constraint) : m_rectangle{rectangle}, m_constraint{constraint} {} - constexpr units::meters_per_second_t MaxVelocity( - const Pose2d& pose, units::curvature_t curvature, - units::meters_per_second_t velocity) const override { + constexpr wpi::units::meters_per_second_t MaxVelocity( + const Pose2d& pose, wpi::units::curvature_t curvature, + wpi::units::meters_per_second_t velocity) const override { if (m_rectangle.Contains(pose.Translation())) { return m_constraint.MaxVelocity(pose, curvature, velocity); } else { - return units::meters_per_second_t{ + return wpi::units::meters_per_second_t{ std::numeric_limits::infinity()}; } } constexpr MinMax MinMaxAcceleration( - const Pose2d& pose, units::curvature_t curvature, - units::meters_per_second_t speed) const override { + const Pose2d& pose, wpi::units::curvature_t curvature, + wpi::units::meters_per_second_t speed) const override { if (m_rectangle.Contains(pose.Translation())) { return m_constraint.MinMaxAcceleration(pose, curvature, speed); } else { @@ -73,4 +73,4 @@ class RectangularRegionConstraint : public TrajectoryConstraint { Constraint m_constraint; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/trajectory/constraint/SwerveDriveKinematicsConstraint.hpp b/wpimath/src/main/native/include/wpi/math/trajectory/constraint/SwerveDriveKinematicsConstraint.hpp index ea8113efb5..23386789a8 100644 --- a/wpimath/src/main/native/include/wpi/math/trajectory/constraint/SwerveDriveKinematicsConstraint.hpp +++ b/wpimath/src/main/native/include/wpi/math/trajectory/constraint/SwerveDriveKinematicsConstraint.hpp @@ -11,7 +11,7 @@ #include "wpi/units/math.hpp" #include "wpi/units/velocity.hpp" -namespace frc { +namespace wpi::math { /** * A class that enforces constraints on the swerve drive kinematics. @@ -22,13 +22,13 @@ template class SwerveDriveKinematicsConstraint : public TrajectoryConstraint { public: SwerveDriveKinematicsConstraint( - const frc::SwerveDriveKinematics& kinematics, - units::meters_per_second_t maxSpeed) + const wpi::math::SwerveDriveKinematics& kinematics, + wpi::units::meters_per_second_t maxSpeed) : m_kinematics(kinematics), m_maxSpeed(maxSpeed) {} - units::meters_per_second_t MaxVelocity( - const Pose2d& pose, units::curvature_t curvature, - units::meters_per_second_t velocity) const override { + wpi::units::meters_per_second_t MaxVelocity( + const Pose2d& pose, wpi::units::curvature_t curvature, + wpi::units::meters_per_second_t velocity) const override { auto xVelocity = velocity * pose.Rotation().Cos(); auto yVelocity = velocity * pose.Rotation().Sin(); auto wheelSpeeds = m_kinematics.ToSwerveModuleStates( @@ -37,17 +37,17 @@ class SwerveDriveKinematicsConstraint : public TrajectoryConstraint { auto normSpeeds = m_kinematics.ToChassisSpeeds(wheelSpeeds); - return units::math::hypot(normSpeeds.vx, normSpeeds.vy); + return wpi::units::math::hypot(normSpeeds.vx, normSpeeds.vy); } - MinMax MinMaxAcceleration(const Pose2d& pose, units::curvature_t curvature, - units::meters_per_second_t speed) const override { + MinMax MinMaxAcceleration(const Pose2d& pose, wpi::units::curvature_t curvature, + wpi::units::meters_per_second_t speed) const override { return {}; } private: - frc::SwerveDriveKinematics m_kinematics; - units::meters_per_second_t m_maxSpeed; + wpi::math::SwerveDriveKinematics m_kinematics; + wpi::units::meters_per_second_t m_maxSpeed; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/trajectory/constraint/TrajectoryConstraint.hpp b/wpimath/src/main/native/include/wpi/math/trajectory/constraint/TrajectoryConstraint.hpp index 17db36c8b9..d39cf3650f 100644 --- a/wpimath/src/main/native/include/wpi/math/trajectory/constraint/TrajectoryConstraint.hpp +++ b/wpimath/src/main/native/include/wpi/math/trajectory/constraint/TrajectoryConstraint.hpp @@ -12,7 +12,7 @@ #include "wpi/units/velocity.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::math { /** * An interface for defining user-defined velocity and acceleration constraints * while generating trajectories. @@ -37,13 +37,13 @@ class WPILIB_DLLEXPORT TrajectoryConstraint { /** * The minimum acceleration. */ - units::meters_per_second_squared_t minAcceleration{ + wpi::units::meters_per_second_squared_t minAcceleration{ -std::numeric_limits::max()}; /** * The maximum acceleration. */ - units::meters_per_second_squared_t maxAcceleration{ + wpi::units::meters_per_second_squared_t maxAcceleration{ std::numeric_limits::max()}; }; @@ -57,9 +57,9 @@ class WPILIB_DLLEXPORT TrajectoryConstraint { * * @return The absolute maximum velocity. */ - constexpr virtual units::meters_per_second_t MaxVelocity( - const Pose2d& pose, units::curvature_t curvature, - units::meters_per_second_t velocity) const = 0; + constexpr virtual wpi::units::meters_per_second_t MaxVelocity( + const Pose2d& pose, wpi::units::curvature_t curvature, + wpi::units::meters_per_second_t velocity) const = 0; /** * Returns the minimum and maximum allowable acceleration for the trajectory @@ -72,7 +72,7 @@ class WPILIB_DLLEXPORT TrajectoryConstraint { * @return The min and max acceleration bounds. */ constexpr virtual MinMax MinMaxAcceleration( - const Pose2d& pose, units::curvature_t curvature, - units::meters_per_second_t speed) const = 0; + const Pose2d& pose, wpi::units::curvature_t curvature, + wpi::units::meters_per_second_t speed) const = 0; }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/trajectory/proto/TrajectoryProto.hpp b/wpimath/src/main/native/include/wpi/math/trajectory/proto/TrajectoryProto.hpp index fad9868bd2..e9cf424531 100644 --- a/wpimath/src/main/native/include/wpi/math/trajectory/proto/TrajectoryProto.hpp +++ b/wpimath/src/main/native/include/wpi/math/trajectory/proto/TrajectoryProto.hpp @@ -10,10 +10,10 @@ #include "wpimath/protobuf/trajectory.npb.h" template <> -struct WPILIB_DLLEXPORT wpi::Protobuf { +struct WPILIB_DLLEXPORT wpi::util::Protobuf { using MessageStruct = wpi_proto_ProtobufTrajectory; - using InputStream = wpi::ProtoInputStream; - using OutputStream = wpi::ProtoOutputStream; - static std::optional Unpack(InputStream& stream); - static bool Pack(OutputStream& stream, const frc::Trajectory& value); + using InputStream = wpi::util::ProtoInputStream; + using OutputStream = wpi::util::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const wpi::math::Trajectory& value); }; diff --git a/wpimath/src/main/native/include/wpi/math/trajectory/proto/TrajectoryStateProto.hpp b/wpimath/src/main/native/include/wpi/math/trajectory/proto/TrajectoryStateProto.hpp index 680a63073b..c9a2e89080 100644 --- a/wpimath/src/main/native/include/wpi/math/trajectory/proto/TrajectoryStateProto.hpp +++ b/wpimath/src/main/native/include/wpi/math/trajectory/proto/TrajectoryStateProto.hpp @@ -10,10 +10,10 @@ #include "wpimath/protobuf/trajectory.npb.h" template <> -struct WPILIB_DLLEXPORT wpi::Protobuf { +struct WPILIB_DLLEXPORT wpi::util::Protobuf { using MessageStruct = wpi_proto_ProtobufTrajectoryState; - using InputStream = wpi::ProtoInputStream; - using OutputStream = wpi::ProtoOutputStream; - static std::optional Unpack(InputStream& stream); - static bool Pack(OutputStream& stream, const frc::Trajectory::State& value); + using InputStream = wpi::util::ProtoInputStream; + using OutputStream = wpi::util::ProtoOutputStream; + static std::optional Unpack(InputStream& stream); + static bool Pack(OutputStream& stream, const wpi::math::Trajectory::State& value); }; diff --git a/wpimath/src/main/native/include/wpi/math/util/ComputerVisionUtil.hpp b/wpimath/src/main/native/include/wpi/math/util/ComputerVisionUtil.hpp index 596952aff1..3f3d598307 100644 --- a/wpimath/src/main/native/include/wpi/math/util/ComputerVisionUtil.hpp +++ b/wpimath/src/main/native/include/wpi/math/util/ComputerVisionUtil.hpp @@ -8,7 +8,7 @@ #include "wpi/math/geometry/Transform3d.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::math { /** * Returns the robot's pose in the field coordinate system given an object's @@ -25,16 +25,16 @@ namespace frc { * pose. This can either be a constant for a rigidly mounted camera, or * variable if the camera is mounted to a turret. If the camera was mounted 3 * inches in front of the "origin" (usually physical center) of the robot, - * this would be frc::Transform3d{3_in, 0_in, 0_in, frc::Rotation3d{}}. + * this would be wpi::math::Transform3d{3_in, 0_in, 0_in, wpi::math::Rotation3d{}}. * @return The robot's field-relative pose. */ WPILIB_DLLEXPORT -constexpr frc::Pose3d ObjectToRobotPose(const frc::Pose3d& objectInField, - const frc::Transform3d& cameraToObject, - const frc::Transform3d& robotToCamera) { +constexpr wpi::math::Pose3d ObjectToRobotPose(const wpi::math::Pose3d& objectInField, + const wpi::math::Transform3d& cameraToObject, + const wpi::math::Transform3d& robotToCamera) { const auto objectToCamera = cameraToObject.Inverse(); const auto cameraToRobot = robotToCamera.Inverse(); return objectInField + objectToCamera + cameraToRobot; } -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/util/MathShared.hpp b/wpimath/src/main/native/include/wpi/math/util/MathShared.hpp index 97fb39b8d5..0c33730f7c 100644 --- a/wpimath/src/main/native/include/wpi/math/util/MathShared.hpp +++ b/wpimath/src/main/native/include/wpi/math/util/MathShared.hpp @@ -21,7 +21,7 @@ class WPILIB_DLLEXPORT MathShared { fmt::format_args args) = 0; virtual void ReportUsage(std::string_view resource, std::string_view data) = 0; - virtual units::second_t GetTimestamp() = 0; + virtual wpi::units::second_t GetTimestamp() = 0; template inline void ReportError(const S& format, Args&&... args) { @@ -62,7 +62,7 @@ class WPILIB_DLLEXPORT MathSharedStore { GetMathShared().ReportUsage(resource, data); } - static units::second_t GetTimestamp() { + static wpi::units::second_t GetTimestamp() { return GetMathShared().GetTimestamp(); } }; diff --git a/wpimath/src/main/native/include/wpi/math/util/MathUtil.hpp b/wpimath/src/main/native/include/wpi/math/util/MathUtil.hpp index c32807aa4b..a04e2c35ff 100644 --- a/wpimath/src/main/native/include/wpi/math/util/MathUtil.hpp +++ b/wpimath/src/main/native/include/wpi/math/util/MathUtil.hpp @@ -20,7 +20,7 @@ #include "wpi/units/velocity.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::math { /** * Returns 0.0 if the given value is within the specified range around zero. The @@ -34,13 +34,13 @@ namespace frc { * @return The value after the deadband is applied. */ template - requires std::is_arithmetic_v || units::traits::is_unit_t_v + requires std::is_arithmetic_v || wpi::units::traits::is_unit_t_v constexpr T ApplyDeadband(T value, T deadband, T maxMagnitude = T{1.0}) { T magnitude; if constexpr (std::is_arithmetic_v) { magnitude = gcem::abs(value); } else { - magnitude = units::math::abs(value); + magnitude = wpi::units::math::abs(value); } if (magnitude < deadband) { @@ -106,7 +106,7 @@ constexpr T ApplyDeadband(T value, T deadband, T maxMagnitude = T{1.0}) { * @return The value after the deadband is applied. */ template - requires std::is_arithmetic_v || units::traits::is_unit_t_v + requires std::is_arithmetic_v || wpi::units::traits::is_unit_t_v Eigen::Vector ApplyDeadband(const Eigen::Vector& value, T deadband, T maxMagnitude = T{1.0}) { if constexpr (std::is_arithmetic_v) { @@ -142,7 +142,7 @@ Eigen::Vector ApplyDeadband(const Eigen::Vector& value, T deadband, * range. */ template - requires std::is_arithmetic_v || units::traits::is_unit_t_v + requires std::is_arithmetic_v || wpi::units::traits::is_unit_t_v constexpr T CopyDirectionPow(T value, double exponent, T maxMagnitude = T{1.0}) { if constexpr (std::is_arithmetic_v) { @@ -150,8 +150,8 @@ constexpr T CopyDirectionPow(T value, double exponent, gcem::pow(gcem::abs(value) / maxMagnitude, exponent) * maxMagnitude, value); } else { - return units::math::copysign( - gcem::pow((units::math::abs(value) / maxMagnitude).value(), exponent) * + return wpi::units::math::copysign( + gcem::pow((wpi::units::math::abs(value) / maxMagnitude).value(), exponent) * maxMagnitude, value); } @@ -176,7 +176,7 @@ constexpr T CopyDirectionPow(T value, double exponent, * the input range. */ template - requires std::is_arithmetic_v || units::traits::is_unit_t_v + requires std::is_arithmetic_v || wpi::units::traits::is_unit_t_v Eigen::Vector CopyDirectionPow(const Eigen::Vector& value, double exponent, T maxMagnitude = T{1.0}) { if constexpr (std::is_arithmetic_v) { @@ -226,12 +226,12 @@ constexpr T InputModulus(T input, T minimumInput, T maximumInput) { * @return Whether or not the actual value is within the allowed tolerance */ template - requires std::is_arithmetic_v || units::traits::is_unit_t_v + requires std::is_arithmetic_v || wpi::units::traits::is_unit_t_v constexpr bool IsNear(T expected, T actual, T tolerance) { if constexpr (std::is_arithmetic_v) { return std::abs(expected - actual) < tolerance; } else { - return units::math::abs(expected - actual) < tolerance; + return wpi::units::math::abs(expected - actual) < tolerance; } } @@ -255,15 +255,15 @@ constexpr bool IsNear(T expected, T actual, T tolerance) { * @return Whether or not the actual value is within the allowed tolerance */ template - requires std::is_arithmetic_v || units::traits::is_unit_t_v + requires std::is_arithmetic_v || wpi::units::traits::is_unit_t_v constexpr bool IsNear(T expected, T actual, T tolerance, T min, T max) { T errorBound = (max - min) / 2.0; - T error = frc::InputModulus(expected - actual, -errorBound, errorBound); + T error = wpi::math::InputModulus(expected - actual, -errorBound, errorBound); if constexpr (std::is_arithmetic_v) { return std::abs(error) < tolerance; } else { - return units::math::abs(error) < tolerance; + return wpi::units::math::abs(error) < tolerance; } } @@ -273,10 +273,10 @@ constexpr bool IsNear(T expected, T actual, T tolerance, T min, T max) { * @param angle Angle to wrap. */ WPILIB_DLLEXPORT -constexpr units::radian_t AngleModulus(units::radian_t angle) { - return InputModulus(angle, - units::radian_t{-std::numbers::pi}, - units::radian_t{std::numbers::pi}); +constexpr wpi::units::radian_t AngleModulus(wpi::units::radian_t angle) { + return InputModulus(angle, + wpi::units::radian_t{-std::numbers::pi}, + wpi::units::radian_t{std::numbers::pi}); } // floorDiv and floorMod algorithms taken from Java @@ -328,15 +328,15 @@ constexpr std::signed_integral auto FloorMod(std::signed_integral auto x, */ constexpr Translation2d SlewRateLimit(const Translation2d& current, const Translation2d& next, - units::second_t dt, - units::meters_per_second_t maxVelocity) { + wpi::units::second_t dt, + wpi::units::meters_per_second_t maxVelocity) { if (maxVelocity < 0_mps) { wpi::math::MathSharedStore::ReportError( "maxVelocity must be a non-negative number, got {}!", maxVelocity); return next; } Translation2d diff = next - current; - units::meter_t dist = diff.Norm(); + wpi::units::meter_t dist = diff.Norm(); if (dist < 1e-9_m) { return next; } @@ -359,15 +359,15 @@ constexpr Translation2d SlewRateLimit(const Translation2d& current, */ constexpr Translation3d SlewRateLimit(const Translation3d& current, const Translation3d& next, - units::second_t dt, - units::meters_per_second_t maxVelocity) { + wpi::units::second_t dt, + wpi::units::meters_per_second_t maxVelocity) { if (maxVelocity < 0_mps) { wpi::math::MathSharedStore::ReportError( "maxVelocity must be a non-negative number, got {}!", maxVelocity); return next; } Translation3d diff = next - current; - units::meter_t dist = diff.Norm(); + wpi::units::meter_t dist = diff.Norm(); if (dist < 1e-9_m) { return next; } @@ -379,4 +379,4 @@ constexpr Translation3d SlewRateLimit(const Translation3d& current, return next; } -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/math/util/StateSpaceUtil.hpp b/wpimath/src/main/native/include/wpi/math/util/StateSpaceUtil.hpp index 9268f09090..76563bac95 100644 --- a/wpimath/src/main/native/include/wpi/math/util/StateSpaceUtil.hpp +++ b/wpimath/src/main/native/include/wpi/math/util/StateSpaceUtil.hpp @@ -18,7 +18,7 @@ #include "wpi/util/Algorithm.hpp" #include "wpi/util/SymbolExports.hpp" -namespace frc { +namespace wpi::math { /** * Creates a cost matrix from the given vector for use with LQR. @@ -46,7 +46,7 @@ constexpr Matrixd MakeCostMatrix( } } - wpi::for_each( + wpi::util::for_each( [&](int i, double tolerance) { if (tolerance == std::numeric_limits::infinity()) { result(i, i) = 0.0; @@ -83,7 +83,7 @@ constexpr Matrixd MakeCovMatrix(Ts... stdDevs) { } } - wpi::for_each([&](int i, double stdDev) { result(i, i) = stdDev * stdDev; }, + wpi::util::for_each([&](int i, double stdDev) { result(i, i) = stdDev * stdDev; }, stdDevs...); return result; @@ -189,7 +189,7 @@ Vectord MakeWhiteNoiseVector(Ts... stdDevs) { std::mt19937 gen{rd()}; Vectord result; - wpi::for_each( + wpi::util::for_each( [&](int i, double stdDev) { // Passing a standard deviation of 0.0 to std::normal_distribution is // undefined behavior @@ -422,4 +422,4 @@ extern template WPILIB_DLLEXPORT Eigen::VectorXd DesaturateInputVector(const Eigen::VectorXd& u, double maxMagnitude); -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/main/native/include/wpi/units/acceleration.hpp b/wpimath/src/main/native/include/wpi/units/acceleration.hpp index 27b41a8583..b6057e5d54 100644 --- a/wpimath/src/main/native/include/wpi/units/acceleration.hpp +++ b/wpimath/src/main/native/include/wpi/units/acceleration.hpp @@ -30,9 +30,9 @@ #include "wpi/units/length.hpp" #include "wpi/units/time.hpp" -namespace units { +namespace wpi::units { /** - * @namespace units::acceleration + * @namespace wpi::units::acceleration * @brief namespace for unit types and containers representing acceleration * values * @details The SI unit for acceleration is `meters_per_second_squared`, and the @@ -43,7 +43,7 @@ namespace units { #if !defined(DISABLE_PREDEFINED_UNITS) || \ defined(ENABLE_PREDEFINED_ACCELERATION_UNITS) UNIT_ADD(acceleration, meters_per_second_squared, meters_per_second_squared, - mps_sq, unit, units::category::acceleration_unit>) + mps_sq, unit, wpi::units::category::acceleration_unit>) UNIT_ADD(acceleration, feet_per_second_squared, feet_per_second_squared, fps_sq, compound_unit>>) UNIT_ADD(acceleration, standard_gravity, standard_gravity, SG, @@ -53,4 +53,4 @@ UNIT_ADD_CATEGORY_TRAIT(acceleration) #endif using namespace acceleration; -} // namespace units +} // namespace wpi::units diff --git a/wpimath/src/main/native/include/wpi/units/angle.hpp b/wpimath/src/main/native/include/wpi/units/angle.hpp index 200991eba7..9e1c46e690 100644 --- a/wpimath/src/main/native/include/wpi/units/angle.hpp +++ b/wpimath/src/main/native/include/wpi/units/angle.hpp @@ -28,9 +28,9 @@ #include "wpi/units/base.hpp" -namespace units { +namespace wpi::units { /** - * @namespace units::angle + * @namespace wpi::units::angle * @brief namespace for unit types and containers representing angle values * @details The SI unit for angle is `radians`, and the corresponding * `base_unit` category is`angle_unit`. @@ -39,7 +39,7 @@ namespace units { */ #if !defined(DISABLE_PREDEFINED_UNITS) || defined(ENABLE_PREDEFINED_ANGLE_UNITS) UNIT_ADD_WITH_METRIC_PREFIXES(angle, radian, radians, rad, - unit, units::category::angle_unit>) + unit, wpi::units::category::angle_unit>) UNIT_ADD(angle, degree, degrees, deg, unit, radians, std::ratio<1>>) UNIT_ADD(angle, arcminute, arcminutes, arcmin, unit, degrees>) @@ -53,4 +53,4 @@ UNIT_ADD_CATEGORY_TRAIT(angle) #endif using namespace angle; -} // namespace units +} // namespace wpi::units diff --git a/wpimath/src/main/native/include/wpi/units/angular_acceleration.hpp b/wpimath/src/main/native/include/wpi/units/angular_acceleration.hpp index 0493b6e27c..b5cd4e7ed5 100644 --- a/wpimath/src/main/native/include/wpi/units/angular_acceleration.hpp +++ b/wpimath/src/main/native/include/wpi/units/angular_acceleration.hpp @@ -8,9 +8,9 @@ #include "wpi/units/base.hpp" #include "wpi/units/time.hpp" -namespace units { +namespace wpi::units { /** - * @namespace units::angular_acceleration + * @namespace wpi::units::angular_acceleration * @brief namespace for unit types and containers representing angular * acceleration values * @details The SI unit for angular acceleration is @@ -21,7 +21,7 @@ namespace units { */ UNIT_ADD(angular_acceleration, radians_per_second_squared, radians_per_second_squared, rad_per_s_sq, - unit, units::category::angular_acceleration_unit>) + unit, wpi::units::category::angular_acceleration_unit>) UNIT_ADD(angular_acceleration, degrees_per_second_squared, degrees_per_second_squared, deg_per_s_sq, compound_unit>>) @@ -39,4 +39,4 @@ UNIT_ADD(angular_acceleration, revolutions_per_minute_per_second, UNIT_ADD_CATEGORY_TRAIT(angular_acceleration) using namespace angular_acceleration; -} // namespace units +} // namespace wpi::units diff --git a/wpimath/src/main/native/include/wpi/units/angular_jerk.hpp b/wpimath/src/main/native/include/wpi/units/angular_jerk.hpp index 4c82d71532..b9387cddb5 100644 --- a/wpimath/src/main/native/include/wpi/units/angular_jerk.hpp +++ b/wpimath/src/main/native/include/wpi/units/angular_jerk.hpp @@ -8,9 +8,9 @@ #include "wpi/units/base.hpp" #include "wpi/units/time.hpp" -namespace units { +namespace wpi::units { /** - * @namespace units::angular_jerk + * @namespace wpi::units::angular_jerk * @brief namespace for unit types and containers representing angular * jerk values * @details The SI unit for angular jerk is @@ -20,7 +20,7 @@ namespace units { * @sa See unit_t for more information on unit type containers. */ UNIT_ADD(angular_jerk, radians_per_second_cubed, radians_per_second_cubed, - rad_per_s_cu, unit, units::category::angular_jerk_unit>) + rad_per_s_cu, unit, wpi::units::category::angular_jerk_unit>) UNIT_ADD(angular_jerk, degrees_per_second_cubed, degrees_per_second_cubed, deg_per_s_cu, compound_unit>>) @@ -31,4 +31,4 @@ UNIT_ADD(angular_jerk, turns_per_second_cubed, turns_per_second_cubed, UNIT_ADD_CATEGORY_TRAIT(angular_jerk) using namespace angular_jerk; -} // namespace units +} // namespace wpi::units diff --git a/wpimath/src/main/native/include/wpi/units/angular_velocity.hpp b/wpimath/src/main/native/include/wpi/units/angular_velocity.hpp index 694481d283..518cc45b26 100644 --- a/wpimath/src/main/native/include/wpi/units/angular_velocity.hpp +++ b/wpimath/src/main/native/include/wpi/units/angular_velocity.hpp @@ -30,9 +30,9 @@ #include "wpi/units/base.hpp" #include "wpi/units/time.hpp" -namespace units { +namespace wpi::units { /** - * @namespace units::angular_velocity + * @namespace wpi::units::angular_velocity * @brief namespace for unit types and containers representing angular velocity * values * @details The SI unit for angular velocity is `radians_per_second`, and the @@ -43,7 +43,7 @@ namespace units { #if !defined(DISABLE_PREDEFINED_UNITS) || \ defined(ENABLE_PREDEFINED_ANGULAR_VELOCITY_UNITS) UNIT_ADD(angular_velocity, radians_per_second, radians_per_second, rad_per_s, - unit, units::category::angular_velocity_unit>) + unit, wpi::units::category::angular_velocity_unit>) UNIT_ADD(angular_velocity, degrees_per_second, degrees_per_second, deg_per_s, compound_unit>) UNIT_ADD(angular_velocity, turns_per_second, turns_per_second, tps, @@ -57,4 +57,4 @@ UNIT_ADD_CATEGORY_TRAIT(angular_velocity) #endif using namespace angular_velocity; -} // namespace units +} // namespace wpi::units diff --git a/wpimath/src/main/native/include/wpi/units/area.hpp b/wpimath/src/main/native/include/wpi/units/area.hpp index ae9f0b22e8..85ccbfec87 100644 --- a/wpimath/src/main/native/include/wpi/units/area.hpp +++ b/wpimath/src/main/native/include/wpi/units/area.hpp @@ -29,9 +29,9 @@ #include "wpi/units/base.hpp" #include "wpi/units/length.hpp" -namespace units { +namespace wpi::units { /** - * @namespace units::area + * @namespace wpi::units::area * @brief namespace for unit types and containers representing area values * @details The SI unit for area is `square_meters`, and the corresponding * `base_unit` category is `area_unit`. @@ -40,7 +40,7 @@ namespace units { */ #if !defined(DISABLE_PREDEFINED_UNITS) || defined(ENABLE_PREDEFINED_AREA_UNITS) UNIT_ADD(area, square_meter, square_meters, sq_m, - unit, units::category::area_unit>) + unit, wpi::units::category::area_unit>) UNIT_ADD(area, square_foot, square_feet, sq_ft, squared) UNIT_ADD(area, square_inch, square_inches, sq_in, squared) UNIT_ADD(area, square_mile, square_miles, sq_mi, squared) @@ -53,4 +53,4 @@ UNIT_ADD_CATEGORY_TRAIT(area) #endif using namespace area; -} // namespace units +} // namespace wpi::units diff --git a/wpimath/src/main/native/include/wpi/units/base.hpp b/wpimath/src/main/native/include/wpi/units/base.hpp index 30ae5c29c0..009d340b36 100644 --- a/wpimath/src/main/native/include/wpi/units/base.hpp +++ b/wpimath/src/main/native/include/wpi/units/base.hpp @@ -87,7 +87,7 @@ // STRING FORMATTER //------------------------------ -namespace units +namespace wpi::units { namespace detail { @@ -107,7 +107,7 @@ namespace units } } -namespace units +namespace wpi::units { template constexpr const char* name(const T&); template constexpr const char* abbreviation(const T&); @@ -128,7 +128,7 @@ namespace units * @param namePlural - plural version of the unit name, e.g. 'meters' * @param abbreviation - abbreviated unit name, e.g. 'm' * @param definition - the variadic parameter is used for the definition of the unit - * (e.g. `unit, units::category::length_unit>`) + * (e.g. `unit, wpi::units::category::length_unit>`) * @note a variadic template is used for the definition to allow templates with * commas to be easily expanded. All the variadic 'arguments' should together * comprise the unit definition. @@ -181,12 +181,12 @@ namespace units #define UNIT_ADD_IO(namespaceName, nameSingular, abbrev)\ }\ template <>\ - struct fmt::formatter \ + struct fmt::formatter \ : fmt::formatter \ {\ template \ auto format(\ - const units::namespaceName::nameSingular ## _t& obj,\ + const wpi::units::namespaceName::nameSingular ## _t& obj,\ FmtContext& ctx) const\ {\ auto out = ctx.out();\ @@ -194,13 +194,13 @@ namespace units return fmt::format_to(out, " " #abbrev);\ }\ };\ - namespace units\ + namespace wpi::units\ {\ namespace namespaceName\ {\ inline std::string to_string(const nameSingular ## _t& obj)\ {\ - return units::detail::to_string(obj()) + std::string(" "#abbrev);\ + return wpi::units::detail::to_string(obj()) + std::string(" "#abbrev);\ }\ } #elif defined(UNIT_LIB_ENABLE_IOSTREAM) @@ -213,7 +213,7 @@ namespace units }\ inline std::string to_string(const nameSingular ## _t& obj)\ {\ - return units::detail::to_string(obj()) + std::string(" "#abbrev);\ + return wpi::units::detail::to_string(obj()) + std::string(" "#abbrev);\ }\ } #else @@ -226,7 +226,7 @@ namespace units * @details The macro generates names for units. E.g. name() of 1_m would be "meter", and * abbreviation would be "m". * @param namespaceName namespace in which the new units will be encapsulated. All literal values - * are placed in the `units::literals` namespace. + * are placed in the `wpi::units::literals` namespace. * @param nameSingular singular version of the unit name, e.g. 'meter' * @param abbreviation - abbreviated unit name, e.g. 'm' */ @@ -246,7 +246,7 @@ template<> constexpr const char* abbreviation(const namespaceName::nameSingular * @details The macro generates user-defined literals for units. A literal suffix is created * using the abbreviation (e.g. `10.0_m`). * @param namespaceName namespace in which the new units will be encapsulated. All literal values - * are placed in the `units::literals` namespace. + * are placed in the `wpi::units::literals` namespace. * @param nameSingular singular version of the unit name, e.g. 'meter' * @param abbreviation - abbreviated unit name, e.g. 'm' * @note When UNIT_HAS_LITERAL_SUPPORT is not defined, the macro does not generate any code @@ -277,12 +277,12 @@ template<> constexpr const char* abbreviation(const namespaceName::nameSingular * using the abbreviation (e.g. `10.0_m`). It also defines a class-specific * cout function which prints both the value and abbreviation of the unit when invoked. * @param namespaceName namespace in which the new units will be encapsulated. All literal values - * are placed in the `units::literals` namespace. + * are placed in the `wpi::units::literals` namespace. * @param nameSingular singular version of the unit name, e.g. 'meter' * @param namePlural - plural version of the unit name, e.g. 'meters' * @param abbreviation - abbreviated unit name, e.g. 'm' * @param definition - the variadic parameter is used for the definition of the unit - * (e.g. `unit, units::category::length_unit>`) + * (e.g. `unit, wpi::units::category::length_unit>`) * @note a variadic template is used for the definition to allow templates with * commas to be easily expanded. All the variadic 'arguments' should together * comprise the unit definition. @@ -303,13 +303,13 @@ template<> constexpr const char* abbreviation(const namespaceName::nameSingular * using the abbreviation (e.g. `10.0_m`). It also defines a class-specific * cout function which prints both the value and abbreviation of the unit when invoked. * @param namespaceName namespace in which the new units will be encapsulated. All literal values - * are placed in the `units::literals` namespace. + * are placed in the `wpi::units::literals` namespace. * @param nameSingular singular version of the unit name, e.g. 'meter' * @param namePlural - plural version of the unit name, e.g. 'meters' * @param abbreviation - abbreviated unit name, e.g. 'm' * @param underlyingType - the underlying type, e.g. 'int' or 'float' * @param definition - the variadic parameter is used for the definition of the unit - * (e.g. `unit, units::category::length_unit>`) + * (e.g. `unit, wpi::units::category::length_unit>`) * @note a variadic template is used for the definition to allow templates with * commas to be easily expanded. All the variadic 'arguments' should together * comprise the unit definition. @@ -325,14 +325,14 @@ template<> constexpr const char* abbreviation(const namespaceName::nameSingular * @brief Macro to create decibel container and literals for an existing unit type. * @details This macro generates the decibel unit container, cout overload, and literal definitions. * @param namespaceName namespace in which the new units will be encapsulated. All literal values - * are placed in the `units::literals` namespace. + * are placed in the `wpi::units::literals` namespace. * @param nameSingular singular version of the base unit name, e.g. 'watt' * @param abbreviation - abbreviated decibel unit name, e.g. 'dBW' */ #define UNIT_ADD_DECIBEL(namespaceName, nameSingular, abbreviation)\ namespace namespaceName\ {\ - /** @name Unit Containers */ /** @{ */ typedef unit_t abbreviation ## _t; /** @} */\ + /** @name Unit Containers */ /** @{ */ typedef unit_t abbreviation ## _t; /** @} */\ }\ UNIT_ADD_IO(namespaceName, abbreviation, abbreviation)\ UNIT_ADD_LITERALS(namespaceName, abbreviation, abbreviation) @@ -354,9 +354,9 @@ template<> constexpr const char* abbreviation(const namespaceName::nameSingular {\ template struct is_ ## unitCategory ## _unit_impl : std::false_type {};\ template\ - struct is_ ## unitCategory ## _unit_impl> : std::is_same>::base_unit_type>, units::category::unitCategory ## _unit>::type {};\ + struct is_ ## unitCategory ## _unit_impl> : std::is_same>::base_unit_type>, wpi::units::category::unitCategory ## _unit>::type {};\ template class N>\ - struct is_ ## unitCategory ## _unit_impl> : std::is_same>::unit_type>, units::category::unitCategory ## _unit>::type {};\ + struct is_ ## unitCategory ## _unit_impl> : std::is_same>::unit_type>, wpi::units::category::unitCategory ## _unit>::type {};\ }\ /** @endcond */\ } @@ -364,7 +364,7 @@ template<> constexpr const char* abbreviation(const namespaceName::nameSingular #define UNIT_ADD_IS_UNIT_CATEGORY_TRAIT(unitCategory)\ namespace traits\ {\ - template struct is_ ## unitCategory ## _unit : std::integral_constant>::value...>::value> {};\ + template struct is_ ## unitCategory ## _unit : std::integral_constant>::value...>::value> {};\ template constexpr bool is_ ## unitCategory ## _unit_v = is_ ## unitCategory ## _unit::value;\ }\ template \ @@ -386,12 +386,12 @@ template<> constexpr const char* abbreviation(const namespaceName::nameSingular * it also creates corresponding units with metric suffixes such as `millimeters`, and `millimeter_t`), as well as the * literal suffixes (e.g. `10.0_mm`). * @param namespaceName namespace in which the new units will be encapsulated. All literal values - * are placed in the `units::literals` namespace. + * are placed in the `wpi::units::literals` namespace. * @param nameSingular singular version of the unit name, e.g. 'meter' * @param namePlural - plural version of the unit name, e.g. 'meters' * @param abbreviation - abbreviated unit name, e.g. 'm' * @param definition - the variadic parameter is used for the definition of the unit - * (e.g. `unit, units::category::length_unit>`) + * (e.g. `unit, wpi::units::category::length_unit>`) * @note a variadic template is used for the definition to allow templates with * commas to be easily expanded. All the variadic 'arguments' should together * comprise the unit definition. @@ -421,12 +421,12 @@ template<> constexpr const char* abbreviation(const namespaceName::nameSingular * it also creates corresponding units with metric suffixes such as `millimeters`, and `millimeter_t`), as well as the * literal suffixes (e.g. `10.0_B`). * @param namespaceName namespace in which the new units will be encapsulated. All literal values - * are placed in the `units::literals` namespace. + * are placed in the `wpi::units::literals` namespace. * @param nameSingular singular version of the unit name, e.g. 'byte' * @param namePlural - plural version of the unit name, e.g. 'bytes' * @param abbreviation - abbreviated unit name, e.g. 'B' * @param definition - the variadic parameter is used for the definition of the unit - * (e.g. `unit, units::category::data_unit>`) + * (e.g. `unit, wpi::units::category::data_unit>`) * @note a variadic template is used for the definition to allow templates with * commas to be easily expanded. All the variadic 'arguments' should together * comprise the unit definition. @@ -445,10 +445,10 @@ template<> constexpr const char* abbreviation(const namespaceName::nameSingular //-------------------- /** - * @namespace units + * @namespace wpi::units * @brief Unit Conversion Library namespace */ -namespace units +namespace wpi::units { //---------------------------------- // DOXYGEN @@ -553,7 +553,7 @@ namespace units * whether `class T` has a numerator static member. */ template - struct has_num : units::detail::has_num_impl::type {}; + struct has_num : wpi::units::detail::has_num_impl::type {}; namespace detail { @@ -576,7 +576,7 @@ namespace units * whether `class T` has a denominator static member. */ template - struct has_den : units::detail::has_den_impl::type {}; + struct has_den : wpi::units::detail::has_den_impl::type {}; /** @endcond */ // END DOXYGEN IGNORE @@ -617,7 +617,7 @@ namespace units * @brief Trait which tests that a set of other traits are all true. */ template - struct all_true : std::is_same, units::bool_pack> {}; + struct all_true : std::is_same, wpi::units::bool_pack> {}; template constexpr bool all_true_t_v = all_true::type::value; /** @endcond */ // DOXYGEN IGNORE @@ -693,7 +693,7 @@ namespace units * whether `class T` implements a `base_unit`. */ template - struct is_base_unit : std::is_base_of {}; + struct is_base_unit : std::is_base_of {}; } /** @cond */ // DOXYGEN IGNORE @@ -719,7 +719,7 @@ namespace units * whether `class T` implements a `unit`. */ template - struct is_unit : std::is_base_of::type {}; + struct is_unit : std::is_base_of::type {}; template constexpr bool is_unit_v = is_unit::value; } @@ -757,7 +757,7 @@ namespace units class Mole = std::ratio<0>, class Candela = std::ratio<0>, class Byte = std::ratio<0>> - struct base_unit : units::detail::_base_unit_t + struct base_unit : wpi::units::detail::_base_unit_t { static_assert(traits::is_ratio::value, "Template parameter `Meter` must be a `std::ratio` representing the exponent of meters the unit has"); static_assert(traits::is_ratio::value, "Template parameter `Kilogram` must be a `std::ratio` representing the exponent of kilograms the unit has"); @@ -851,13 +851,13 @@ namespace units */ template struct unit; template - struct unit, PiExponent, Translation> : units::detail::_unit + struct unit, PiExponent, Translation> : wpi::units::detail::_unit { static_assert(traits::is_ratio::value, "Template parameter `Conversion` must be a `std::ratio` representing the conversion factor to `BaseUnit`."); static_assert(traits::is_ratio::value, "Template parameter `PiExponent` must be a `std::ratio` representing the exponents of Pi the unit has."); static_assert(traits::is_ratio::value, "Template parameter `Translation` must be a `std::ratio` representing an additive translation required by the unit conversion."); - typedef typename units::base_unit base_unit_type; + typedef typename wpi::units::base_unit base_unit_type; typedef Conversion conversion_ratio; typedef Translation translation_ratio; typedef PiExponent pi_exponent_ratio; @@ -876,7 +876,7 @@ namespace units * - a ratio representing a datum translation required for the conversion (e.g. `std::ratio<32>` for a fahrenheit to celsius conversion) * * Typically, a specific unit, like `meters`, would be implemented as a type alias - * of `unit`, i.e. `using meters = unit, units::category::length_unit`, or + * of `unit`, i.e. `using meters = unit, wpi::units::category::length_unit`, or * `using inches = unit, feet>`. * @tparam Conversion std::ratio representing scalar multiplication factor. * @tparam BaseUnit Unit type which this unit is derived from. May be a `base_unit`, or another `unit`. @@ -884,13 +884,13 @@ namespace units * @tparam Translation std::ratio representing any datum translation required by the conversion. */ template, class Translation = std::ratio<0>> - struct unit : units::detail::_unit + struct unit : wpi::units::detail::_unit { static_assert(traits::is_unit::value, "Template parameter `BaseUnit` must be a `unit` type."); static_assert(traits::is_ratio::value, "Template parameter `Conversion` must be a `std::ratio` representing the conversion factor to `BaseUnit`."); static_assert(traits::is_ratio::value, "Template parameter `PiExponent` must be a `std::ratio` representing the exponents of Pi the unit has."); - typedef typename units::traits::unit_traits::base_unit_type base_unit_type; + typedef typename wpi::units::traits::unit_traits::base_unit_type base_unit_type; typedef typename std::ratio_multiply conversion_ratio; typedef typename std::ratio_add pi_exponent_ratio; typedef typename std::ratio_add, typename BaseUnit::translation_ratio> translation_ratio; @@ -933,7 +933,7 @@ namespace units * Since compatible */ template - using base_unit_of = typename units::detail::base_unit_of_impl::type; + using base_unit_of = typename wpi::units::detail::base_unit_of_impl::type; } /** @cond */ // DOXYGEN IGNORE @@ -1122,8 +1122,8 @@ namespace units struct inverse_impl { using type = unit < std::ratio, - inverse_base::base_unit_type>>, - std::ratio_multiply::pi_exponent_ratio, std::ratio<-1>>, + inverse_base::base_unit_type>>, + std::ratio_multiply::pi_exponent_ratio, std::ratio<-1>>, std::ratio < 0 >> ; // inverses are rates or change, the translation factor goes away. }; } @@ -1135,7 +1135,7 @@ namespace units * @tparam U `unit` type to invert. * @details E.g. `inverse` will represent meters^-1 (i.e. 1/meters). */ - template using inverse = typename units::detail::inverse_impl::type; + template using inverse = typename wpi::units::detail::inverse_impl::type; /** @cond */ // DOXYGEN IGNORE namespace detail @@ -1166,7 +1166,7 @@ namespace units * @details E.g. `square` will represent meters^2. */ template - using squared = typename units::detail::squared_impl::type; + using squared = typename wpi::units::detail::squared_impl::type; /** @cond */ // DOXYGEN IGNORE namespace detail @@ -1196,7 +1196,7 @@ namespace units * @details E.g. `cubed` will represent meters^3. */ template - using cubed = typename units::detail::cubed_impl::type; + using cubed = typename wpi::units::detail::cubed_impl::type; /** @cond */ // DOXYGEN IGNORE namespace detail @@ -1357,7 +1357,7 @@ namespace units * integer overflow errors occur in the compiler. */ template - using ratio_sqrt = typename units::detail::Sqrt>::type; + using ratio_sqrt = typename wpi::units::detail::Sqrt>::type; /** @cond */ // DOXYGEN IGNORE namespace detail @@ -1402,7 +1402,7 @@ namespace units * Use only when absolutely necessary. */ template - using square_root = typename units::detail::sqrt_impl::type; + using square_root = typename wpi::units::detail::sqrt_impl::type; //------------------------------ // COMPOUND UNITS @@ -1435,7 +1435,7 @@ namespace units * @ingroup UnitTypes */ template - using compound_unit = typename units::detail::compound_impl::type; + using compound_unit = typename wpi::units::detail::compound_impl::type; //------------------------------ // PREFIXES @@ -1453,7 +1453,7 @@ namespace units { static_assert(traits::is_ratio::value, "Template parameter `Ratio` must be a `std::ratio`."); static_assert(traits::is_unit::value, "Template parameter `Unit` must be a `unit` type."); - typedef typename units::unit type; + typedef typename wpi::units::unit type; }; /// recursive exponential implementation @@ -1478,22 +1478,22 @@ namespace units * @ingroup Decimal Prefixes * @{ */ - template using atto = typename units::detail::prefix::type; ///< Represents the type of `class U` with the metric 'atto' prefix appended. @details E.g. atto represents meters*10^-18 @tparam U unit type to apply the prefix to. - template using femto = typename units::detail::prefix::type; ///< Represents the type of `class U` with the metric 'femto' prefix appended. @details E.g. femto represents meters*10^-15 @tparam U unit type to apply the prefix to. - template using pico = typename units::detail::prefix::type; ///< Represents the type of `class U` with the metric 'pico' prefix appended. @details E.g. pico represents meters*10^-12 @tparam U unit type to apply the prefix to. - template using nano = typename units::detail::prefix::type; ///< Represents the type of `class U` with the metric 'nano' prefix appended. @details E.g. nano represents meters*10^-9 @tparam U unit type to apply the prefix to. - template using micro = typename units::detail::prefix::type; ///< Represents the type of `class U` with the metric 'micro' prefix appended. @details E.g. micro represents meters*10^-6 @tparam U unit type to apply the prefix to. - template using milli = typename units::detail::prefix::type; ///< Represents the type of `class U` with the metric 'milli' prefix appended. @details E.g. milli represents meters*10^-3 @tparam U unit type to apply the prefix to. - template using centi = typename units::detail::prefix::type; ///< Represents the type of `class U` with the metric 'centi' prefix appended. @details E.g. centi represents meters*10^-2 @tparam U unit type to apply the prefix to. - template using deci = typename units::detail::prefix::type; ///< Represents the type of `class U` with the metric 'deci' prefix appended. @details E.g. deci represents meters*10^-1 @tparam U unit type to apply the prefix to. - template using deca = typename units::detail::prefix::type; ///< Represents the type of `class U` with the metric 'deca' prefix appended. @details E.g. deca represents meters*10^1 @tparam U unit type to apply the prefix to. - template using hecto = typename units::detail::prefix::type; ///< Represents the type of `class U` with the metric 'hecto' prefix appended. @details E.g. hecto represents meters*10^2 @tparam U unit type to apply the prefix to. - template using kilo = typename units::detail::prefix::type; ///< Represents the type of `class U` with the metric 'kilo' prefix appended. @details E.g. kilo represents meters*10^3 @tparam U unit type to apply the prefix to. - template using mega = typename units::detail::prefix::type; ///< Represents the type of `class U` with the metric 'mega' prefix appended. @details E.g. mega represents meters*10^6 @tparam U unit type to apply the prefix to. - template using giga = typename units::detail::prefix::type; ///< Represents the type of `class U` with the metric 'giga' prefix appended. @details E.g. giga represents meters*10^9 @tparam U unit type to apply the prefix to. - template using tera = typename units::detail::prefix::type; ///< Represents the type of `class U` with the metric 'tera' prefix appended. @details E.g. tera represents meters*10^12 @tparam U unit type to apply the prefix to. - template using peta = typename units::detail::prefix::type; ///< Represents the type of `class U` with the metric 'peta' prefix appended. @details E.g. peta represents meters*10^15 @tparam U unit type to apply the prefix to. - template using exa = typename units::detail::prefix::type; ///< Represents the type of `class U` with the metric 'exa' prefix appended. @details E.g. exa represents meters*10^18 @tparam U unit type to apply the prefix to. + template using atto = typename wpi::units::detail::prefix::type; ///< Represents the type of `class U` with the metric 'atto' prefix appended. @details E.g. atto represents meters*10^-18 @tparam U unit type to apply the prefix to. + template using femto = typename wpi::units::detail::prefix::type; ///< Represents the type of `class U` with the metric 'femto' prefix appended. @details E.g. femto represents meters*10^-15 @tparam U unit type to apply the prefix to. + template using pico = typename wpi::units::detail::prefix::type; ///< Represents the type of `class U` with the metric 'pico' prefix appended. @details E.g. pico represents meters*10^-12 @tparam U unit type to apply the prefix to. + template using nano = typename wpi::units::detail::prefix::type; ///< Represents the type of `class U` with the metric 'nano' prefix appended. @details E.g. nano represents meters*10^-9 @tparam U unit type to apply the prefix to. + template using micro = typename wpi::units::detail::prefix::type; ///< Represents the type of `class U` with the metric 'micro' prefix appended. @details E.g. micro represents meters*10^-6 @tparam U unit type to apply the prefix to. + template using milli = typename wpi::units::detail::prefix::type; ///< Represents the type of `class U` with the metric 'milli' prefix appended. @details E.g. milli represents meters*10^-3 @tparam U unit type to apply the prefix to. + template using centi = typename wpi::units::detail::prefix::type; ///< Represents the type of `class U` with the metric 'centi' prefix appended. @details E.g. centi represents meters*10^-2 @tparam U unit type to apply the prefix to. + template using deci = typename wpi::units::detail::prefix::type; ///< Represents the type of `class U` with the metric 'deci' prefix appended. @details E.g. deci represents meters*10^-1 @tparam U unit type to apply the prefix to. + template using deca = typename wpi::units::detail::prefix::type; ///< Represents the type of `class U` with the metric 'deca' prefix appended. @details E.g. deca represents meters*10^1 @tparam U unit type to apply the prefix to. + template using hecto = typename wpi::units::detail::prefix::type; ///< Represents the type of `class U` with the metric 'hecto' prefix appended. @details E.g. hecto represents meters*10^2 @tparam U unit type to apply the prefix to. + template using kilo = typename wpi::units::detail::prefix::type; ///< Represents the type of `class U` with the metric 'kilo' prefix appended. @details E.g. kilo represents meters*10^3 @tparam U unit type to apply the prefix to. + template using mega = typename wpi::units::detail::prefix::type; ///< Represents the type of `class U` with the metric 'mega' prefix appended. @details E.g. mega represents meters*10^6 @tparam U unit type to apply the prefix to. + template using giga = typename wpi::units::detail::prefix::type; ///< Represents the type of `class U` with the metric 'giga' prefix appended. @details E.g. giga represents meters*10^9 @tparam U unit type to apply the prefix to. + template using tera = typename wpi::units::detail::prefix::type; ///< Represents the type of `class U` with the metric 'tera' prefix appended. @details E.g. tera represents meters*10^12 @tparam U unit type to apply the prefix to. + template using peta = typename wpi::units::detail::prefix::type; ///< Represents the type of `class U` with the metric 'peta' prefix appended. @details E.g. peta represents meters*10^15 @tparam U unit type to apply the prefix to. + template using exa = typename wpi::units::detail::prefix::type; ///< Represents the type of `class U` with the metric 'exa' prefix appended. @details E.g. exa represents meters*10^18 @tparam U unit type to apply the prefix to. /** @} @} */ /** @@ -1502,12 +1502,12 @@ namespace units * @ingroup Binary Prefixes * @{ */ - template using kibi = typename units::detail::prefix, U>::type; ///< Represents the type of `class U` with the binary 'kibi' prefix appended. @details E.g. kibi represents bytes*2^10 @tparam U unit type to apply the prefix to. - template using mebi = typename units::detail::prefix, U>::type; ///< Represents the type of `class U` with the binary 'mibi' prefix appended. @details E.g. mebi represents bytes*2^20 @tparam U unit type to apply the prefix to. - template using gibi = typename units::detail::prefix, U>::type; ///< Represents the type of `class U` with the binary 'gibi' prefix appended. @details E.g. gibi represents bytes*2^30 @tparam U unit type to apply the prefix to. - template using tebi = typename units::detail::prefix, U>::type; ///< Represents the type of `class U` with the binary 'tebi' prefix appended. @details E.g. tebi represents bytes*2^40 @tparam U unit type to apply the prefix to. - template using pebi = typename units::detail::prefix, U>::type; ///< Represents the type of `class U` with the binary 'pebi' prefix appended. @details E.g. pebi represents bytes*2^50 @tparam U unit type to apply the prefix to. - template using exbi = typename units::detail::prefix, U>::type; ///< Represents the type of `class U` with the binary 'exbi' prefix appended. @details E.g. exbi represents bytes*2^60 @tparam U unit type to apply the prefix to. + template using kibi = typename wpi::units::detail::prefix, U>::type; ///< Represents the type of `class U` with the binary 'kibi' prefix appended. @details E.g. kibi represents bytes*2^10 @tparam U unit type to apply the prefix to. + template using mebi = typename wpi::units::detail::prefix, U>::type; ///< Represents the type of `class U` with the binary 'mibi' prefix appended. @details E.g. mebi represents bytes*2^20 @tparam U unit type to apply the prefix to. + template using gibi = typename wpi::units::detail::prefix, U>::type; ///< Represents the type of `class U` with the binary 'gibi' prefix appended. @details E.g. gibi represents bytes*2^30 @tparam U unit type to apply the prefix to. + template using tebi = typename wpi::units::detail::prefix, U>::type; ///< Represents the type of `class U` with the binary 'tebi' prefix appended. @details E.g. tebi represents bytes*2^40 @tparam U unit type to apply the prefix to. + template using pebi = typename wpi::units::detail::prefix, U>::type; ///< Represents the type of `class U` with the binary 'pebi' prefix appended. @details E.g. pebi represents bytes*2^50 @tparam U unit type to apply the prefix to. + template using exbi = typename wpi::units::detail::prefix, U>::type; ///< Represents the type of `class U` with the binary 'exbi' prefix appended. @details E.g. exbi represents bytes*2^60 @tparam U unit type to apply the prefix to. /** @} @} */ //------------------------------ @@ -1529,8 +1529,8 @@ namespace units * @sa is_convertible_unit_t */ template - struct is_convertible_unit : std::is_same ::base_unit_type>, - base_unit_of::base_unit_type >> {}; + struct is_convertible_unit : std::is_same ::base_unit_type>, + base_unit_of::base_unit_type >> {}; template constexpr bool is_convertible_unit_v = is_convertible_unit::value; } @@ -1663,7 +1663,7 @@ namespace units using piRequired = std::integral_constant, PiRatio>::value)>; using translationRequired = std::integral_constant, Translation>::value)>; - return units::detail::convert + return wpi::units::detail::convert (value, isSame{}, piRequired{}, translationRequired{}); } @@ -1741,7 +1741,7 @@ namespace units * - have an `operator()` member which returns the non-linear value stored in the scale * - have an accessible `m_value` member type which stores the linearized value in the scale. * - * Linear/nonlinear scales are used by `units::unit` to store values and scale them + * Linear/nonlinear scales are used by `wpi::units::unit` to store values and scale them * if they represent things like dB. */ template @@ -1762,7 +1762,7 @@ namespace units #ifdef FOR_DOXYGEN_PURPOSES_ONLY /** * @ingroup TypeTraits - * @brief Trait for accessing the publicly defined types of `units::unit_t` + * @brief Trait for accessing the publicly defined types of `wpi::units::unit_t` * @details The units library determines certain properties of the unit_t types passed to them * and what they represent by using the members of the corresponding unit_t_traits instantiation. */ @@ -1792,7 +1792,7 @@ namespace units /** * @ingroup TypeTraits - * @brief Trait for accessing the publicly defined types of `units::unit_t` + * @brief Trait for accessing the publicly defined types of `wpi::units::unit_t` * @details */ template @@ -1826,7 +1826,7 @@ namespace units */ template struct is_convertible_unit_t : std::integral_constant::unit_type, typename units::traits::unit_t_traits::unit_type>::value> + is_convertible_unit::unit_type, typename wpi::units::traits::unit_t_traits::unit_type>::value> {}; } @@ -1865,7 +1865,7 @@ namespace units * whether `class T` implements a `unit`. */ template - struct is_unit_t : std::is_base_of::type {}; + struct is_unit_t : std::is_base_of::type {}; template constexpr bool is_unit_t_v = is_unit_t::value; } @@ -1926,7 +1926,7 @@ namespace units * - \ref constantContainers "constant unit containers" */ template class NonLinearScale = linear_scale> - class unit_t : public NonLinearScale, units::detail::_unit_t + class unit_t : public NonLinearScale, wpi::units::detail::_unit_t { static_assert(traits::is_unit::value, "Template parameter `Units` must be a unit tag. Check that you aren't using a unit type (_t)."); static_assert(traits::is_nonlinear_scale, T>::value, "Template parameter `NonLinearScale` does not conform to the `is_nonlinear_scale` concept."); @@ -1981,7 +1981,7 @@ namespace units */ template::value && traits::is_ratio::value>> constexpr unit_t(const std::chrono::duration& value) noexcept : - nls(units::convert, category::time_unit>, Units>(static_cast(std::chrono::duration_cast(value).count()))) + nls(wpi::units::convert, category::time_unit>, Units>(static_cast(std::chrono::duration_cast(value).count()))) { } @@ -1994,7 +1994,7 @@ namespace units template class NlsRhs> requires traits::is_unit_v && traits::is_unit_v && traits::is_convertible_unit_v constexpr unit_t(const unit_t& rhs) noexcept : - nls(units::convert(rhs.m_value), std::true_type() /*store linear value*/) + nls(wpi::units::convert(rhs.m_value), std::true_type() /*store linear value*/) { } @@ -2007,7 +2007,7 @@ namespace units template class NlsRhs> inline unit_t& operator=(const unit_t& rhs) noexcept { - nls::m_value = units::convert(rhs.m_value); + nls::m_value = wpi::units::convert(rhs.m_value); return *this; } @@ -2032,7 +2032,7 @@ namespace units template class NlsRhs> constexpr bool operator<(const unit_t& rhs) const noexcept { - return (nls::m_value < units::convert(rhs.m_value)); + return (nls::m_value < wpi::units::convert(rhs.m_value)); } /** @@ -2044,7 +2044,7 @@ namespace units template class NlsRhs> constexpr bool operator<=(const unit_t& rhs) const noexcept { - return (nls::m_value <= units::convert(rhs.m_value)); + return (nls::m_value <= wpi::units::convert(rhs.m_value)); } /** @@ -2056,7 +2056,7 @@ namespace units template class NlsRhs> constexpr bool operator>(const unit_t& rhs) const noexcept { - return (nls::m_value > units::convert(rhs.m_value)); + return (nls::m_value > wpi::units::convert(rhs.m_value)); } /** @@ -2068,7 +2068,7 @@ namespace units template class NlsRhs> constexpr bool operator>=(const unit_t& rhs) const noexcept { - return (nls::m_value >= units::convert(rhs.m_value)); + return (nls::m_value >= wpi::units::convert(rhs.m_value)); } /** @@ -2081,15 +2081,15 @@ namespace units template class NlsRhs, std::enable_if_t::value || std::is_floating_point::value, int> = 0> constexpr bool operator==(const unit_t& rhs) const noexcept { - return detail::abs(nls::m_value - units::convert(rhs.m_value)) < std::numeric_limits::epsilon() * - detail::abs(nls::m_value + units::convert(rhs.m_value)) || - detail::abs(nls::m_value - units::convert(rhs.m_value)) < (std::numeric_limits::min)(); + return detail::abs(nls::m_value - wpi::units::convert(rhs.m_value)) < std::numeric_limits::epsilon() * + detail::abs(nls::m_value + wpi::units::convert(rhs.m_value)) || + detail::abs(nls::m_value - wpi::units::convert(rhs.m_value)) < (std::numeric_limits::min)(); } template class NlsRhs, std::enable_if_t::value && std::is_integral::value, int> = 0> constexpr bool operator==(const unit_t& rhs) const noexcept { - return nls::m_value == units::convert(rhs.m_value); + return nls::m_value == wpi::units::convert(rhs.m_value); } /** @@ -2159,7 +2159,7 @@ namespace units constexpr operator Ty() const noexcept { // this conversion also resolves any PI exponents, by converting from a non-zero PI ratio to a zero-pi ratio. - return static_cast(units::convert, units::category::scalar_unit>>((*this)())); + return static_cast(wpi::units::convert, wpi::units::category::scalar_unit>>((*this)())); } /** @@ -2176,10 +2176,10 @@ namespace units * @brief chrono implicit type conversion. * @details only enabled for time unit types. */ - template, category::time_unit>>::value, int> = 0> + template, category::time_unit>>::value, int> = 0> constexpr operator std::chrono::nanoseconds() const noexcept { - return std::chrono::duration_cast(std::chrono::duration(units::convert, category::time_unit>>((*this)()))); + return std::chrono::duration_cast(std::chrono::duration(wpi::units::convert, category::time_unit>>((*this)()))); } /** @@ -2187,7 +2187,7 @@ namespace units */ constexpr const char* name() const noexcept { - return units::name(*this); + return wpi::units::name(*this); } /** @@ -2195,7 +2195,7 @@ namespace units */ constexpr const char* abbreviation() const noexcept { - return units::abbreviation(*this); + return wpi::units::abbreviation(*this); } public: @@ -2387,7 +2387,7 @@ namespace units * to a built-in arithmetic type. This may be useful for compatibility with libraries * and legacy code that don't support `unit_t` types. E.g * @code meter_t unitVal(5); - * double value = units::unit_cast(unitVal); // value = 5.0 + * double value = wpi::units::unit_cast(unitVal); // value = 5.0 * @endcode * @tparam T Type to cast the unit type to. Must be a built-in arithmetic type. * @param value Unit value to cast. @@ -2417,15 +2417,15 @@ namespace units */ #if !defined(_MSC_VER) || _MSC_VER > 1800 // bug in VS2013 prevents this from working template - struct has_linear_scale : std::integral_constant::underlying_type>, T>::value...>::value > {}; + struct has_linear_scale : std::integral_constant::underlying_type>, T>::value...>::value > {}; template constexpr bool has_linear_scale_v = has_linear_scale::value; #else template struct has_linear_scale : std::integral_constant::underlying_type>, T1>::value && - std::is_base_of::underlying_type>, T2>::value && - std::is_base_of::underlying_type>, T3>::value> {}; + std::is_base_of::underlying_type>, T1>::value && + std::is_base_of::underlying_type>, T2>::value && + std::is_base_of::underlying_type>, T3>::value> {}; template constexpr bool has_linear_scale_v = has_linear_scale::value; #endif @@ -2439,15 +2439,15 @@ namespace units */ #if !defined(_MSC_VER) || _MSC_VER > 1800 // bug in VS2013 prevents this from working template - struct has_decibel_scale : std::integral_constant::underlying_type>, T>::value...>::value> {}; + struct has_decibel_scale : std::integral_constant::underlying_type>, T>::value...>::value> {}; template constexpr bool has_decibel_scale_v = has_decibel_scale::value; #else template struct has_decibel_scale : std::integral_constant::underlying_type>, T1>::value && - std::is_base_of::underlying_type>, T2>::value && - std::is_base_of::underlying_type>, T3>::value> {}; + std::is_base_of::underlying_type>, T1>::value && + std::is_base_of::underlying_type>, T2>::value && + std::is_base_of::underlying_type>, T3>::value> {}; template constexpr bool has_decibel_scale_v = has_decibel_scale::value; #endif @@ -2462,7 +2462,7 @@ namespace units */ template struct is_same_scale : std::integral_constant::non_linear_scale_type, typename units::traits::unit_t_traits::non_linear_scale_type>::value> + std::is_same::non_linear_scale_type, typename wpi::units::traits::unit_t_traits::non_linear_scale_type>::value> {}; template constexpr bool is_same_scale_v = is_same_scale::value; @@ -2512,8 +2512,8 @@ namespace units // Scalar units are the *ONLY* units implicitly convertible to/from built-in types. namespace dimensionless { - typedef unit, units::category::scalar_unit> scalar; - typedef unit, units::category::dimensionless_unit> dimensionless; + typedef unit, wpi::units::category::scalar_unit> scalar; + typedef unit, wpi::units::category::dimensionless_unit> dimensionless; typedef unit_t scalar_t; typedef scalar_t dimensionless_t; @@ -2545,8 +2545,8 @@ namespace units template::value, int> = 0> constexpr UnitTypeLhs operator+(const UnitTypeLhs& lhs, const UnitTypeRhs& rhs) noexcept { - using UnitsLhs = typename units::traits::unit_t_traits::unit_type; - using UnitsRhs = typename units::traits::unit_t_traits::unit_type; + using UnitsLhs = typename wpi::units::traits::unit_t_traits::unit_type; + using UnitsRhs = typename wpi::units::traits::unit_t_traits::unit_type; return UnitTypeLhs(lhs() + convert(rhs())); } @@ -2568,8 +2568,8 @@ namespace units template::value, int> = 0> constexpr UnitTypeLhs operator-(const UnitTypeLhs& lhs, const UnitTypeRhs& rhs) noexcept { - using UnitsLhs = typename units::traits::unit_t_traits::unit_type; - using UnitsRhs = typename units::traits::unit_t_traits::unit_type; + using UnitsLhs = typename wpi::units::traits::unit_t_traits::unit_type; + using UnitsRhs = typename wpi::units::traits::unit_t_traits::unit_type; return UnitTypeLhs(lhs() - convert(rhs())); } @@ -2590,21 +2590,21 @@ namespace units /// Multiplication type for convertible unit_t types with a linear scale. @returns the multiplied value, with the same type as left-hand side unit. template::value && traits::has_linear_scale::value, int> = 0> - constexpr auto operator*(const UnitTypeLhs& lhs, const UnitTypeRhs& rhs) noexcept -> unit_t::unit_type>>> + constexpr auto operator*(const UnitTypeLhs& lhs, const UnitTypeRhs& rhs) noexcept -> unit_t::unit_type>>> { - using UnitsLhs = typename units::traits::unit_t_traits::unit_type; - using UnitsRhs = typename units::traits::unit_t_traits::unit_type; - return unit_t::unit_type>>> + using UnitsLhs = typename wpi::units::traits::unit_t_traits::unit_type; + using UnitsRhs = typename wpi::units::traits::unit_t_traits::unit_type; + return unit_t::unit_type>>> (lhs() * convert(rhs())); } /// Multiplication type for non-convertible unit_t types with a linear scale. @returns the multiplied value, whose type is a compound unit of the left and right hand side values. template::value && traits::has_linear_scale::value && !traits::is_dimensionless_unit::value && !traits::is_dimensionless_unit::value, int> = 0> - constexpr auto operator*(const UnitTypeLhs& lhs, const UnitTypeRhs& rhs) noexcept -> unit_t::unit_type, typename units::traits::unit_t_traits::unit_type>> + constexpr auto operator*(const UnitTypeLhs& lhs, const UnitTypeRhs& rhs) noexcept -> unit_t::unit_type, typename wpi::units::traits::unit_t_traits::unit_type>> { - using UnitsLhs = typename units::traits::unit_t_traits::unit_type; - using UnitsRhs = typename units::traits::unit_t_traits::unit_type; + using UnitsLhs = typename wpi::units::traits::unit_t_traits::unit_type; + using UnitsRhs = typename wpi::units::traits::unit_t_traits::unit_type; return unit_t> (lhs() * rhs()); } @@ -2648,18 +2648,18 @@ namespace units std::enable_if_t::value && traits::has_linear_scale::value, int> = 0> constexpr dimensionless::scalar_t operator/(const UnitTypeLhs& lhs, const UnitTypeRhs& rhs) noexcept { - using UnitsLhs = typename units::traits::unit_t_traits::unit_type; - using UnitsRhs = typename units::traits::unit_t_traits::unit_type; + using UnitsLhs = typename wpi::units::traits::unit_t_traits::unit_type; + using UnitsRhs = typename wpi::units::traits::unit_t_traits::unit_type; return dimensionless::scalar_t(lhs() / convert(rhs())); } /// Division for non-convertible unit_t types with a linear scale. @returns the lhs divided by the rhs, with a compound unit type of lhs/rhs template::value && traits::has_linear_scale::value && !traits::is_dimensionless_unit::value && !traits::is_dimensionless_unit::value, int> = 0> - constexpr auto operator/(const UnitTypeLhs& lhs, const UnitTypeRhs& rhs) noexcept -> unit_t::unit_type, inverse::unit_type>>> + constexpr auto operator/(const UnitTypeLhs& lhs, const UnitTypeRhs& rhs) noexcept -> unit_t::unit_type, inverse::unit_type>>> { - using UnitsLhs = typename units::traits::unit_t_traits::unit_type; - using UnitsRhs = typename units::traits::unit_t_traits::unit_type; + using UnitsLhs = typename wpi::units::traits::unit_t_traits::unit_type; + using UnitsRhs = typename wpi::units::traits::unit_t_traits::unit_type; return unit_t>> (lhs() / rhs()); } @@ -2675,9 +2675,9 @@ namespace units /// Division of a dimensionless unit by a unit_t type with a linear scale template::value && traits::is_dimensionless_unit::value && !traits::is_dimensionless_unit::value, int> = 0> - constexpr auto operator/(const UnitTypeLhs& lhs, const UnitTypeRhs& rhs) noexcept -> unit_t::unit_type>> + constexpr auto operator/(const UnitTypeLhs& lhs, const UnitTypeRhs& rhs) noexcept -> unit_t::unit_type>> { - return unit_t::unit_type>> + return unit_t::unit_type>> (static_cast(lhs) / rhs()); } @@ -2692,9 +2692,9 @@ namespace units /// Division of a scalar by a unit_t type with a linear scale template::value && traits::has_linear_scale::value, int> = 0> - constexpr auto operator/(T lhs, const UnitTypeRhs& rhs) noexcept -> unit_t::unit_type>> + constexpr auto operator/(T lhs, const UnitTypeRhs& rhs) noexcept -> unit_t::unit_type>> { - using UnitsRhs = typename units::traits::unit_t_traits::unit_type; + using UnitsRhs = typename wpi::units::traits::unit_t_traits::unit_type; return unit_t> (lhs / rhs()); } @@ -2703,75 +2703,75 @@ namespace units // SCALAR COMPARISONS //---------------------------------- - template::value>> + template::value>> constexpr bool operator==(const UNIT_LIB_DEFAULT_TYPE lhs, const Units& rhs) noexcept { return detail::abs(lhs - static_cast(rhs)) < std::numeric_limits::epsilon() * detail::abs(lhs + static_cast(rhs)) || detail::abs(lhs - static_cast(rhs)) < (std::numeric_limits::min)(); } - template::value>> + template::value>> constexpr bool operator==(const Units& lhs, const UNIT_LIB_DEFAULT_TYPE rhs) noexcept { return detail::abs(static_cast(lhs) - rhs) < std::numeric_limits::epsilon() * detail::abs(static_cast(lhs) + rhs) || detail::abs(static_cast(lhs) - rhs) < (std::numeric_limits::min)(); } - template::value>> + template::value>> constexpr bool operator!=(const UNIT_LIB_DEFAULT_TYPE lhs, const Units& rhs) noexcept { return!(lhs == static_cast(rhs)); } - template::value>> + template::value>> constexpr bool operator!=(const Units& lhs, const UNIT_LIB_DEFAULT_TYPE rhs) noexcept { return !(static_cast(lhs) == rhs); } - template::value>> + template::value>> constexpr bool operator>=(const UNIT_LIB_DEFAULT_TYPE lhs, const Units& rhs) noexcept { return std::isgreaterequal(lhs, static_cast(rhs)); } - template::value>> + template::value>> constexpr bool operator>=(const Units& lhs, const UNIT_LIB_DEFAULT_TYPE rhs) noexcept { return std::isgreaterequal(static_cast(lhs), rhs); } - template::value>> + template::value>> constexpr bool operator>(const UNIT_LIB_DEFAULT_TYPE lhs, const Units& rhs) noexcept { return lhs > static_cast(rhs); } - template::value>> + template::value>> constexpr bool operator>(const Units& lhs, const UNIT_LIB_DEFAULT_TYPE rhs) noexcept { return static_cast(lhs) > rhs; } - template::value>> + template::value>> constexpr bool operator<=(const UNIT_LIB_DEFAULT_TYPE lhs, const Units& rhs) noexcept { return std::islessequal(lhs, static_cast(rhs)); } - template::value>> + template::value>> constexpr bool operator<=(const Units& lhs, const UNIT_LIB_DEFAULT_TYPE rhs) noexcept { return std::islessequal(static_cast(lhs), rhs); } - template::value>> + template::value>> constexpr bool operator<(const UNIT_LIB_DEFAULT_TYPE lhs, const Units& rhs) noexcept { return lhs < static_cast(rhs); } - template::value>> + template::value>> constexpr bool operator<(const Units& lhs, const UNIT_LIB_DEFAULT_TYPE rhs) noexcept { return static_cast(lhs) < rhs; @@ -2787,7 +2787,7 @@ namespace units /// recursive exponential implementation template struct power_of_unit { - typedef typename units::detail::unit_multiply::type> type; + typedef typename wpi::units::detail::unit_multiply::type> type; }; /// End recursion @@ -2808,9 +2808,9 @@ namespace units * @returns new unit_t, raised to the given exponent */ template::value, int>> - constexpr auto pow(const UnitType& value) noexcept -> unit_t::unit_type>::type, typename units::traits::unit_t_traits::underlying_type, linear_scale> + constexpr auto pow(const UnitType& value) noexcept -> unit_t::unit_type>::type, typename wpi::units::traits::unit_t_traits::underlying_type, linear_scale> { - return unit_t::unit_type>::type, typename units::traits::unit_t_traits::underlying_type, linear_scale> + return unit_t::unit_type>::type, typename wpi::units::traits::unit_t_traits::underlying_type, linear_scale> (gcem::pow(value(), power)); } @@ -2823,10 +2823,10 @@ namespace units * @returns new unit_t, raised to the given exponent */ template::value, int>> - constexpr auto cpow(const UnitType& value) noexcept -> unit_t::unit_type>::type, typename units::traits::unit_t_traits::underlying_type, linear_scale> + constexpr auto cpow(const UnitType& value) noexcept -> unit_t::unit_type>::type, typename wpi::units::traits::unit_t_traits::underlying_type, linear_scale> { - static_assert(power >= 0, "cpow cannot accept negative numbers. Try units::math::pow instead."); - return unit_t::unit_type>::type, typename units::traits::unit_t_traits::underlying_type, linear_scale> + static_assert(power >= 0, "cpow cannot accept negative numbers. Try wpi::units::math::pow instead."); + return unit_t::unit_type>::type, typename wpi::units::traits::unit_t_traits::underlying_type, linear_scale> (detail::pow(value(), power)); } } @@ -2882,11 +2882,11 @@ namespace units } #if __has_include() && !defined(UNIT_LIB_DISABLE_FMT) template <> -struct fmt::formatter : fmt::formatter +struct fmt::formatter : fmt::formatter { template auto format( - const units::dimensionless::dB_t& obj, + const wpi::units::dimensionless::dB_t& obj, FmtContext& ctx) const { auto out = ctx.out(); @@ -2896,7 +2896,7 @@ struct fmt::formatter : fmt::formatter }; #endif -namespace units { +namespace wpi::units { //------------------------------ // DECIBEL ARITHMETIC //------------------------------ @@ -2904,11 +2904,11 @@ namespace units { /// Addition for convertible unit_t types with a decibel_scale template::value, int> = 0> - constexpr inline auto operator+(const UnitTypeLhs& lhs, const UnitTypeRhs& rhs) noexcept -> unit_t::unit_type>>, typename units::traits::unit_t_traits::underlying_type, decibel_scale> + constexpr inline auto operator+(const UnitTypeLhs& lhs, const UnitTypeRhs& rhs) noexcept -> unit_t::unit_type>>, typename wpi::units::traits::unit_t_traits::underlying_type, decibel_scale> { - using LhsUnits = typename units::traits::unit_t_traits::unit_type; - using RhsUnits = typename units::traits::unit_t_traits::unit_type; - using underlying_type = typename units::traits::unit_t_traits::underlying_type; + using LhsUnits = typename wpi::units::traits::unit_t_traits::unit_type; + using RhsUnits = typename wpi::units::traits::unit_t_traits::unit_type; + using underlying_type = typename wpi::units::traits::unit_t_traits::underlying_type; return unit_t>, underlying_type, decibel_scale> (lhs.template toLinearized() * convert(rhs.template toLinearized()), std::true_type()); @@ -2918,7 +2918,7 @@ namespace units { template::value && !traits::is_dimensionless_unit::value, int> = 0> constexpr inline UnitTypeLhs operator+(const UnitTypeLhs& lhs, const dimensionless::dB_t& rhs) noexcept { - using underlying_type = typename units::traits::unit_t_traits::underlying_type; + using underlying_type = typename wpi::units::traits::unit_t_traits::underlying_type; return UnitTypeLhs(lhs.template toLinearized() * rhs.template toLinearized(), std::true_type()); } @@ -2926,17 +2926,17 @@ namespace units { template::value && !traits::is_dimensionless_unit::value, int> = 0> constexpr inline UnitTypeRhs operator+(const dimensionless::dB_t& lhs, const UnitTypeRhs& rhs) noexcept { - using underlying_type = typename units::traits::unit_t_traits::underlying_type; + using underlying_type = typename wpi::units::traits::unit_t_traits::underlying_type; return UnitTypeRhs(lhs.template toLinearized() * rhs.template toLinearized(), std::true_type()); } /// Subtraction for convertible unit_t types with a decibel_scale template::value, int> = 0> - constexpr inline auto operator-(const UnitTypeLhs& lhs, const UnitTypeRhs& rhs) noexcept -> unit_t::unit_type, inverse::unit_type>>, typename units::traits::unit_t_traits::underlying_type, decibel_scale> + constexpr inline auto operator-(const UnitTypeLhs& lhs, const UnitTypeRhs& rhs) noexcept -> unit_t::unit_type, inverse::unit_type>>, typename wpi::units::traits::unit_t_traits::underlying_type, decibel_scale> { - using LhsUnits = typename units::traits::unit_t_traits::unit_type; - using RhsUnits = typename units::traits::unit_t_traits::unit_type; - using underlying_type = typename units::traits::unit_t_traits::underlying_type; + using LhsUnits = typename wpi::units::traits::unit_t_traits::unit_type; + using RhsUnits = typename wpi::units::traits::unit_t_traits::unit_type; + using underlying_type = typename wpi::units::traits::unit_t_traits::underlying_type; return unit_t>, underlying_type, decibel_scale> (lhs.template toLinearized() / convert(rhs.template toLinearized()), std::true_type()); @@ -2946,16 +2946,16 @@ namespace units { template::value && !traits::is_dimensionless_unit::value, int> = 0> constexpr inline UnitTypeLhs operator-(const UnitTypeLhs& lhs, const dimensionless::dB_t& rhs) noexcept { - using underlying_type = typename units::traits::unit_t_traits::underlying_type; + using underlying_type = typename wpi::units::traits::unit_t_traits::underlying_type; return UnitTypeLhs(lhs.template toLinearized() / rhs.template toLinearized(), std::true_type()); } /// Subtraction between unit_t types with a decibel_scale and dimensionless dB units template::value && !traits::is_dimensionless_unit::value, int> = 0> - constexpr inline auto operator-(const dimensionless::dB_t& lhs, const UnitTypeRhs& rhs) noexcept -> unit_t::unit_type>, typename units::traits::unit_t_traits::underlying_type, decibel_scale> + constexpr inline auto operator-(const dimensionless::dB_t& lhs, const UnitTypeRhs& rhs) noexcept -> unit_t::unit_type>, typename wpi::units::traits::unit_t_traits::underlying_type, decibel_scale> { - using RhsUnits = typename units::traits::unit_t_traits::unit_type; - using underlying_type = typename units::traits::unit_t_traits::underlying_type; + using RhsUnits = typename wpi::units::traits::unit_t_traits::unit_type; + using underlying_type = typename wpi::units::traits::unit_t_traits::underlying_type; return unit_t, underlying_type, decibel_scale> (lhs.template toLinearized() / rhs.template toLinearized(), std::true_type()); @@ -2978,7 +2978,7 @@ namespace units { #ifdef FOR_DOXYGEN_PURPOSES_ONLY /** * @ingroup TypeTraits - * @brief Trait for accessing the publicly defined types of `units::unit_value_t_traits` + * @brief Trait for accessing the publicly defined types of `wpi::units::unit_value_t_traits` * @details The units library determines certain properties of the `unit_value_t` types passed to * them and what they represent by using the members of the corresponding `unit_value_t_traits` * instantiation. @@ -3005,7 +3005,7 @@ namespace units { /** * @ingroup TypeTraits - * @brief Trait for accessing the publicly defined types of `units::unit_value_t_traits` + * @brief Trait for accessing the publicly defined types of `wpi::units::unit_value_t_traits` * @details */ template @@ -3037,7 +3037,7 @@ namespace units { * */ template - struct unit_value_t : units::detail::_unit_value_t + struct unit_value_t : wpi::units::detail::_unit_value_t { typedef Units unit_type; typedef std::ratio ratio; @@ -3058,7 +3058,7 @@ namespace units { */ template::unit_type> struct is_unit_value_t : std::integral_constant, T>::value> + std::is_base_of, T>::value> {}; template::unit_type> constexpr bool is_unit_value_t_v = is_unit_value_t::value; @@ -3066,11 +3066,11 @@ namespace units { /** * @ingroup TypeTraits * @brief Trait which tests whether type T is a unit_value_t with a unit type in the given category. - * @details e.g. `is_unit_value_t_category>::value` would be true + * @details e.g. `is_unit_value_t_category>::value` would be true */ template struct is_unit_value_t_category : std::integral_constant::unit_type>, Category>::value> + std::is_same::unit_type>, Category>::value> { static_assert(is_base_unit::value, "Template parameter `Category` must be a `base_unit` type."); }; @@ -3090,12 +3090,12 @@ namespace units { using _UNIT1 = typename traits::unit_value_t_traits::unit_type; using _UNIT2 = typename traits::unit_value_t_traits::unit_type; - using _CONV1 = typename units::traits::unit_traits<_UNIT1>::conversion_ratio; - using _CONV2 = typename units::traits::unit_traits<_UNIT2>::conversion_ratio; + using _CONV1 = typename wpi::units::traits::unit_traits<_UNIT1>::conversion_ratio; + using _CONV2 = typename wpi::units::traits::unit_traits<_UNIT2>::conversion_ratio; using _RATIO1 = typename traits::unit_value_t_traits::ratio; using _RATIO2 = typename traits::unit_value_t_traits::ratio; using _RATIO2CONV = typename std::ratio_divide, _CONV1>; - using _PI_EXP = std::ratio_subtract::pi_exponent_ratio, typename units::traits::unit_traits<_UNIT1>::pi_exponent_ratio>; + using _PI_EXP = std::ratio_subtract::pi_exponent_ratio, typename wpi::units::traits::unit_traits<_UNIT1>::pi_exponent_ratio>; }; } /** @endcond */ // END DOXYGEN IGNORE @@ -3111,10 +3111,10 @@ namespace units { * @note very similar in concept to `std::ratio_add` */ template - struct unit_value_add : units::detail::unit_value_arithmetic, units::detail::_unit_value_t::unit_type> + struct unit_value_add : wpi::units::detail::unit_value_arithmetic, wpi::units::detail::_unit_value_t::unit_type> { /** @cond */ // DOXYGEN IGNORE - using Base = units::detail::unit_value_arithmetic; + using Base = wpi::units::detail::unit_value_arithmetic; typedef typename Base::_UNIT1 unit_type; using ratio = std::ratio_add; @@ -3144,7 +3144,7 @@ namespace units { static constexpr const unit_t value(std::true_type) noexcept { return unit_t(((UNIT_LIB_DEFAULT_TYPE)Base::_RATIO1::num / Base::_RATIO1::den) + - ((UNIT_LIB_DEFAULT_TYPE)Base::_RATIO2CONV::num / Base::_RATIO2CONV::den) * std::pow(units::constants::detail::PI_VAL, ((UNIT_LIB_DEFAULT_TYPE)Base::_PI_EXP::num / Base::_PI_EXP::den))); + ((UNIT_LIB_DEFAULT_TYPE)Base::_RATIO2CONV::num / Base::_RATIO2CONV::den) * std::pow(wpi::units::constants::detail::PI_VAL, ((UNIT_LIB_DEFAULT_TYPE)Base::_PI_EXP::num / Base::_PI_EXP::den))); } /** @endcond */ // END DOXYGEN IGNORE }; @@ -3160,10 +3160,10 @@ namespace units { * @note very similar in concept to `std::ratio_subtract` */ template - struct unit_value_subtract : units::detail::unit_value_arithmetic, units::detail::_unit_value_t::unit_type> + struct unit_value_subtract : wpi::units::detail::unit_value_arithmetic, wpi::units::detail::_unit_value_t::unit_type> { /** @cond */ // DOXYGEN IGNORE - using Base = units::detail::unit_value_arithmetic; + using Base = wpi::units::detail::unit_value_arithmetic; typedef typename Base::_UNIT1 unit_type; using ratio = std::ratio_subtract; @@ -3194,7 +3194,7 @@ namespace units { static constexpr const unit_t value(std::true_type) noexcept { return unit_t(((UNIT_LIB_DEFAULT_TYPE)Base::_RATIO1::num / Base::_RATIO1::den) - ((UNIT_LIB_DEFAULT_TYPE)Base::_RATIO2CONV::num / Base::_RATIO2CONV::den) - * std::pow(units::constants::detail::PI_VAL, ((UNIT_LIB_DEFAULT_TYPE)Base::_PI_EXP::num / Base::_PI_EXP::den))); + * std::pow(wpi::units::constants::detail::PI_VAL, ((UNIT_LIB_DEFAULT_TYPE)Base::_PI_EXP::num / Base::_PI_EXP::den))); } /** @endcond */ // END DOXYGEN IGNORE }; }; @@ -3210,13 +3210,13 @@ namespace units { * @note very similar in concept to `std::ratio_multiply` */ template - struct unit_value_multiply : units::detail::unit_value_arithmetic, - units::detail::_unit_value_t::unit_type, + struct unit_value_multiply : wpi::units::detail::unit_value_arithmetic, + wpi::units::detail::_unit_value_t::unit_type, typename traits::unit_value_t_traits::unit_type>::value, compound_unit::unit_type>>, compound_unit::unit_type, typename traits::unit_value_t_traits::unit_type>>::type> { /** @cond */ // DOXYGEN IGNORE - using Base = units::detail::unit_value_arithmetic; + using Base = wpi::units::detail::unit_value_arithmetic; using unit_type = std::conditional_t::value, compound_unit>, compound_unit>; using ratio = std::conditional_t::value, std::ratio_multiply, std::ratio_multiply>; @@ -3244,7 +3244,7 @@ namespace units { // value if PI *is* involved static constexpr const unit_t value(std::true_type) noexcept { - return unit_t(((UNIT_LIB_DEFAULT_TYPE)ratio::num / ratio::den) * std::pow(units::constants::detail::PI_VAL, ((UNIT_LIB_DEFAULT_TYPE)Base::_PI_EXP::num / Base::_PI_EXP::den))); + return unit_t(((UNIT_LIB_DEFAULT_TYPE)ratio::num / ratio::den) * std::pow(wpi::units::constants::detail::PI_VAL, ((UNIT_LIB_DEFAULT_TYPE)Base::_PI_EXP::num / Base::_PI_EXP::den))); } /** @endcond */ // END DOXYGEN IGNORE }; @@ -3260,13 +3260,13 @@ namespace units { * @note very similar in concept to `std::ratio_divide` */ template - struct unit_value_divide : units::detail::unit_value_arithmetic, - units::detail::_unit_value_t::unit_type, + struct unit_value_divide : wpi::units::detail::unit_value_arithmetic, + wpi::units::detail::_unit_value_t::unit_type, typename traits::unit_value_t_traits::unit_type>::value, dimensionless::scalar, compound_unit::unit_type, inverse::unit_type>>>::type> { /** @cond */ // DOXYGEN IGNORE - using Base = units::detail::unit_value_arithmetic; + using Base = wpi::units::detail::unit_value_arithmetic; using unit_type = std::conditional_t::value, dimensionless::scalar, compound_unit>>; using ratio = std::conditional_t::value, std::ratio_divide, std::ratio_divide>; @@ -3294,7 +3294,7 @@ namespace units { // value if PI *is* involved static constexpr const unit_t value(std::true_type) noexcept { - return unit_t(((UNIT_LIB_DEFAULT_TYPE)ratio::num / ratio::den) * std::pow(units::constants::detail::PI_VAL, ((UNIT_LIB_DEFAULT_TYPE)Base::_PI_EXP::num / Base::_PI_EXP::den))); + return unit_t(((UNIT_LIB_DEFAULT_TYPE)ratio::num / ratio::den) * std::pow(wpi::units::constants::detail::PI_VAL, ((UNIT_LIB_DEFAULT_TYPE)Base::_PI_EXP::num / Base::_PI_EXP::den))); } /** @endcond */ // END DOXYGEN IGNORE }; @@ -3306,16 +3306,16 @@ namespace units { * @tparam U1 `unit_value_t` to take the exponentiation of. * @sa unit_value_t_traits to access information about the properties of the class, * such as it's unit type and rational value. - * @note very similar in concept to `units::math::pow` + * @note very similar in concept to `wpi::units::math::pow` */ template - struct unit_value_power : units::detail::unit_value_arithmetic, units::detail::_unit_value_t::unit_type>::type> + struct unit_value_power : wpi::units::detail::unit_value_arithmetic, wpi::units::detail::_unit_value_t::unit_type>::type> { /** @cond */ // DOXYGEN IGNORE - using Base = units::detail::unit_value_arithmetic; + using Base = wpi::units::detail::unit_value_arithmetic; - using unit_type = typename units::detail::power_of_unit::type; - using ratio = typename units::detail::power_of_ratio::type; + using unit_type = typename wpi::units::detail::power_of_unit::type; + using ratio = typename wpi::units::detail::power_of_ratio::type; using pi_exponent = std::ratio_multiply, typename Base::_UNIT1::pi_exponent_ratio>; /** @endcond */ // END DOXYGEN IGNORE @@ -3341,7 +3341,7 @@ namespace units { // value if PI *is* involved static constexpr const unit_t value(std::true_type) noexcept { - return unit_t(((UNIT_LIB_DEFAULT_TYPE)ratio::num / ratio::den) * std::pow(units::constants::detail::PI_VAL, ((UNIT_LIB_DEFAULT_TYPE)pi_exponent::num / pi_exponent::den))); + return unit_t(((UNIT_LIB_DEFAULT_TYPE)ratio::num / ratio::den) * std::pow(wpi::units::constants::detail::PI_VAL, ((UNIT_LIB_DEFAULT_TYPE)pi_exponent::num / pi_exponent::den))); } /** @endcond */ // END DOXYGEN IGNORE }; }; @@ -3353,13 +3353,13 @@ namespace units { * @tparam U1 `unit_value_t` to take the square root of. * @sa unit_value_t_traits to access information about the properties of the class, * such as it's unit type and rational value. - * @note very similar in concept to `units::ratio_sqrt` + * @note very similar in concept to `wpi::units::ratio_sqrt` */ template - struct unit_value_sqrt : units::detail::unit_value_arithmetic, units::detail::_unit_value_t::unit_type, Eps>> + struct unit_value_sqrt : wpi::units::detail::unit_value_arithmetic, wpi::units::detail::_unit_value_t::unit_type, Eps>> { /** @cond */ // DOXYGEN IGNORE - using Base = units::detail::unit_value_arithmetic; + using Base = wpi::units::detail::unit_value_arithmetic; using unit_type = square_root; using ratio = ratio_sqrt; @@ -3388,7 +3388,7 @@ namespace units { // value if PI *is* involved static constexpr const unit_t value(std::true_type) noexcept { - return unit_t(((UNIT_LIB_DEFAULT_TYPE)ratio::num / ratio::den) * std::pow(units::constants::detail::PI_VAL, ((UNIT_LIB_DEFAULT_TYPE)pi_exponent::num / pi_exponent::den))); + return unit_t(((UNIT_LIB_DEFAULT_TYPE)ratio::num / ratio::den) * std::pow(wpi::units::constants::detail::PI_VAL, ((UNIT_LIB_DEFAULT_TYPE)pi_exponent::num / pi_exponent::den))); } /** @endcond */ // END DOXYGEN IGNORE }; @@ -3442,8 +3442,8 @@ namespace units { #endif // _MSC_VER #if defined(UNIT_HAS_LITERAL_SUPPORT) -namespace units::literals {} -using namespace units::literals; +namespace wpi::units::literals {} +using namespace wpi::units::literals; #endif // UNIT_HAS_LITERAL_SUPPORT #if __has_include() && !defined(UNIT_LIB_DISABLE_FMT) diff --git a/wpimath/src/main/native/include/wpi/units/capacitance.hpp b/wpimath/src/main/native/include/wpi/units/capacitance.hpp index ee576136f5..0d3a39199f 100644 --- a/wpimath/src/main/native/include/wpi/units/capacitance.hpp +++ b/wpimath/src/main/native/include/wpi/units/capacitance.hpp @@ -28,9 +28,9 @@ #include "wpi/units/base.hpp" -namespace units { +namespace wpi::units { /** - * @namespace units::capacitance + * @namespace wpi::units::capacitance * @brief namespace for unit types and containers representing capacitance * values * @details The SI unit for capacitance is `farads`, and the corresponding @@ -42,10 +42,10 @@ namespace units { defined(ENABLE_PREDEFINED_CAPACITANCE_UNITS) UNIT_ADD_WITH_METRIC_PREFIXES( capacitance, farad, farads, F, - unit, units::category::capacitance_unit>) + unit, wpi::units::category::capacitance_unit>) UNIT_ADD_CATEGORY_TRAIT(capacitance) #endif using namespace capacitance; -} // namespace units +} // namespace wpi::units diff --git a/wpimath/src/main/native/include/wpi/units/charge.hpp b/wpimath/src/main/native/include/wpi/units/charge.hpp index f1aa370c1a..5efd5060ab 100644 --- a/wpimath/src/main/native/include/wpi/units/charge.hpp +++ b/wpimath/src/main/native/include/wpi/units/charge.hpp @@ -30,9 +30,9 @@ #include "wpi/units/current.hpp" #include "wpi/units/time.hpp" -namespace units { +namespace wpi::units { /** - * @namespace units::charge + * @namespace wpi::units::charge * @brief namespace for unit types and containers representing charge values * @details The SI unit for charge is `coulombs`, and the corresponding * `base_unit` category is `charge_unit`. @@ -42,7 +42,7 @@ namespace units { #if !defined(DISABLE_PREDEFINED_UNITS) || \ defined(ENABLE_PREDEFINED_CHARGE_UNITS) UNIT_ADD_WITH_METRIC_PREFIXES(charge, coulomb, coulombs, C, - unit, units::category::charge_unit>) + unit, wpi::units::category::charge_unit>) UNIT_ADD_WITH_METRIC_PREFIXES(charge, ampere_hour, ampere_hours, Ah, compound_unit) @@ -50,4 +50,4 @@ UNIT_ADD_CATEGORY_TRAIT(charge) #endif using namespace charge; -} // namespace units +} // namespace wpi::units diff --git a/wpimath/src/main/native/include/wpi/units/concentration.hpp b/wpimath/src/main/native/include/wpi/units/concentration.hpp index 62c6808fb9..bd48a826ff 100644 --- a/wpimath/src/main/native/include/wpi/units/concentration.hpp +++ b/wpimath/src/main/native/include/wpi/units/concentration.hpp @@ -28,9 +28,9 @@ #include "wpi/units/base.hpp" -namespace units { +namespace wpi::units { /** - * @namespace units::concentration + * @namespace wpi::units::concentration * @brief namespace for unit types and containers representing concentration * values * @details The SI unit for concentration is `parts_per_million`, and the @@ -41,16 +41,16 @@ namespace units { #if !defined(DISABLE_PREDEFINED_UNITS) || \ defined(ENABLE_PREDEFINED_CONCENTRATION_UNITS) UNIT_ADD(concentration, ppm, parts_per_million, ppm, - unit, units::category::scalar_unit>) + unit, wpi::units::category::scalar_unit>) UNIT_ADD(concentration, ppb, parts_per_billion, ppb, unit, parts_per_million>) UNIT_ADD(concentration, ppt, parts_per_trillion, ppt, unit, parts_per_billion>) UNIT_ADD(concentration, percent, percent, pct, - unit, units::category::scalar_unit>) + unit, wpi::units::category::scalar_unit>) UNIT_ADD_CATEGORY_TRAIT(concentration) #endif using namespace concentration; -} // namespace units +} // namespace wpi::units diff --git a/wpimath/src/main/native/include/wpi/units/conductance.hpp b/wpimath/src/main/native/include/wpi/units/conductance.hpp index b0b57c5a0f..6e47f62632 100644 --- a/wpimath/src/main/native/include/wpi/units/conductance.hpp +++ b/wpimath/src/main/native/include/wpi/units/conductance.hpp @@ -28,9 +28,9 @@ #include "wpi/units/base.hpp" -namespace units { +namespace wpi::units { /** - * @namespace units::conductance + * @namespace wpi::units::conductance * @brief namespace for unit types and containers representing conductance * values * @details The SI unit for conductance is `siemens`, and the corresponding @@ -42,10 +42,10 @@ namespace units { defined(ENABLE_PREDEFINED_CONDUCTANCE_UNITS) UNIT_ADD_WITH_METRIC_PREFIXES( conductance, siemens, siemens, S, - unit, units::category::conductance_unit>) + unit, wpi::units::category::conductance_unit>) UNIT_ADD_CATEGORY_TRAIT(conductance) #endif using namespace conductance; -} // namespace units +} // namespace wpi::units diff --git a/wpimath/src/main/native/include/wpi/units/constants.hpp b/wpimath/src/main/native/include/wpi/units/constants.hpp index 22eb4f516c..e11e1e9606 100644 --- a/wpimath/src/main/native/include/wpi/units/constants.hpp +++ b/wpimath/src/main/native/include/wpi/units/constants.hpp @@ -43,7 +43,7 @@ #include "wpi/units/time.hpp" #include "wpi/units/velocity.hpp" -namespace units::constants { +namespace wpi::units::constants { /** * @name Unit Containers * @anchor constantContainers @@ -64,7 +64,7 @@ static constexpr const unit_t> h( static constexpr const unit_t< compound_unit>>> mu0(pi * 4.0e-7 * force::newton_t(1) / - units::math::cpow<2>(current::ampere_t(1))); ///< vacuum permeability. + wpi::units::math::cpow<2>(current::ampere_t(1))); ///< vacuum permeability. static constexpr const unit_t< compound_unit>> epsilon0(1.0 / (mu0 * math::cpow<2>(c))); ///< vacuum permitivity. @@ -99,4 +99,4 @@ static constexpr const unit_t< (15 * math::cpow<3>(h) * math::cpow<2>(c) * math::cpow<4>(N_A))); ///< Stefan-Boltzmann constant. /** @} */ -} // namespace units::constants +} // namespace wpi::units::constants diff --git a/wpimath/src/main/native/include/wpi/units/current.hpp b/wpimath/src/main/native/include/wpi/units/current.hpp index 79d684d5da..da07975668 100644 --- a/wpimath/src/main/native/include/wpi/units/current.hpp +++ b/wpimath/src/main/native/include/wpi/units/current.hpp @@ -28,9 +28,9 @@ #include "wpi/units/base.hpp" -namespace units { +namespace wpi::units { /** - * @namespace units::current + * @namespace wpi::units::current * @brief namespace for unit types and containers representing current values * @details The SI unit for current is `amperes`, and the corresponding * `base_unit` category is `current_unit`. @@ -41,10 +41,10 @@ namespace units { defined(ENABLE_PREDEFINED_CURRENT_UNITS) UNIT_ADD_WITH_METRIC_PREFIXES( current, ampere, amperes, A, - unit, units::category::current_unit>) + unit, wpi::units::category::current_unit>) UNIT_ADD_CATEGORY_TRAIT(current) #endif using namespace current; -} // namespace units +} // namespace wpi::units diff --git a/wpimath/src/main/native/include/wpi/units/curvature.hpp b/wpimath/src/main/native/include/wpi/units/curvature.hpp index e8517583d3..01fbdeb425 100644 --- a/wpimath/src/main/native/include/wpi/units/curvature.hpp +++ b/wpimath/src/main/native/include/wpi/units/curvature.hpp @@ -8,7 +8,7 @@ #include "wpi/units/base.hpp" #include "wpi/units/length.hpp" -namespace units { -using curvature_t = units::unit_t< - units::compound_unit>>; -} // namespace units +namespace wpi::units { +using curvature_t = wpi::units::unit_t< + wpi::units::compound_unit>>; +} // namespace wpi::units diff --git a/wpimath/src/main/native/include/wpi/units/data.hpp b/wpimath/src/main/native/include/wpi/units/data.hpp index 90d51d7bc8..000be5db27 100644 --- a/wpimath/src/main/native/include/wpi/units/data.hpp +++ b/wpimath/src/main/native/include/wpi/units/data.hpp @@ -28,9 +28,9 @@ #include "wpi/units/base.hpp" -namespace units { +namespace wpi::units { /** - * @namespace units::data + * @namespace wpi::units::data * @brief namespace for unit types and containers representing data values * @details The base unit for data is `bytes`, and the corresponding `base_unit` * category is `data_unit`. @@ -39,7 +39,7 @@ namespace units { */ #if !defined(DISABLE_PREDEFINED_UNITS) || defined(ENABLE_PREDEFINED_DATA_UNITS) UNIT_ADD_WITH_METRIC_AND_BINARY_PREFIXES( - data, byte, bytes, B, unit, units::category::data_unit>) + data, byte, bytes, B, unit, wpi::units::category::data_unit>) UNIT_ADD(data, exabyte, exabytes, EB, unit, petabytes>) UNIT_ADD_WITH_METRIC_AND_BINARY_PREFIXES(data, bit, bits, b, unit, byte>) @@ -49,4 +49,4 @@ UNIT_ADD_CATEGORY_TRAIT(data) #endif using namespace data; -} // namespace units +} // namespace wpi::units diff --git a/wpimath/src/main/native/include/wpi/units/data_transfer_rate.hpp b/wpimath/src/main/native/include/wpi/units/data_transfer_rate.hpp index be5f506898..cec0c219c2 100644 --- a/wpimath/src/main/native/include/wpi/units/data_transfer_rate.hpp +++ b/wpimath/src/main/native/include/wpi/units/data_transfer_rate.hpp @@ -28,9 +28,9 @@ #include "wpi/units/base.hpp" -namespace units { +namespace wpi::units { /** - * @namespace units::data_transfer_rate + * @namespace wpi::units::data_transfer_rate * @brief namespace for unit types and containers representing data values * @details The base unit for data is `bytes`, and the corresponding `base_unit` * category is `data_unit`. @@ -41,7 +41,7 @@ namespace units { defined(ENABLE_PREDEFINED_DATA_TRANSFER_RATE_UNITS) UNIT_ADD_WITH_METRIC_AND_BINARY_PREFIXES( data_transfer_rate, bytes_per_second, bytes_per_second, Bps, - unit, units::category::data_transfer_rate_unit>) + unit, wpi::units::category::data_transfer_rate_unit>) UNIT_ADD(data_transfer_rate, exabytes_per_second, exabytes_per_second, EBps, unit, petabytes_per_second>) UNIT_ADD_WITH_METRIC_AND_BINARY_PREFIXES( @@ -54,4 +54,4 @@ UNIT_ADD_CATEGORY_TRAIT(data_transfer_rate) #endif using namespace data_transfer_rate; -} // namespace units +} // namespace wpi::units diff --git a/wpimath/src/main/native/include/wpi/units/density.hpp b/wpimath/src/main/native/include/wpi/units/density.hpp index 4a33ec45f3..48b13f2859 100644 --- a/wpimath/src/main/native/include/wpi/units/density.hpp +++ b/wpimath/src/main/native/include/wpi/units/density.hpp @@ -30,9 +30,9 @@ #include "wpi/units/mass.hpp" #include "wpi/units/volume.hpp" -namespace units { +namespace wpi::units { /** - * @namespace units::density + * @namespace wpi::units::density * @brief namespace for unit types and containers representing density values * @details The SI unit for density is `kilograms_per_cubic_meter`, and the * corresponding `base_unit` category is `density_unit`. @@ -42,7 +42,7 @@ namespace units { #if !defined(DISABLE_PREDEFINED_UNITS) || \ defined(ENABLE_PREDEFINED_DENSITY_UNITS) UNIT_ADD(density, kilograms_per_cubic_meter, kilograms_per_cubic_meter, - kg_per_cu_m, unit, units::category::density_unit>) + kg_per_cu_m, unit, wpi::units::category::density_unit>) UNIT_ADD(density, grams_per_milliliter, grams_per_milliliter, g_per_mL, compound_unit>) UNIT_ADD(density, kilograms_per_liter, kilograms_per_liter, kg_per_L, @@ -67,4 +67,4 @@ UNIT_ADD_CATEGORY_TRAIT(density) #endif using namespace density; -} // namespace units +} // namespace wpi::units diff --git a/wpimath/src/main/native/include/wpi/units/dimensionless.hpp b/wpimath/src/main/native/include/wpi/units/dimensionless.hpp index 1aeed922a1..e62332ce99 100644 --- a/wpimath/src/main/native/include/wpi/units/dimensionless.hpp +++ b/wpimath/src/main/native/include/wpi/units/dimensionless.hpp @@ -28,9 +28,9 @@ #include "wpi/units/base.hpp" -namespace units { +namespace wpi::units { using dimensionless::dB_t; using dimensionless::dimensionless_t; using dimensionless::scalar; using dimensionless::scalar_t; -} // namespace units +} // namespace wpi::units diff --git a/wpimath/src/main/native/include/wpi/units/energy.hpp b/wpimath/src/main/native/include/wpi/units/energy.hpp index 25947dd547..42ccf0103d 100644 --- a/wpimath/src/main/native/include/wpi/units/energy.hpp +++ b/wpimath/src/main/native/include/wpi/units/energy.hpp @@ -28,9 +28,9 @@ #include "wpi/units/base.hpp" -namespace units { +namespace wpi::units { /** - * @namespace units::energy + * @namespace wpi::units::energy * @brief namespace for unit types and containers representing energy values * @details The SI unit for energy is `joules`, and the corresponding * `base_unit` category is `energy_unit`. @@ -40,7 +40,7 @@ namespace units { #if !defined(DISABLE_PREDEFINED_UNITS) || \ defined(ENABLE_PREDEFINED_ENERGY_UNITS) UNIT_ADD_WITH_METRIC_PREFIXES(energy, joule, joules, J, - unit, units::category::energy_unit>) + unit, wpi::units::category::energy_unit>) UNIT_ADD_WITH_METRIC_PREFIXES(energy, calorie, calories, cal, unit, joules>) UNIT_ADD(energy, kilowatt_hour, kilowatt_hours, kWh, @@ -62,4 +62,4 @@ UNIT_ADD_CATEGORY_TRAIT(energy) #endif using namespace energy; -} // namespace units +} // namespace wpi::units diff --git a/wpimath/src/main/native/include/wpi/units/force.hpp b/wpimath/src/main/native/include/wpi/units/force.hpp index 46b2c0e1a0..7188e9690b 100644 --- a/wpimath/src/main/native/include/wpi/units/force.hpp +++ b/wpimath/src/main/native/include/wpi/units/force.hpp @@ -32,9 +32,9 @@ #include "wpi/units/mass.hpp" #include "wpi/units/time.hpp" -namespace units { +namespace wpi::units { /** - * @namespace units::force + * @namespace wpi::units::force * @brief namespace for unit types and containers representing force values * @details The SI unit for force is `newtons`, and the corresponding * `base_unit` category is `force_unit`. @@ -43,7 +43,7 @@ namespace units { */ #if !defined(DISABLE_PREDEFINED_UNITS) || defined(ENABLE_PREDEFINED_FORCE_UNITS) UNIT_ADD_WITH_METRIC_PREFIXES(force, newton, newtons, N, - unit, units::category::force_unit>) + unit, wpi::units::category::force_unit>) UNIT_ADD( force, pound, pounds, lbf, compound_unit>>) @@ -59,4 +59,4 @@ UNIT_ADD_CATEGORY_TRAIT(force) using force::newton_t; using force::newtons; -} // namespace units +} // namespace wpi::units diff --git a/wpimath/src/main/native/include/wpi/units/formatter.hpp b/wpimath/src/main/native/include/wpi/units/formatter.hpp index 504e326c72..fcbc370cde 100644 --- a/wpimath/src/main/native/include/wpi/units/formatter.hpp +++ b/wpimath/src/main/native/include/wpi/units/formatter.hpp @@ -19,7 +19,7 @@ */ template struct fmt::formatter>> { + std::enable_if_t>> { template constexpr auto parse(ParseContext& ctx) { return m_underlying.parse(ctx); @@ -35,182 +35,182 @@ struct fmt::formatter, - typename units::traits::unit_traits::base_unit_type>; + wpi::units::unit, + typename wpi::units::traits::unit_traits::base_unit_type>; auto out = ctx.out(); - out = m_underlying.format(units::convert(obj()), ctx); + out = m_underlying.format(wpi::units::convert(obj()), ctx); - if constexpr (units::traits::unit_traits< + if constexpr (wpi::units::traits::unit_traits< Units>::base_unit_type::meter_ratio::num != 0) { out = fmt::format_to(out, " m"); } - if constexpr (units::traits::unit_traits< + if constexpr (wpi::units::traits::unit_traits< Units>::base_unit_type::meter_ratio::num != 0 && - units::traits::unit_traits< + wpi::units::traits::unit_traits< Units>::base_unit_type::meter_ratio::num != 1) { out = fmt::format_to( out, "^{}", - units::traits::unit_traits::base_unit_type::meter_ratio::num); + wpi::units::traits::unit_traits::base_unit_type::meter_ratio::num); } - if constexpr (units::traits::unit_traits< + if constexpr (wpi::units::traits::unit_traits< Units>::base_unit_type::meter_ratio::den != 1) { out = fmt::format_to( out, "/{}", - units::traits::unit_traits::base_unit_type::meter_ratio::den); + wpi::units::traits::unit_traits::base_unit_type::meter_ratio::den); } - if constexpr (units::traits::unit_traits< + if constexpr (wpi::units::traits::unit_traits< Units>::base_unit_type::kilogram_ratio::num != 0) { out = fmt::format_to(out, " kg"); } - if constexpr (units::traits::unit_traits< + if constexpr (wpi::units::traits::unit_traits< Units>::base_unit_type::kilogram_ratio::num != 0 && - units::traits::unit_traits< + wpi::units::traits::unit_traits< Units>::base_unit_type::kilogram_ratio::num != 1) { out = fmt::format_to(out, "^{}", - units::traits::unit_traits< + wpi::units::traits::unit_traits< Units>::base_unit_type::kilogram_ratio::num); } - if constexpr (units::traits::unit_traits< + if constexpr (wpi::units::traits::unit_traits< Units>::base_unit_type::kilogram_ratio::den != 1) { out = fmt::format_to(out, "/{}", - units::traits::unit_traits< + wpi::units::traits::unit_traits< Units>::base_unit_type::kilogram_ratio::den); } - if constexpr (units::traits::unit_traits< + if constexpr (wpi::units::traits::unit_traits< Units>::base_unit_type::second_ratio::num != 0) { out = fmt::format_to(out, " s"); } - if constexpr (units::traits::unit_traits< + if constexpr (wpi::units::traits::unit_traits< Units>::base_unit_type::second_ratio::num != 0 && - units::traits::unit_traits< + wpi::units::traits::unit_traits< Units>::base_unit_type::second_ratio::num != 1) { out = fmt::format_to( out, "^{}", - units::traits::unit_traits::base_unit_type::second_ratio::num); + wpi::units::traits::unit_traits::base_unit_type::second_ratio::num); } - if constexpr (units::traits::unit_traits< + if constexpr (wpi::units::traits::unit_traits< Units>::base_unit_type::second_ratio::den != 1) { out = fmt::format_to( out, "/{}", - units::traits::unit_traits::base_unit_type::second_ratio::den); + wpi::units::traits::unit_traits::base_unit_type::second_ratio::den); } - if constexpr (units::traits::unit_traits< + if constexpr (wpi::units::traits::unit_traits< Units>::base_unit_type::ampere_ratio::num != 0) { out = fmt::format_to(out, " A"); } - if constexpr (units::traits::unit_traits< + if constexpr (wpi::units::traits::unit_traits< Units>::base_unit_type::ampere_ratio::num != 0 && - units::traits::unit_traits< + wpi::units::traits::unit_traits< Units>::base_unit_type::ampere_ratio::num != 1) { out = fmt::format_to( out, "^{}", - units::traits::unit_traits::base_unit_type::ampere_ratio::num); + wpi::units::traits::unit_traits::base_unit_type::ampere_ratio::num); } - if constexpr (units::traits::unit_traits< + if constexpr (wpi::units::traits::unit_traits< Units>::base_unit_type::ampere_ratio::den != 1) { out = fmt::format_to( out, "/{}", - units::traits::unit_traits::base_unit_type::ampere_ratio::den); + wpi::units::traits::unit_traits::base_unit_type::ampere_ratio::den); } - if constexpr (units::traits::unit_traits< + if constexpr (wpi::units::traits::unit_traits< Units>::base_unit_type::kelvin_ratio::num != 0) { out = fmt::format_to(out, " K"); } - if constexpr (units::traits::unit_traits< + if constexpr (wpi::units::traits::unit_traits< Units>::base_unit_type::kelvin_ratio::num != 0 && - units::traits::unit_traits< + wpi::units::traits::unit_traits< Units>::base_unit_type::kelvin_ratio::num != 1) { out = fmt::format_to( out, "^{}", - units::traits::unit_traits::base_unit_type::kelvin_ratio::num); + wpi::units::traits::unit_traits::base_unit_type::kelvin_ratio::num); } - if constexpr (units::traits::unit_traits< + if constexpr (wpi::units::traits::unit_traits< Units>::base_unit_type::kelvin_ratio::den != 1) { out = fmt::format_to( out, "/{}", - units::traits::unit_traits::base_unit_type::kelvin_ratio::den); + wpi::units::traits::unit_traits::base_unit_type::kelvin_ratio::den); } - if constexpr (units::traits::unit_traits< + if constexpr (wpi::units::traits::unit_traits< Units>::base_unit_type::mole_ratio::num != 0) { out = fmt::format_to(out, " mol"); } - if constexpr (units::traits::unit_traits< + if constexpr (wpi::units::traits::unit_traits< Units>::base_unit_type::mole_ratio::num != 0 && - units::traits::unit_traits< + wpi::units::traits::unit_traits< Units>::base_unit_type::mole_ratio::num != 1) { out = fmt::format_to( out, "^{}", - units::traits::unit_traits::base_unit_type::mole_ratio::num); + wpi::units::traits::unit_traits::base_unit_type::mole_ratio::num); } - if constexpr (units::traits::unit_traits< + if constexpr (wpi::units::traits::unit_traits< Units>::base_unit_type::mole_ratio::den != 1) { out = fmt::format_to( out, "/{}", - units::traits::unit_traits::base_unit_type::mole_ratio::den); + wpi::units::traits::unit_traits::base_unit_type::mole_ratio::den); } - if constexpr (units::traits::unit_traits< + if constexpr (wpi::units::traits::unit_traits< Units>::base_unit_type::candela_ratio::num != 0) { out = fmt::format_to(out, " cd"); } - if constexpr (units::traits::unit_traits< + if constexpr (wpi::units::traits::unit_traits< Units>::base_unit_type::candela_ratio::num != 0 && - units::traits::unit_traits< + wpi::units::traits::unit_traits< Units>::base_unit_type::candela_ratio::num != 1) { out = fmt::format_to(out, "^{}", - units::traits::unit_traits< + wpi::units::traits::unit_traits< Units>::base_unit_type::candela_ratio::num); } - if constexpr (units::traits::unit_traits< + if constexpr (wpi::units::traits::unit_traits< Units>::base_unit_type::candela_ratio::den != 1) { out = fmt::format_to(out, "/{}", - units::traits::unit_traits< + wpi::units::traits::unit_traits< Units>::base_unit_type::candela_ratio::den); } - if constexpr (units::traits::unit_traits< + if constexpr (wpi::units::traits::unit_traits< Units>::base_unit_type::radian_ratio::num != 0) { out = fmt::format_to(out, " rad"); } - if constexpr (units::traits::unit_traits< + if constexpr (wpi::units::traits::unit_traits< Units>::base_unit_type::radian_ratio::num != 0 && - units::traits::unit_traits< + wpi::units::traits::unit_traits< Units>::base_unit_type::radian_ratio::num != 1) { out = fmt::format_to( out, "^{}", - units::traits::unit_traits::base_unit_type::radian_ratio::num); + wpi::units::traits::unit_traits::base_unit_type::radian_ratio::num); } - if constexpr (units::traits::unit_traits< + if constexpr (wpi::units::traits::unit_traits< Units>::base_unit_type::radian_ratio::den != 1) { out = fmt::format_to( out, "/{}", - units::traits::unit_traits::base_unit_type::radian_ratio::den); + wpi::units::traits::unit_traits::base_unit_type::radian_ratio::den); } - if constexpr (units::traits::unit_traits< + if constexpr (wpi::units::traits::unit_traits< Units>::base_unit_type::byte_ratio::num != 0) { out = fmt::format_to(out, " b"); } - if constexpr (units::traits::unit_traits< + if constexpr (wpi::units::traits::unit_traits< Units>::base_unit_type::byte_ratio::num != 0 && - units::traits::unit_traits< + wpi::units::traits::unit_traits< Units>::base_unit_type::byte_ratio::num != 1) { out = fmt::format_to( out, "^{}", - units::traits::unit_traits::base_unit_type::byte_ratio::num); + wpi::units::traits::unit_traits::base_unit_type::byte_ratio::num); } - if constexpr (units::traits::unit_traits< + if constexpr (wpi::units::traits::unit_traits< Units>::base_unit_type::byte_ratio::den != 1) { out = fmt::format_to( out, "/{}", - units::traits::unit_traits::base_unit_type::byte_ratio::den); + wpi::units::traits::unit_traits::base_unit_type::byte_ratio::den); } return out; diff --git a/wpimath/src/main/native/include/wpi/units/frequency.hpp b/wpimath/src/main/native/include/wpi/units/frequency.hpp index 5b61ce1d0b..f73e87740c 100644 --- a/wpimath/src/main/native/include/wpi/units/frequency.hpp +++ b/wpimath/src/main/native/include/wpi/units/frequency.hpp @@ -28,9 +28,9 @@ #include "wpi/units/base.hpp" -namespace units { +namespace wpi::units { /** - * @namespace units::frequency + * @namespace wpi::units::frequency * @brief namespace for unit types and containers representing frequency values * @details The SI unit for frequency is `hertz`, and the corresponding * `base_unit` category is `frequency_unit`. @@ -41,10 +41,10 @@ namespace units { defined(ENABLE_PREDEFINED_FREQUENCY_UNITS) UNIT_ADD_WITH_METRIC_PREFIXES( frequency, hertz, hertz, Hz, - unit, units::category::frequency_unit>) + unit, wpi::units::category::frequency_unit>) UNIT_ADD_CATEGORY_TRAIT(frequency) #endif using namespace frequency; -} // namespace units +} // namespace wpi::units diff --git a/wpimath/src/main/native/include/wpi/units/illuminance.hpp b/wpimath/src/main/native/include/wpi/units/illuminance.hpp index 810d998638..c5d2b1e00b 100644 --- a/wpimath/src/main/native/include/wpi/units/illuminance.hpp +++ b/wpimath/src/main/native/include/wpi/units/illuminance.hpp @@ -30,9 +30,9 @@ #include "wpi/units/length.hpp" #include "wpi/units/luminous_flux.hpp" -namespace units { +namespace wpi::units { /** - * @namespace units::illuminance + * @namespace wpi::units::illuminance * @brief namespace for unit types and containers representing illuminance * values * @details The SI unit for illuminance is `luxes`, and the corresponding @@ -44,7 +44,7 @@ namespace units { defined(ENABLE_PREDEFINED_ILLUMINANCE_UNITS) UNIT_ADD_WITH_METRIC_PREFIXES( illuminance, lux, luxes, lx, - unit, units::category::illuminance_unit>) + unit, wpi::units::category::illuminance_unit>) UNIT_ADD(illuminance, footcandle, footcandles, fc, compound_unit>>) UNIT_ADD(illuminance, lumens_per_square_inch, lumens_per_square_inch, @@ -58,4 +58,4 @@ UNIT_ADD_CATEGORY_TRAIT(illuminance) #endif using namespace illuminance; -} // namespace units +} // namespace wpi::units diff --git a/wpimath/src/main/native/include/wpi/units/impedance.hpp b/wpimath/src/main/native/include/wpi/units/impedance.hpp index aecddd6ea9..74d2631b5a 100644 --- a/wpimath/src/main/native/include/wpi/units/impedance.hpp +++ b/wpimath/src/main/native/include/wpi/units/impedance.hpp @@ -28,9 +28,9 @@ #include "wpi/units/base.hpp" -namespace units { +namespace wpi::units { /** - * @namespace units::impedance + * @namespace wpi::units::impedance * @brief namespace for unit types and containers representing impedance values * @details The SI unit for impedance is `ohms`, and the corresponding * `base_unit` category is `impedance_unit`. @@ -41,10 +41,10 @@ namespace units { defined(ENABLE_PREDEFINED_IMPEDANCE_UNITS) UNIT_ADD_WITH_METRIC_PREFIXES( impedance, ohm, ohms, Ohm, - unit, units::category::impedance_unit>) + unit, wpi::units::category::impedance_unit>) UNIT_ADD_CATEGORY_TRAIT(impedance) #endif using namespace impedance; -} // namespace units +} // namespace wpi::units diff --git a/wpimath/src/main/native/include/wpi/units/inductance.hpp b/wpimath/src/main/native/include/wpi/units/inductance.hpp index 06ee883d6c..328a10e267 100644 --- a/wpimath/src/main/native/include/wpi/units/inductance.hpp +++ b/wpimath/src/main/native/include/wpi/units/inductance.hpp @@ -28,9 +28,9 @@ #include "wpi/units/base.hpp" -namespace units { +namespace wpi::units { /** - * @namespace units::inductance + * @namespace wpi::units::inductance * @brief namespace for unit types and containers representing inductance values * @details The SI unit for inductance is `henrys`, and the corresponding * `base_unit` category is `inductance_unit`. @@ -41,10 +41,10 @@ namespace units { defined(ENABLE_PREDEFINED_INDUCTANCE_UNITS) UNIT_ADD_WITH_METRIC_PREFIXES( inductance, henry, henries, H, - unit, units::category::inductance_unit>) + unit, wpi::units::category::inductance_unit>) UNIT_ADD_CATEGORY_TRAIT(inductance) #endif using namespace inductance; -} // namespace units +} // namespace wpi::units diff --git a/wpimath/src/main/native/include/wpi/units/length.hpp b/wpimath/src/main/native/include/wpi/units/length.hpp index 9e4a5601c9..de174e140a 100644 --- a/wpimath/src/main/native/include/wpi/units/length.hpp +++ b/wpimath/src/main/native/include/wpi/units/length.hpp @@ -28,9 +28,9 @@ #include "wpi/units/base.hpp" -namespace units { +namespace wpi::units { /** - * @namespace units::length + * @namespace wpi::units::length * @brief namespace for unit types and containers representing length values * @details The SI unit for length is `meters`, and the corresponding * `base_unit` category is `length_unit`. @@ -40,7 +40,7 @@ namespace units { #if !defined(DISABLE_PREDEFINED_UNITS) || \ defined(ENABLE_PREDEFINED_LENGTH_UNITS) UNIT_ADD_WITH_METRIC_PREFIXES(length, meter, meters, m, - unit, units::category::length_unit>) + unit, wpi::units::category::length_unit>) UNIT_ADD(length, foot, feet, ft, unit, meters>) UNIT_ADD(length, inch, inches, in, unit, feet>) UNIT_ADD(length, mil, mils, mil, unit, inches>) @@ -69,4 +69,4 @@ UNIT_ADD_CATEGORY_TRAIT(length) #endif using namespace length; -} // namespace units +} // namespace wpi::units diff --git a/wpimath/src/main/native/include/wpi/units/luminous_flux.hpp b/wpimath/src/main/native/include/wpi/units/luminous_flux.hpp index c4b911d8ad..3125e9aee9 100644 --- a/wpimath/src/main/native/include/wpi/units/luminous_flux.hpp +++ b/wpimath/src/main/native/include/wpi/units/luminous_flux.hpp @@ -28,9 +28,9 @@ #include "wpi/units/base.hpp" -namespace units { +namespace wpi::units { /** - * @namespace units::luminous_flux + * @namespace wpi::units::luminous_flux * @brief namespace for unit types and containers representing luminous_flux * values * @details The SI unit for luminous_flux is `lumens`, and the corresponding @@ -42,10 +42,10 @@ namespace units { defined(ENABLE_PREDEFINED_LUMINOUS_FLUX_UNITS) UNIT_ADD_WITH_METRIC_PREFIXES( luminous_flux, lumen, lumens, lm, - unit, units::category::luminous_flux_unit>) + unit, wpi::units::category::luminous_flux_unit>) UNIT_ADD_CATEGORY_TRAIT(luminous_flux) #endif using namespace luminous_flux; -} // namespace units +} // namespace wpi::units diff --git a/wpimath/src/main/native/include/wpi/units/luminous_intensity.hpp b/wpimath/src/main/native/include/wpi/units/luminous_intensity.hpp index 8ea92230a2..88753ea5c7 100644 --- a/wpimath/src/main/native/include/wpi/units/luminous_intensity.hpp +++ b/wpimath/src/main/native/include/wpi/units/luminous_intensity.hpp @@ -28,9 +28,9 @@ #include "wpi/units/base.hpp" -namespace units { +namespace wpi::units { /** - * @namespace units::luminous_intensity + * @namespace wpi::units::luminous_intensity * @brief namespace for unit types and containers representing * luminous_intensity values * @details The SI unit for luminous_intensity is `candelas`, and the @@ -42,10 +42,10 @@ namespace units { defined(ENABLE_PREDEFINED_LUMINOUS_INTENSITY_UNITS) UNIT_ADD_WITH_METRIC_PREFIXES( luminous_intensity, candela, candelas, cd, - unit, units::category::luminous_intensity_unit>) + unit, wpi::units::category::luminous_intensity_unit>) UNIT_ADD_CATEGORY_TRAIT(luminous_intensity) #endif using namespace luminous_intensity; -} // namespace units +} // namespace wpi::units diff --git a/wpimath/src/main/native/include/wpi/units/magnetic_field_strength.hpp b/wpimath/src/main/native/include/wpi/units/magnetic_field_strength.hpp index e69d44c50e..de2b52a15d 100644 --- a/wpimath/src/main/native/include/wpi/units/magnetic_field_strength.hpp +++ b/wpimath/src/main/native/include/wpi/units/magnetic_field_strength.hpp @@ -30,9 +30,9 @@ #include "wpi/units/length.hpp" #include "wpi/units/magnetic_flux.hpp" -namespace units { +namespace wpi::units { /** - * @namespace units::magnetic_field_strength + * @namespace wpi::units::magnetic_field_strength * @brief namespace for unit types and containers representing * magnetic_field_strength values * @details The SI unit for magnetic_field_strength is `teslas`, and the @@ -47,7 +47,7 @@ namespace units { defined(ENABLE_PREDEFINED_MAGNETIC_FIELD_STRENGTH_UNITS) UNIT_ADD_WITH_METRIC_PREFIXES( magnetic_field_strength, tesla, teslas, Te, - unit, units::category::magnetic_field_strength_unit>) + unit, wpi::units::category::magnetic_field_strength_unit>) UNIT_ADD( magnetic_field_strength, gauss, gauss, G, compound_unit>>) @@ -56,4 +56,4 @@ UNIT_ADD_CATEGORY_TRAIT(magnetic_field_strength) #endif using namespace magnetic_field_strength; -} // namespace units +} // namespace wpi::units diff --git a/wpimath/src/main/native/include/wpi/units/magnetic_flux.hpp b/wpimath/src/main/native/include/wpi/units/magnetic_flux.hpp index 8aac7d002c..906b592586 100644 --- a/wpimath/src/main/native/include/wpi/units/magnetic_flux.hpp +++ b/wpimath/src/main/native/include/wpi/units/magnetic_flux.hpp @@ -28,9 +28,9 @@ #include "wpi/units/base.hpp" -namespace units { +namespace wpi::units { /** - * @namespace units::magnetic_flux + * @namespace wpi::units::magnetic_flux * @brief namespace for unit types and containers representing magnetic_flux * values * @details The SI unit for magnetic_flux is `webers`, and the corresponding @@ -42,7 +42,7 @@ namespace units { defined(ENABLE_PREDEFINED_MAGNETIC_FLUX_UNITS) UNIT_ADD_WITH_METRIC_PREFIXES( magnetic_flux, weber, webers, Wb, - unit, units::category::magnetic_flux_unit>) + unit, wpi::units::category::magnetic_flux_unit>) UNIT_ADD(magnetic_flux, maxwell, maxwells, Mx, unit, webers>) @@ -50,4 +50,4 @@ UNIT_ADD_CATEGORY_TRAIT(magnetic_flux) #endif using namespace magnetic_flux; -} // namespace units +} // namespace wpi::units diff --git a/wpimath/src/main/native/include/wpi/units/mass.hpp b/wpimath/src/main/native/include/wpi/units/mass.hpp index 7d12105f7b..78883fb11c 100644 --- a/wpimath/src/main/native/include/wpi/units/mass.hpp +++ b/wpimath/src/main/native/include/wpi/units/mass.hpp @@ -28,9 +28,9 @@ #include "wpi/units/base.hpp" -namespace units { +namespace wpi::units { /** - * @namespace units::mass + * @namespace wpi::units::mass * @brief namespace for unit types and containers representing mass values * @details The SI unit for mass is `kilograms`, and the corresponding * `base_unit` category is `mass_unit`. @@ -39,7 +39,7 @@ namespace units { */ #if !defined(DISABLE_PREDEFINED_UNITS) || defined(ENABLE_PREDEFINED_MASS_UNITS) UNIT_ADD_WITH_METRIC_PREFIXES( - mass, gram, grams, g, unit, units::category::mass_unit>) + mass, gram, grams, g, unit, wpi::units::category::mass_unit>) UNIT_ADD(mass, metric_ton, metric_tons, t, unit, kilograms>) UNIT_ADD(mass, pound, pounds, lb, unit, kilograms>) @@ -55,4 +55,4 @@ UNIT_ADD_CATEGORY_TRAIT(mass) #endif using namespace mass; -} // namespace units +} // namespace wpi::units diff --git a/wpimath/src/main/native/include/wpi/units/math.hpp b/wpimath/src/main/native/include/wpi/units/math.hpp index 70ea967eb3..988e5aad9c 100644 --- a/wpimath/src/main/native/include/wpi/units/math.hpp +++ b/wpimath/src/main/native/include/wpi/units/math.hpp @@ -44,7 +44,7 @@ * rounding functions, etc. * @sa See `unit_t` for more information on unit type containers. */ -namespace units::math { +namespace wpi::units::math { //---------------------------------- // TRIGONOMETRIC FUNCTIONS //---------------------------------- @@ -185,7 +185,7 @@ constexpr angle::radian_t atan2(const Y y, const X x) noexcept { // X and Y could be different length units, so normalize them return angle::radian_t( gcem::atan2(y.template convert< - typename units::traits::unit_t_traits::unit_type>()(), + typename wpi::units::traits::unit_t_traits::unit_type>()(), x())); } #endif @@ -298,7 +298,7 @@ constexpr angle::radian_t asinh(const ScalarUnit x) noexcept { * @param[in] x Value whose arc hyperbolic tangent is computed, in the interval * [-1,+1]. If the argument is out of this interval, a domain error * occurs. For values of -1 and +1, a pole error may occur. - * @returns units::angle::radian_t + * @returns wpi::units::angle::radian_t */ #if !defined(DISABLE_PREDEFINED_UNITS) || defined(ENABLE_PREDEFINED_ANGLE_UNITS) template @@ -481,14 +481,14 @@ constexpr dimensionless::scalar_t log2(const ScalarUnit x) noexcept { */ template < class UnitType, - std::enable_if_t::value, int> = 0> + std::enable_if_t::value, int> = 0> inline constexpr auto sqrt(const UnitType& value) noexcept -> unit_t< - square_root::unit_type>, - typename units::traits::unit_t_traits::underlying_type, + square_root::unit_type>, + typename wpi::units::traits::unit_t_traits::underlying_type, linear_scale> { return unit_t< - square_root::unit_type>, - typename units::traits::unit_t_traits::underlying_type, + square_root::unit_type>, + typename wpi::units::traits::unit_t_traits::underlying_type, linear_scale>(gcem::sqrt(value())); } @@ -502,7 +502,7 @@ inline constexpr auto sqrt(const UnitType& value) noexcept -> unit_t< */ template ::value, + wpi::units::traits::has_linear_scale::value, int> = 0> inline constexpr UnitTypeLhs hypot(const UnitTypeLhs& x, const UnitTypeRhs& y) { static_assert(traits::is_convertible_unit_t::value, @@ -510,7 +510,7 @@ inline constexpr UnitTypeLhs hypot(const UnitTypeLhs& x, const UnitTypeRhs& y) { return UnitTypeLhs(gcem::hypot( x(), y.template convert< - typename units::traits::unit_t_traits::unit_type>()())); + typename wpi::units::traits::unit_t_traits::unit_type>()())); } //---------------------------------- @@ -564,7 +564,7 @@ constexpr UnitTypeLhs fmod(const UnitTypeLhs numer, return UnitTypeLhs(gcem::fmod( numer(), denom.template convert< - typename units::traits::unit_t_traits::unit_type>()())); + typename wpi::units::traits::unit_t_traits::unit_type>()())); } /** @@ -648,7 +648,7 @@ UnitTypeLhs fdim(const UnitTypeLhs x, const UnitTypeRhs y) noexcept { return UnitTypeLhs(std::fdim( x(), y.template convert< - typename units::traits::unit_t_traits::unit_type>()())); + typename wpi::units::traits::unit_t_traits::unit_type>()())); } /** @@ -670,7 +670,7 @@ constexpr UnitTypeLhs fmax(const UnitTypeLhs x, const UnitTypeRhs y) noexcept { return UnitTypeLhs(gcem::max( x(), y.template convert< - typename units::traits::unit_t_traits::unit_type>()())); + typename wpi::units::traits::unit_t_traits::unit_type>()())); } /** @@ -693,7 +693,7 @@ constexpr UnitTypeLhs fmin(const UnitTypeLhs x, const UnitTypeRhs y) noexcept { return UnitTypeLhs(gcem::min( x(), y.template convert< - typename units::traits::unit_t_traits::unit_type>()())); + typename wpi::units::traits::unit_t_traits::unit_type>()())); } //---------------------------------- @@ -747,10 +747,10 @@ auto fma(const UnitTypeLhs x, const UnitMultiply y, const UnitAdd z) noexcept static_assert( traits::is_convertible_unit_t< compound_unit< - typename units::traits::unit_t_traits::unit_type, - typename units::traits::unit_t_traits::unit_type>, - typename units::traits::unit_t_traits::unit_type>::value, + typename wpi::units::traits::unit_t_traits::unit_type, + typename wpi::units::traits::unit_t_traits::unit_type>, + typename wpi::units::traits::unit_t_traits::unit_type>::value, "Unit types are not compatible."); return resultType(std::fma(x(), y(), resultType(z)())); } -} // namespace units::math +} // namespace wpi::units::math diff --git a/wpimath/src/main/native/include/wpi/units/moment_of_inertia.hpp b/wpimath/src/main/native/include/wpi/units/moment_of_inertia.hpp index af58c9071b..570a6355aa 100644 --- a/wpimath/src/main/native/include/wpi/units/moment_of_inertia.hpp +++ b/wpimath/src/main/native/include/wpi/units/moment_of_inertia.hpp @@ -8,9 +8,9 @@ #include "wpi/units/base.hpp" #include "wpi/units/mass.hpp" -namespace units { +namespace wpi::units { UNIT_ADD(moment_of_inertia, kilogram_square_meter, kilogram_square_meters, kg_sq_m, compound_unit) using namespace moment_of_inertia; -} // namespace units +} // namespace wpi::units diff --git a/wpimath/src/main/native/include/wpi/units/power.hpp b/wpimath/src/main/native/include/wpi/units/power.hpp index 6beca87912..c9a31cb70a 100644 --- a/wpimath/src/main/native/include/wpi/units/power.hpp +++ b/wpimath/src/main/native/include/wpi/units/power.hpp @@ -28,9 +28,9 @@ #include "wpi/units/base.hpp" -namespace units { +namespace wpi::units { /** - * @namespace units::power + * @namespace wpi::units::power * @brief namespace for unit types and containers representing power values * @details The SI unit for power is `watts`, and the corresponding `base_unit` * category is `power_unit`. @@ -39,7 +39,7 @@ namespace units { */ #if !defined(DISABLE_PREDEFINED_UNITS) || defined(ENABLE_PREDEFINED_POWER_UNITS) UNIT_ADD_WITH_METRIC_PREFIXES(power, watt, watts, W, - unit, units::category::power_unit>) + unit, wpi::units::category::power_unit>) UNIT_ADD(power, horsepower, horsepower, hp, unit, watts>) UNIT_ADD_DECIBEL(power, watt, dBW) UNIT_ADD_DECIBEL(power, milliwatt, dBm) @@ -48,4 +48,4 @@ UNIT_ADD_CATEGORY_TRAIT(power) #endif using namespace power; -} // namespace units +} // namespace wpi::units diff --git a/wpimath/src/main/native/include/wpi/units/pressure.hpp b/wpimath/src/main/native/include/wpi/units/pressure.hpp index 453230f881..f373980553 100644 --- a/wpimath/src/main/native/include/wpi/units/pressure.hpp +++ b/wpimath/src/main/native/include/wpi/units/pressure.hpp @@ -30,9 +30,9 @@ #include "wpi/units/force.hpp" #include "wpi/units/length.hpp" -namespace units { +namespace wpi::units { /** - * @namespace units::pressure + * @namespace wpi::units::pressure * @brief namespace for unit types and containers representing pressure values * @details The SI unit for pressure is `pascals`, and the corresponding * `base_unit` category is `pressure_unit`. @@ -43,7 +43,7 @@ namespace units { defined(ENABLE_PREDEFINED_PRESSURE_UNITS) UNIT_ADD_WITH_METRIC_PREFIXES( pressure, pascal, pascals, Pa, - unit, units::category::pressure_unit>) + unit, wpi::units::category::pressure_unit>) UNIT_ADD(pressure, bar, bars, bar, unit, kilo>) UNIT_ADD(pressure, mbar, mbars, mbar, unit, milli>) UNIT_ADD(pressure, atmosphere, atmospheres, atm, @@ -56,4 +56,4 @@ UNIT_ADD_CATEGORY_TRAIT(pressure) #endif using namespace pressure; -} // namespace units +} // namespace wpi::units diff --git a/wpimath/src/main/native/include/wpi/units/radiation.hpp b/wpimath/src/main/native/include/wpi/units/radiation.hpp index 99e46117a5..2916b4006d 100644 --- a/wpimath/src/main/native/include/wpi/units/radiation.hpp +++ b/wpimath/src/main/native/include/wpi/units/radiation.hpp @@ -37,9 +37,9 @@ #include "wpi/units/frequency.hpp" #include "wpi/units/mass.hpp" -namespace units { +namespace wpi::units { /** - * @namespace units::radiation + * @namespace wpi::units::radiation * @brief namespace for unit types and containers representing radiation values * @details The SI units for radiation are: * - source activity: becquerel @@ -51,7 +51,7 @@ namespace units { #if !defined(DISABLE_PREDEFINED_UNITS) || \ defined(ENABLE_PREDEFINED_RADIATION_UNITS) UNIT_ADD_WITH_METRIC_PREFIXES(radiation, becquerel, becquerels, Bq, - unit, units::frequency::hertz>) + unit, wpi::units::frequency::hertz>) UNIT_ADD_WITH_METRIC_PREFIXES( radiation, gray, grays, Gy, compound_unit>) @@ -66,4 +66,4 @@ UNIT_ADD_CATEGORY_TRAIT(radioactivity) #endif using namespace radiation; -} // namespace units +} // namespace wpi::units diff --git a/wpimath/src/main/native/include/wpi/units/solid_angle.hpp b/wpimath/src/main/native/include/wpi/units/solid_angle.hpp index c265b51efe..9fd2bbee90 100644 --- a/wpimath/src/main/native/include/wpi/units/solid_angle.hpp +++ b/wpimath/src/main/native/include/wpi/units/solid_angle.hpp @@ -29,9 +29,9 @@ #include "wpi/units/angle.hpp" #include "wpi/units/base.hpp" -namespace units { +namespace wpi::units { /** - * @namespace units::solid_angle + * @namespace wpi::units::solid_angle * @brief namespace for unit types and containers representing solid_angle * values * @details The SI unit for solid_angle is `steradians`, and the corresponding @@ -43,7 +43,7 @@ namespace units { defined(ENABLE_PREDEFINED_SOLID_ANGLE_UNITS) UNIT_ADD_WITH_METRIC_PREFIXES( solid_angle, steradian, steradians, sr, - unit, units::category::solid_angle_unit>) + unit, wpi::units::category::solid_angle_unit>) UNIT_ADD(solid_angle, degree_squared, degrees_squared, sq_deg, squared) UNIT_ADD(solid_angle, spat, spats, sp, @@ -53,4 +53,4 @@ UNIT_ADD_CATEGORY_TRAIT(solid_angle) #endif using namespace solid_angle; -} // namespace units +} // namespace wpi::units diff --git a/wpimath/src/main/native/include/wpi/units/substance.hpp b/wpimath/src/main/native/include/wpi/units/substance.hpp index b9c57b02af..ec9b50295a 100644 --- a/wpimath/src/main/native/include/wpi/units/substance.hpp +++ b/wpimath/src/main/native/include/wpi/units/substance.hpp @@ -28,9 +28,9 @@ #include "wpi/units/base.hpp" -namespace units { +namespace wpi::units { /** - * @namespace units::substance + * @namespace wpi::units::substance * @brief namespace for unit types and containers representing substance values * @details The SI unit for substance is `moles`, and the corresponding * `base_unit` category is `substance_unit`. @@ -40,10 +40,10 @@ namespace units { #if !defined(DISABLE_PREDEFINED_UNITS) || \ defined(ENABLE_PREDEFINED_SUBSTANCE_UNITS) UNIT_ADD(substance, mole, moles, mol, - unit, units::category::substance_unit>) + unit, wpi::units::category::substance_unit>) UNIT_ADD_CATEGORY_TRAIT(substance) #endif using namespace substance; -} // namespace units +} // namespace wpi::units diff --git a/wpimath/src/main/native/include/wpi/units/temperature.hpp b/wpimath/src/main/native/include/wpi/units/temperature.hpp index f7c538ab5c..c14e035ffc 100644 --- a/wpimath/src/main/native/include/wpi/units/temperature.hpp +++ b/wpimath/src/main/native/include/wpi/units/temperature.hpp @@ -28,12 +28,12 @@ #include "wpi/units/base.hpp" -namespace units { +namespace wpi::units { // NOTE: temperature units have special conversion overloads, since they // require translations and aren't a reversible transform. /** - * @namespace units::temperature + * @namespace wpi::units::temperature * @brief namespace for unit types and containers representing temperature * values * @details The SI unit for temperature is `kelvin`, and the corresponding @@ -44,7 +44,7 @@ namespace units { #if !defined(DISABLE_PREDEFINED_UNITS) || \ defined(ENABLE_PREDEFINED_TEMPERATURE_UNITS) UNIT_ADD(temperature, kelvin, kelvin, K, - unit, units::category::temperature_unit>) + unit, wpi::units::category::temperature_unit>) UNIT_ADD(temperature, celsius, celsius, degC, unit, kelvin, std::ratio<0>, std::ratio<27315, 100>>) UNIT_ADD(temperature, fahrenheit, fahrenheit, degF, @@ -56,4 +56,4 @@ UNIT_ADD_CATEGORY_TRAIT(temperature) #endif using namespace temperature; -} // namespace units +} // namespace wpi::units diff --git a/wpimath/src/main/native/include/wpi/units/time.hpp b/wpimath/src/main/native/include/wpi/units/time.hpp index 8ddf69625b..ede6f51bff 100644 --- a/wpimath/src/main/native/include/wpi/units/time.hpp +++ b/wpimath/src/main/native/include/wpi/units/time.hpp @@ -28,9 +28,9 @@ #include "wpi/units/base.hpp" -namespace units { +namespace wpi::units { /** - * @namespace units::time + * @namespace wpi::units::time * @brief namespace for unit types and containers representing time values * @details The SI unit for time is `seconds`, and the corresponding `base_unit` * category is `time_unit`. @@ -39,7 +39,7 @@ namespace units { */ #if !defined(DISABLE_PREDEFINED_UNITS) || defined(ENABLE_PREDEFINED_TIME_UNITS) UNIT_ADD_WITH_METRIC_PREFIXES(time, second, seconds, s, - unit, units::category::time_unit>) + unit, wpi::units::category::time_unit>) UNIT_ADD(time, minute, minutes, min, unit, seconds>) UNIT_ADD(time, hour, hours, hr, unit, minutes>) UNIT_ADD(time, day, days, d, unit, hours>) @@ -54,4 +54,4 @@ UNIT_ADD_CATEGORY_TRAIT(time) #endif using namespace time; -} // namespace units +} // namespace wpi::units diff --git a/wpimath/src/main/native/include/wpi/units/torque.hpp b/wpimath/src/main/native/include/wpi/units/torque.hpp index da2fb691b1..0c06e8c54a 100644 --- a/wpimath/src/main/native/include/wpi/units/torque.hpp +++ b/wpimath/src/main/native/include/wpi/units/torque.hpp @@ -31,9 +31,9 @@ #include "wpi/units/force.hpp" #include "wpi/units/length.hpp" -namespace units { +namespace wpi::units { /** - * @namespace units::torque + * @namespace wpi::units::torque * @brief namespace for unit types and containers representing torque values * @details The SI unit for torque is `newton_meters`, and the corresponding * `base_unit` category is `torque_units`. @@ -43,7 +43,7 @@ namespace units { #if !defined(DISABLE_PREDEFINED_UNITS) || \ defined(ENABLE_PREDEFINED_TORQUE_UNITS) UNIT_ADD(torque, newton_meter, newton_meters, Nm, - unit, units::energy::joule>) + unit, wpi::units::energy::joule>) UNIT_ADD(torque, foot_pound, foot_pounds, ftlb, compound_unit) UNIT_ADD(torque, foot_poundal, foot_poundals, ftpdl, @@ -57,4 +57,4 @@ UNIT_ADD_CATEGORY_TRAIT(torque) #endif using namespace torque; -} // namespace units +} // namespace wpi::units diff --git a/wpimath/src/main/native/include/wpi/units/velocity.hpp b/wpimath/src/main/native/include/wpi/units/velocity.hpp index 88dd43af63..09c24c055d 100644 --- a/wpimath/src/main/native/include/wpi/units/velocity.hpp +++ b/wpimath/src/main/native/include/wpi/units/velocity.hpp @@ -30,9 +30,9 @@ #include "wpi/units/length.hpp" #include "wpi/units/time.hpp" -namespace units { +namespace wpi::units { /** - * @namespace units::velocity + * @namespace wpi::units::velocity * @brief namespace for unit types and containers representing velocity values * @details The SI unit for velocity is `meters_per_second`, and the * corresponding `base_unit` category is `velocity_unit`. @@ -42,7 +42,7 @@ namespace units { #if !defined(DISABLE_PREDEFINED_UNITS) || \ defined(ENABLE_PREDEFINED_VELOCITY_UNITS) UNIT_ADD(velocity, meters_per_second, meters_per_second, mps, - unit, units::category::velocity_unit>) + unit, wpi::units::category::velocity_unit>) UNIT_ADD(velocity, feet_per_second, feet_per_second, fps, compound_unit>) UNIT_ADD(velocity, miles_per_hour, miles_per_hour, mph, @@ -56,4 +56,4 @@ UNIT_ADD_CATEGORY_TRAIT(velocity) #endif using namespace velocity; -} // namespace units +} // namespace wpi::units diff --git a/wpimath/src/main/native/include/wpi/units/voltage.hpp b/wpimath/src/main/native/include/wpi/units/voltage.hpp index 844775ebe7..4f2b88724b 100644 --- a/wpimath/src/main/native/include/wpi/units/voltage.hpp +++ b/wpimath/src/main/native/include/wpi/units/voltage.hpp @@ -28,9 +28,9 @@ #include "wpi/units/base.hpp" -namespace units { +namespace wpi::units { /** - * @namespace units::voltage + * @namespace wpi::units::voltage * @brief namespace for unit types and containers representing voltage values * @details The SI unit for voltage is `volts`, and the corresponding * `base_unit` category is `voltage_unit`. @@ -40,7 +40,7 @@ namespace units { #if !defined(DISABLE_PREDEFINED_UNITS) || \ defined(ENABLE_PREDEFINED_VOLTAGE_UNITS) UNIT_ADD_WITH_METRIC_PREFIXES( - voltage, volt, volts, V, unit, units::category::voltage_unit>) + voltage, volt, volts, V, unit, wpi::units::category::voltage_unit>) UNIT_ADD(voltage, statvolt, statvolts, statV, unit, volts>) UNIT_ADD(voltage, abvolt, abvolts, abV, unit, volts>) @@ -49,4 +49,4 @@ UNIT_ADD_CATEGORY_TRAIT(voltage) #endif using namespace voltage; -} // namespace units +} // namespace wpi::units diff --git a/wpimath/src/main/native/include/wpi/units/volume.hpp b/wpimath/src/main/native/include/wpi/units/volume.hpp index 87bac25f6e..9ad18f7bf7 100644 --- a/wpimath/src/main/native/include/wpi/units/volume.hpp +++ b/wpimath/src/main/native/include/wpi/units/volume.hpp @@ -29,9 +29,9 @@ #include "wpi/units/base.hpp" #include "wpi/units/length.hpp" -namespace units { +namespace wpi::units { /** - * @namespace units::volume + * @namespace wpi::units::volume * @brief namespace for unit types and containers representing volume values * @details The SI unit for volume is `cubic_meters`, and the corresponding * `base_unit` category is `volume_unit`. @@ -41,7 +41,7 @@ namespace units { #if !defined(DISABLE_PREDEFINED_UNITS) || \ defined(ENABLE_PREDEFINED_VOLUME_UNITS) UNIT_ADD(volume, cubic_meter, cubic_meters, cu_m, - unit, units::category::volume_unit>) + unit, wpi::units::category::volume_unit>) UNIT_ADD(volume, cubic_millimeter, cubic_millimeters, cu_mm, cubed) UNIT_ADD(volume, cubic_kilometer, cubic_kilometers, cu_km, @@ -80,4 +80,4 @@ UNIT_ADD_CATEGORY_TRAIT(volume) #endif using namespace volume; -} // namespace units +} // namespace wpi::units diff --git a/wpimath/src/main/native/thirdparty/sleipnir/include/gch/small_vector.hpp b/wpimath/src/main/native/thirdparty/sleipnir/include/gch/small_vector.hpp index 25f6710e9f..cd6ef22e05 100644 --- a/wpimath/src/main/native/thirdparty/sleipnir/include/gch/small_vector.hpp +++ b/wpimath/src/main/native/thirdparty/sleipnir/include/gch/small_vector.hpp @@ -7,6 +7,6 @@ namespace gch { template -using small_vector = wpi::SmallVector; +using small_vector = wpi::util::SmallVector; } // namespace gch diff --git a/wpimath/src/main/native/thirdparty/sleipnir/include/sleipnir/util/spy.hpp b/wpimath/src/main/native/thirdparty/sleipnir/include/sleipnir/util/spy.hpp index 43dcc748b6..74dd7990b0 100644 --- a/wpimath/src/main/native/thirdparty/sleipnir/include/sleipnir/util/spy.hpp +++ b/wpimath/src/main/native/thirdparty/sleipnir/include/sleipnir/util/spy.hpp @@ -116,7 +116,7 @@ class SLEIPNIR_DLLEXPORT Spy { */ void write32le(int32_t num) { if constexpr (std::endian::native != std::endian::little) { - num = wpi::byteswap(num); + num = wpi::util::byteswap(num); } m_file.write(reinterpret_cast(&num), sizeof(num)); } diff --git a/wpimath/src/main/python/pyproject.toml b/wpimath/src/main/python/pyproject.toml index 1b2de2631f..e58f426316 100644 --- a/wpimath/src/main/python/pyproject.toml +++ b/wpimath/src/main/python/pyproject.toml @@ -115,1344 +115,1344 @@ includedir = ["wpimath/_impl/src", "wpimath/_impl/src/type_casters"] [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_acceleration_type_caster.h" types = [ - "units::feet_per_second_squared_t", - "units::meters_per_second_squared_t", - "units::standard_gravity_t", + "wpi::units::feet_per_second_squared_t", + "wpi::units::meters_per_second_squared_t", + "wpi::units::standard_gravity_t", ] default_arg_cast = true [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_acceleration_type_caster.h" types = [ - "units::feet_per_second_squared", - "units::feet_per_second_squared", - "units::meters_per_second_squared", - "units::meters_per_second_squared", - "units::standard_gravity", - "units::standard_gravity", + "wpi::units::feet_per_second_squared", + "wpi::units::feet_per_second_squared", + "wpi::units::meters_per_second_squared", + "wpi::units::meters_per_second_squared", + "wpi::units::standard_gravity", + "wpi::units::standard_gravity", ] default_arg_cast = false [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_angle_type_caster.h" types = [ - "units::arcminute_t", - "units::arcsecond_t", - "units::degree_t", - "units::gradian_t", - "units::kiloradian_t", - "units::microradian_t", - "units::milliarcsecond_t", - "units::milliradian_t", - "units::nanoradian_t", - "units::radian_t", - "units::turn_t", + "wpi::units::arcminute_t", + "wpi::units::arcsecond_t", + "wpi::units::degree_t", + "wpi::units::gradian_t", + "wpi::units::kiloradian_t", + "wpi::units::microradian_t", + "wpi::units::milliarcsecond_t", + "wpi::units::milliradian_t", + "wpi::units::nanoradian_t", + "wpi::units::radian_t", + "wpi::units::turn_t", ] default_arg_cast = true [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_angle_type_caster.h" types = [ - "units::arcminute", - "units::arcminutes", - "units::arcsecond", - "units::arcseconds", - "units::degree", - "units::degrees", - "units::gradian", - "units::gradians", - "units::kiloradian", - "units::kiloradians", - "units::microradian", - "units::microradians", - "units::milliarcsecond", - "units::milliarcseconds", - "units::milliradian", - "units::milliradians", - "units::nanoradian", - "units::nanoradians", - "units::radian", - "units::radians", - "units::turn", - "units::turns", + "wpi::units::arcminute", + "wpi::units::arcminutes", + "wpi::units::arcsecond", + "wpi::units::arcseconds", + "wpi::units::degree", + "wpi::units::degrees", + "wpi::units::gradian", + "wpi::units::gradians", + "wpi::units::kiloradian", + "wpi::units::kiloradians", + "wpi::units::microradian", + "wpi::units::microradians", + "wpi::units::milliarcsecond", + "wpi::units::milliarcseconds", + "wpi::units::milliradian", + "wpi::units::milliradians", + "wpi::units::nanoradian", + "wpi::units::nanoradians", + "wpi::units::radian", + "wpi::units::radians", + "wpi::units::turn", + "wpi::units::turns", ] default_arg_cast = false [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_angular_acceleration_type_caster.h" types = [ - "units::radians_per_second_squared_t", - "units::degrees_per_second_squared_t", - "units::turns_per_second_squared_t", + "wpi::units::radians_per_second_squared_t", + "wpi::units::degrees_per_second_squared_t", + "wpi::units::turns_per_second_squared_t", ] default_arg_cast = true [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_angular_acceleration_type_caster.h" types = [ - "units::radians_per_second_squared", - "units::degrees_per_second_squared", - "units::turns_per_second_squared", + "wpi::units::radians_per_second_squared", + "wpi::units::degrees_per_second_squared", + "wpi::units::turns_per_second_squared", ] default_arg_cast = false [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_angular_velocity_type_caster.h" types = [ - "units::degrees_per_second_t", - "units::milliarcseconds_per_year_t", - "units::radians_per_second_t", - "units::turns_per_second_t", - "units::revolutions_per_minute_t", + "wpi::units::degrees_per_second_t", + "wpi::units::milliarcseconds_per_year_t", + "wpi::units::radians_per_second_t", + "wpi::units::turns_per_second_t", + "wpi::units::revolutions_per_minute_t", ] default_arg_cast = true [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_angular_velocity_type_caster.h" types = [ - "units::degrees_per_second", - "units::milliarcseconds_per_year", - "units::radians_per_second", - "units::turns_per_second", - "units::revolutions_per_minute", + "wpi::units::degrees_per_second", + "wpi::units::milliarcseconds_per_year", + "wpi::units::radians_per_second", + "wpi::units::turns_per_second", + "wpi::units::revolutions_per_minute", ] default_arg_cast = false [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_area_type_caster.h" types = [ - "units::acre_t", - "units::hectare_t", - "units::square_foot_t", - "units::square_inch_t", - "units::square_kilometer_t", - "units::square_meter_t", - "units::square_mile_t", + "wpi::units::acre_t", + "wpi::units::hectare_t", + "wpi::units::square_foot_t", + "wpi::units::square_inch_t", + "wpi::units::square_kilometer_t", + "wpi::units::square_meter_t", + "wpi::units::square_mile_t", ] default_arg_cast = true [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_area_type_caster.h" types = [ - "units::acre", - "units::acres", - "units::hectare", - "units::hectares", - "units::square_feet", - "units::square_foot", - "units::square_inch", - "units::square_inches", - "units::square_kilometer", - "units::square_kilometers", - "units::square_meter", - "units::square_meters", - "units::square_mile", - "units::square_miles", + "wpi::units::acre", + "wpi::units::acres", + "wpi::units::hectare", + "wpi::units::hectares", + "wpi::units::square_feet", + "wpi::units::square_foot", + "wpi::units::square_inch", + "wpi::units::square_inches", + "wpi::units::square_kilometer", + "wpi::units::square_kilometers", + "wpi::units::square_meter", + "wpi::units::square_meters", + "wpi::units::square_mile", + "wpi::units::square_miles", ] default_arg_cast = false [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_capacitance_type_caster.h" types = [ - "units::farad_t", - "units::kilofarad_t", - "units::microfarad_t", - "units::millifarad_t", - "units::nanofarad_t", + "wpi::units::farad_t", + "wpi::units::kilofarad_t", + "wpi::units::microfarad_t", + "wpi::units::millifarad_t", + "wpi::units::nanofarad_t", ] default_arg_cast = true [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_capacitance_type_caster.h" types = [ - "units::farad", - "units::farads", - "units::kilofarad", - "units::kilofarads", - "units::microfarad", - "units::microfarads", - "units::millifarad", - "units::millifarads", - "units::nanofarad", - "units::nanofarads", + "wpi::units::farad", + "wpi::units::farads", + "wpi::units::kilofarad", + "wpi::units::kilofarads", + "wpi::units::microfarad", + "wpi::units::microfarads", + "wpi::units::millifarad", + "wpi::units::millifarads", + "wpi::units::nanofarad", + "wpi::units::nanofarads", ] default_arg_cast = false [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_charge_type_caster.h" types = [ - "units::ampere_hour_t", - "units::coulomb_t", - "units::kiloampere_hour_t", - "units::kilocoulomb_t", - "units::microampere_hour_t", - "units::microcoulomb_t", - "units::milliampere_hour_t", - "units::millicoulomb_t", - "units::nanoampere_hour_t", - "units::nanocoulomb_t", + "wpi::units::ampere_hour_t", + "wpi::units::coulomb_t", + "wpi::units::kiloampere_hour_t", + "wpi::units::kilocoulomb_t", + "wpi::units::microampere_hour_t", + "wpi::units::microcoulomb_t", + "wpi::units::milliampere_hour_t", + "wpi::units::millicoulomb_t", + "wpi::units::nanoampere_hour_t", + "wpi::units::nanocoulomb_t", ] default_arg_cast = true [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_charge_type_caster.h" types = [ - "units::ampere_hour", - "units::ampere_hours", - "units::coulomb", - "units::coulombs", - "units::kiloampere_hour", - "units::kiloampere_hours", - "units::kilocoulomb", - "units::kilocoulombs", - "units::microampere_hour", - "units::microampere_hours", - "units::microcoulomb", - "units::microcoulombs", - "units::milliampere_hour", - "units::milliampere_hours", - "units::millicoulomb", - "units::millicoulombs", - "units::nanoampere_hour", - "units::nanoampere_hours", - "units::nanocoulomb", - "units::nanocoulombs", + "wpi::units::ampere_hour", + "wpi::units::ampere_hours", + "wpi::units::coulomb", + "wpi::units::coulombs", + "wpi::units::kiloampere_hour", + "wpi::units::kiloampere_hours", + "wpi::units::kilocoulomb", + "wpi::units::kilocoulombs", + "wpi::units::microampere_hour", + "wpi::units::microampere_hours", + "wpi::units::microcoulomb", + "wpi::units::microcoulombs", + "wpi::units::milliampere_hour", + "wpi::units::milliampere_hours", + "wpi::units::millicoulomb", + "wpi::units::millicoulombs", + "wpi::units::nanoampere_hour", + "wpi::units::nanoampere_hours", + "wpi::units::nanocoulomb", + "wpi::units::nanocoulombs", ] default_arg_cast = false [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_concentration_type_caster.h" types = [ - "units::percent_t", - "units::ppb_t", - "units::ppm_t", - "units::ppt_t", + "wpi::units::percent_t", + "wpi::units::ppb_t", + "wpi::units::ppm_t", + "wpi::units::ppt_t", ] default_arg_cast = true [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_concentration_type_caster.h" types = [ - "units::parts_per_billion", - "units::parts_per_million", - "units::parts_per_trillion", - "units::percent", - "units::percent", - "units::ppb", - "units::ppm", - "units::ppt", + "wpi::units::parts_per_billion", + "wpi::units::parts_per_million", + "wpi::units::parts_per_trillion", + "wpi::units::percent", + "wpi::units::percent", + "wpi::units::ppb", + "wpi::units::ppm", + "wpi::units::ppt", ] default_arg_cast = false [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_conductance_type_caster.h" types = [ - "units::kilosiemens_t", - "units::microsiemens_t", - "units::millisiemens_t", - "units::nanosiemens_t", - "units::siemens_t", + "wpi::units::kilosiemens_t", + "wpi::units::microsiemens_t", + "wpi::units::millisiemens_t", + "wpi::units::nanosiemens_t", + "wpi::units::siemens_t", ] default_arg_cast = true [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_conductance_type_caster.h" types = [ - "units::kilosiemens", - "units::kilosiemens", - "units::microsiemens", - "units::microsiemens", - "units::millisiemens", - "units::millisiemens", - "units::nanosiemens", - "units::nanosiemens", - "units::siemens", - "units::siemens", + "wpi::units::kilosiemens", + "wpi::units::kilosiemens", + "wpi::units::microsiemens", + "wpi::units::microsiemens", + "wpi::units::millisiemens", + "wpi::units::millisiemens", + "wpi::units::nanosiemens", + "wpi::units::nanosiemens", + "wpi::units::siemens", + "wpi::units::siemens", ] default_arg_cast = false [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_current_type_caster.h" types = [ - "units::ampere_t", - "units::kiloampere_t", - "units::microampere_t", - "units::milliampere_t", - "units::nanoampere_t", + "wpi::units::ampere_t", + "wpi::units::kiloampere_t", + "wpi::units::microampere_t", + "wpi::units::milliampere_t", + "wpi::units::nanoampere_t", ] default_arg_cast = true [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_current_type_caster.h" types = [ - "units::ampere", - "units::amperes", - "units::kiloampere", - "units::kiloamperes", - "units::microampere", - "units::microamperes", - "units::milliampere", - "units::milliamperes", - "units::nanoampere", - "units::nanoamperes", + "wpi::units::ampere", + "wpi::units::amperes", + "wpi::units::kiloampere", + "wpi::units::kiloamperes", + "wpi::units::microampere", + "wpi::units::microamperes", + "wpi::units::milliampere", + "wpi::units::milliamperes", + "wpi::units::nanoampere", + "wpi::units::nanoamperes", ] default_arg_cast = false [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_data_type_caster.h" types = [ - "units::exabit_t", - "units::exabyte_t", + "wpi::units::exabit_t", + "wpi::units::exabyte_t", ] default_arg_cast = true [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_data_type_caster.h" types = [ - "units::exabit", - "units::exabits", - "units::exabyte", - "units::exabytes", + "wpi::units::exabit", + "wpi::units::exabits", + "wpi::units::exabyte", + "wpi::units::exabytes", ] default_arg_cast = false [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_data_transfer_rate_type_caster.h" types = [ - "units::exabits_per_second_t", - "units::exabytes_per_second_t", + "wpi::units::exabits_per_second_t", + "wpi::units::exabytes_per_second_t", ] default_arg_cast = true [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_data_transfer_rate_type_caster.h" types = [ - "units::exabits_per_second", - "units::exabits_per_second", - "units::exabytes_per_second", - "units::exabytes_per_second", + "wpi::units::exabits_per_second", + "wpi::units::exabits_per_second", + "wpi::units::exabytes_per_second", + "wpi::units::exabytes_per_second", ] default_arg_cast = false [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_density_type_caster.h" types = [ - "units::grams_per_milliliter_t", - "units::kilograms_per_cubic_meter_t", - "units::kilograms_per_liter_t", - "units::ounces_per_cubic_foot_t", - "units::ounces_per_cubic_inch_t", - "units::ounces_per_gallon_t", - "units::pounds_per_cubic_foot_t", - "units::pounds_per_cubic_inch_t", - "units::pounds_per_gallon_t", - "units::slugs_per_cubic_foot_t", + "wpi::units::grams_per_milliliter_t", + "wpi::units::kilograms_per_cubic_meter_t", + "wpi::units::kilograms_per_liter_t", + "wpi::units::ounces_per_cubic_foot_t", + "wpi::units::ounces_per_cubic_inch_t", + "wpi::units::ounces_per_gallon_t", + "wpi::units::pounds_per_cubic_foot_t", + "wpi::units::pounds_per_cubic_inch_t", + "wpi::units::pounds_per_gallon_t", + "wpi::units::slugs_per_cubic_foot_t", ] default_arg_cast = true [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_density_type_caster.h" types = [ - "units::grams_per_milliliter", - "units::grams_per_milliliter", - "units::kilograms_per_cubic_meter", - "units::kilograms_per_cubic_meter", - "units::kilograms_per_liter", - "units::kilograms_per_liter", - "units::ounces_per_cubic_foot", - "units::ounces_per_cubic_foot", - "units::ounces_per_cubic_inch", - "units::ounces_per_cubic_inch", - "units::ounces_per_gallon", - "units::ounces_per_gallon", - "units::pounds_per_cubic_foot", - "units::pounds_per_cubic_foot", - "units::pounds_per_cubic_inch", - "units::pounds_per_cubic_inch", - "units::pounds_per_gallon", - "units::pounds_per_gallon", - "units::slugs_per_cubic_foot", - "units::slugs_per_cubic_foot", + "wpi::units::grams_per_milliliter", + "wpi::units::grams_per_milliliter", + "wpi::units::kilograms_per_cubic_meter", + "wpi::units::kilograms_per_cubic_meter", + "wpi::units::kilograms_per_liter", + "wpi::units::kilograms_per_liter", + "wpi::units::ounces_per_cubic_foot", + "wpi::units::ounces_per_cubic_foot", + "wpi::units::ounces_per_cubic_inch", + "wpi::units::ounces_per_cubic_inch", + "wpi::units::ounces_per_gallon", + "wpi::units::ounces_per_gallon", + "wpi::units::pounds_per_cubic_foot", + "wpi::units::pounds_per_cubic_foot", + "wpi::units::pounds_per_cubic_inch", + "wpi::units::pounds_per_cubic_inch", + "wpi::units::pounds_per_gallon", + "wpi::units::pounds_per_gallon", + "wpi::units::slugs_per_cubic_foot", + "wpi::units::slugs_per_cubic_foot", ] default_arg_cast = false [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_energy_type_caster.h" types = [ - "units::british_thermal_unit_59_t", - "units::british_thermal_unit_iso_t", - "units::british_thermal_unit_t", - "units::calorie_t", - "units::foot_pound_t", - "units::joule_t", - "units::kilocalorie_t", - "units::kilojoule_t", - "units::kilowatt_hour_t", - "units::microcalorie_t", - "units::microjoule_t", - "units::millicalorie_t", - "units::millijoule_t", - "units::nanocalorie_t", - "units::nanojoule_t", - "units::therm_t", - "units::watt_hour_t", + "wpi::units::british_thermal_unit_59_t", + "wpi::units::british_thermal_unit_iso_t", + "wpi::units::british_thermal_unit_t", + "wpi::units::calorie_t", + "wpi::units::foot_pound_t", + "wpi::units::joule_t", + "wpi::units::kilocalorie_t", + "wpi::units::kilojoule_t", + "wpi::units::kilowatt_hour_t", + "wpi::units::microcalorie_t", + "wpi::units::microjoule_t", + "wpi::units::millicalorie_t", + "wpi::units::millijoule_t", + "wpi::units::nanocalorie_t", + "wpi::units::nanojoule_t", + "wpi::units::therm_t", + "wpi::units::watt_hour_t", ] default_arg_cast = true [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_energy_type_caster.h" types = [ - "units::british_thermal_unit", - "units::british_thermal_unit_59", - "units::british_thermal_unit_iso", - "units::british_thermal_units", - "units::british_thermal_units_59", - "units::british_thermal_units_iso", - "units::calorie", - "units::calories", - "units::foot_pound", - "units::foot_pounds", - "units::joule", - "units::joules", - "units::kilocalorie", - "units::kilocalories", - "units::kilojoule", - "units::kilojoules", - "units::kilowatt_hour", - "units::kilowatt_hours", - "units::microcalorie", - "units::microcalories", - "units::microjoule", - "units::microjoules", - "units::millicalorie", - "units::millicalories", - "units::millijoule", - "units::millijoules", - "units::nanocalorie", - "units::nanocalories", - "units::nanojoule", - "units::nanojoules", - "units::therm", - "units::therms", - "units::watt_hour", - "units::watt_hours", + "wpi::units::british_thermal_unit", + "wpi::units::british_thermal_unit_59", + "wpi::units::british_thermal_unit_iso", + "wpi::units::british_thermal_units", + "wpi::units::british_thermal_units_59", + "wpi::units::british_thermal_units_iso", + "wpi::units::calorie", + "wpi::units::calories", + "wpi::units::foot_pound", + "wpi::units::foot_pounds", + "wpi::units::joule", + "wpi::units::joules", + "wpi::units::kilocalorie", + "wpi::units::kilocalories", + "wpi::units::kilojoule", + "wpi::units::kilojoules", + "wpi::units::kilowatt_hour", + "wpi::units::kilowatt_hours", + "wpi::units::microcalorie", + "wpi::units::microcalories", + "wpi::units::microjoule", + "wpi::units::microjoules", + "wpi::units::millicalorie", + "wpi::units::millicalories", + "wpi::units::millijoule", + "wpi::units::millijoules", + "wpi::units::nanocalorie", + "wpi::units::nanocalories", + "wpi::units::nanojoule", + "wpi::units::nanojoules", + "wpi::units::therm", + "wpi::units::therms", + "wpi::units::watt_hour", + "wpi::units::watt_hours", ] default_arg_cast = false [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_force_type_caster.h" types = [ - "units::dyne_t", - "units::kilonewton_t", - "units::kilopond_t", - "units::micronewton_t", - "units::millinewton_t", - "units::nanonewton_t", - "units::newton_t", - "units::pound_t", - "units::poundal_t", + "wpi::units::dyne_t", + "wpi::units::kilonewton_t", + "wpi::units::kilopond_t", + "wpi::units::micronewton_t", + "wpi::units::millinewton_t", + "wpi::units::nanonewton_t", + "wpi::units::newton_t", + "wpi::units::pound_t", + "wpi::units::poundal_t", ] default_arg_cast = true [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_force_type_caster.h" types = [ - "units::dyne", - "units::dynes", - "units::kilonewton", - "units::kilonewtons", - "units::kilopond", - "units::kiloponds", - "units::micronewton", - "units::micronewtons", - "units::millinewton", - "units::millinewtons", - "units::nanonewton", - "units::nanonewtons", - "units::newton", - "units::newtons", - "units::pound", - "units::poundal", - "units::poundals", - "units::pounds", + "wpi::units::dyne", + "wpi::units::dynes", + "wpi::units::kilonewton", + "wpi::units::kilonewtons", + "wpi::units::kilopond", + "wpi::units::kiloponds", + "wpi::units::micronewton", + "wpi::units::micronewtons", + "wpi::units::millinewton", + "wpi::units::millinewtons", + "wpi::units::nanonewton", + "wpi::units::nanonewtons", + "wpi::units::newton", + "wpi::units::newtons", + "wpi::units::pound", + "wpi::units::poundal", + "wpi::units::poundals", + "wpi::units::pounds", ] default_arg_cast = false [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_frequency_type_caster.h" types = [ - "units::hertz_t", - "units::kilohertz_t", - "units::microhertz_t", - "units::millihertz_t", - "units::nanohertz_t", + "wpi::units::hertz_t", + "wpi::units::kilohertz_t", + "wpi::units::microhertz_t", + "wpi::units::millihertz_t", + "wpi::units::nanohertz_t", ] default_arg_cast = true [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_frequency_type_caster.h" types = [ - "units::hertz", - "units::hertz", - "units::kilohertz", - "units::kilohertz", - "units::microhertz", - "units::microhertz", - "units::millihertz", - "units::millihertz", - "units::nanohertz", - "units::nanohertz", + "wpi::units::hertz", + "wpi::units::hertz", + "wpi::units::kilohertz", + "wpi::units::kilohertz", + "wpi::units::microhertz", + "wpi::units::microhertz", + "wpi::units::millihertz", + "wpi::units::millihertz", + "wpi::units::nanohertz", + "wpi::units::nanohertz", ] default_arg_cast = false [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_illuminance_type_caster.h" types = [ - "units::footcandle_t", - "units::kilolux_t", - "units::lumens_per_square_inch_t", - "units::lux_t", - "units::microlux_t", - "units::millilux_t", - "units::nanolux_t", - "units::phot_t", + "wpi::units::footcandle_t", + "wpi::units::kilolux_t", + "wpi::units::lumens_per_square_inch_t", + "wpi::units::lux_t", + "wpi::units::microlux_t", + "wpi::units::millilux_t", + "wpi::units::nanolux_t", + "wpi::units::phot_t", ] default_arg_cast = true [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_illuminance_type_caster.h" types = [ - "units::footcandle", - "units::footcandles", - "units::kilolux", - "units::kiloluxes", - "units::lumens_per_square_inch", - "units::lumens_per_square_inch", - "units::lux", - "units::luxes", - "units::microlux", - "units::microluxes", - "units::millilux", - "units::milliluxes", - "units::nanolux", - "units::nanoluxes", - "units::phot", - "units::phots", + "wpi::units::footcandle", + "wpi::units::footcandles", + "wpi::units::kilolux", + "wpi::units::kiloluxes", + "wpi::units::lumens_per_square_inch", + "wpi::units::lumens_per_square_inch", + "wpi::units::lux", + "wpi::units::luxes", + "wpi::units::microlux", + "wpi::units::microluxes", + "wpi::units::millilux", + "wpi::units::milliluxes", + "wpi::units::nanolux", + "wpi::units::nanoluxes", + "wpi::units::phot", + "wpi::units::phots", ] default_arg_cast = false [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_impedance_type_caster.h" types = [ - "units::kiloohm_t", - "units::microohm_t", - "units::milliohm_t", - "units::nanoohm_t", - "units::ohm_t", + "wpi::units::kiloohm_t", + "wpi::units::microohm_t", + "wpi::units::milliohm_t", + "wpi::units::nanoohm_t", + "wpi::units::ohm_t", ] default_arg_cast = true [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_impedance_type_caster.h" types = [ - "units::kiloohm", - "units::kiloohms", - "units::microohm", - "units::microohms", - "units::milliohm", - "units::milliohms", - "units::nanoohm", - "units::nanoohms", - "units::ohm", - "units::ohms", + "wpi::units::kiloohm", + "wpi::units::kiloohms", + "wpi::units::microohm", + "wpi::units::microohms", + "wpi::units::milliohm", + "wpi::units::milliohms", + "wpi::units::nanoohm", + "wpi::units::nanoohms", + "wpi::units::ohm", + "wpi::units::ohms", ] default_arg_cast = false [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_inductance_type_caster.h" types = [ - "units::henry_t", - "units::kilohenry_t", - "units::microhenry_t", - "units::millihenry_t", - "units::nanohenry_t", + "wpi::units::henry_t", + "wpi::units::kilohenry_t", + "wpi::units::microhenry_t", + "wpi::units::millihenry_t", + "wpi::units::nanohenry_t", ] default_arg_cast = true [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_inductance_type_caster.h" types = [ - "units::henries", - "units::henry", - "units::kilohenries", - "units::kilohenry", - "units::microhenries", - "units::microhenry", - "units::millihenries", - "units::millihenry", - "units::nanohenries", - "units::nanohenry", + "wpi::units::henries", + "wpi::units::henry", + "wpi::units::kilohenries", + "wpi::units::kilohenry", + "wpi::units::microhenries", + "wpi::units::microhenry", + "wpi::units::millihenries", + "wpi::units::millihenry", + "wpi::units::nanohenries", + "wpi::units::nanohenry", ] default_arg_cast = false [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_length_type_caster.h" types = [ - "units::angstrom_t", - "units::astronicalUnit_t", - "units::centimeter_t", - "units::chain_t", - "units::cubit_t", - "units::fathom_t", - "units::foot_t", - "units::furlong_t", - "units::hand_t", - "units::inch_t", - "units::kilometer_t", - "units::league_t", - "units::lightyear_t", - "units::meter_t", - "units::micrometer_t", - "units::mil_t", - "units::mile_t", - "units::millimeter_t", - "units::nanometer_t", - "units::nauticalLeague_t", - "units::nauticalMile_t", - "units::parsec_t", - "units::yard_t", + "wpi::units::angstrom_t", + "wpi::units::astronicalUnit_t", + "wpi::units::centimeter_t", + "wpi::units::chain_t", + "wpi::units::cubit_t", + "wpi::units::fathom_t", + "wpi::units::foot_t", + "wpi::units::furlong_t", + "wpi::units::hand_t", + "wpi::units::inch_t", + "wpi::units::kilometer_t", + "wpi::units::league_t", + "wpi::units::lightyear_t", + "wpi::units::meter_t", + "wpi::units::micrometer_t", + "wpi::units::mil_t", + "wpi::units::mile_t", + "wpi::units::millimeter_t", + "wpi::units::nanometer_t", + "wpi::units::nauticalLeague_t", + "wpi::units::nauticalMile_t", + "wpi::units::parsec_t", + "wpi::units::yard_t", ] default_arg_cast = true [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_length_type_caster.h" types = [ - "units::angstrom", - "units::angstroms", - "units::astronicalUnit", - "units::astronicalUnits", - "units::chain", - "units::chains", - "units::cubit", - "units::cubits", - "units::fathom", - "units::fathoms", - "units::feet", - "units::foot", - "units::furlong", - "units::furlongs", - "units::hand", - "units::hands", - "units::inch", - "units::inches", - "units::kilometer", - "units::kilometers", - "units::league", - "units::leagues", - "units::lightyear", - "units::lightyears", - "units::meter", - "units::meters", - "units::micrometer", - "units::micrometers", - "units::mil", - "units::mile", - "units::miles", - "units::millimeter", - "units::millimeters", - "units::mils", - "units::nanometer", - "units::nanometers", - "units::nauticalLeague", - "units::nauticalLeagues", - "units::nauticalMile", - "units::nauticalMiles", - "units::parsec", - "units::parsecs", - "units::yard", - "units::yards", + "wpi::units::angstrom", + "wpi::units::angstroms", + "wpi::units::astronicalUnit", + "wpi::units::astronicalUnits", + "wpi::units::chain", + "wpi::units::chains", + "wpi::units::cubit", + "wpi::units::cubits", + "wpi::units::fathom", + "wpi::units::fathoms", + "wpi::units::feet", + "wpi::units::foot", + "wpi::units::furlong", + "wpi::units::furlongs", + "wpi::units::hand", + "wpi::units::hands", + "wpi::units::inch", + "wpi::units::inches", + "wpi::units::kilometer", + "wpi::units::kilometers", + "wpi::units::league", + "wpi::units::leagues", + "wpi::units::lightyear", + "wpi::units::lightyears", + "wpi::units::meter", + "wpi::units::meters", + "wpi::units::micrometer", + "wpi::units::micrometers", + "wpi::units::mil", + "wpi::units::mile", + "wpi::units::miles", + "wpi::units::millimeter", + "wpi::units::millimeters", + "wpi::units::mils", + "wpi::units::nanometer", + "wpi::units::nanometers", + "wpi::units::nauticalLeague", + "wpi::units::nauticalLeagues", + "wpi::units::nauticalMile", + "wpi::units::nauticalMiles", + "wpi::units::parsec", + "wpi::units::parsecs", + "wpi::units::yard", + "wpi::units::yards", ] default_arg_cast = false [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_luminous_flux_type_caster.h" types = [ - "units::kilolumen_t", - "units::lumen_t", - "units::microlumen_t", - "units::millilumen_t", - "units::nanolumen_t", + "wpi::units::kilolumen_t", + "wpi::units::lumen_t", + "wpi::units::microlumen_t", + "wpi::units::millilumen_t", + "wpi::units::nanolumen_t", ] default_arg_cast = true [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_luminous_flux_type_caster.h" types = [ - "units::kilolumen", - "units::kilolumens", - "units::lumen", - "units::lumens", - "units::microlumen", - "units::microlumens", - "units::millilumen", - "units::millilumens", - "units::nanolumen", - "units::nanolumens", + "wpi::units::kilolumen", + "wpi::units::kilolumens", + "wpi::units::lumen", + "wpi::units::lumens", + "wpi::units::microlumen", + "wpi::units::microlumens", + "wpi::units::millilumen", + "wpi::units::millilumens", + "wpi::units::nanolumen", + "wpi::units::nanolumens", ] default_arg_cast = false [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_luminous_intensity_type_caster.h" types = [ - "units::candela_t", - "units::kilocandela_t", - "units::microcandela_t", - "units::millicandela_t", - "units::nanocandela_t", + "wpi::units::candela_t", + "wpi::units::kilocandela_t", + "wpi::units::microcandela_t", + "wpi::units::millicandela_t", + "wpi::units::nanocandela_t", ] default_arg_cast = true [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_luminous_intensity_type_caster.h" types = [ - "units::candela", - "units::candelas", - "units::kilocandela", - "units::kilocandelas", - "units::microcandela", - "units::microcandelas", - "units::millicandela", - "units::millicandelas", - "units::nanocandela", - "units::nanocandelas", + "wpi::units::candela", + "wpi::units::candelas", + "wpi::units::kilocandela", + "wpi::units::kilocandelas", + "wpi::units::microcandela", + "wpi::units::microcandelas", + "wpi::units::millicandela", + "wpi::units::millicandelas", + "wpi::units::nanocandela", + "wpi::units::nanocandelas", ] default_arg_cast = false [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_magnetic_field_strength_type_caster.h" types = [ - "units::gauss_t", - "units::kilotesla_t", - "units::microtesla_t", - "units::millitesla_t", - "units::nanotesla_t", - "units::tesla_t", + "wpi::units::gauss_t", + "wpi::units::kilotesla_t", + "wpi::units::microtesla_t", + "wpi::units::millitesla_t", + "wpi::units::nanotesla_t", + "wpi::units::tesla_t", ] default_arg_cast = true [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_magnetic_field_strength_type_caster.h" types = [ - "units::gauss", - "units::gauss", - "units::kilotesla", - "units::kiloteslas", - "units::microtesla", - "units::microteslas", - "units::millitesla", - "units::milliteslas", - "units::nanotesla", - "units::nanoteslas", - "units::tesla", - "units::teslas", + "wpi::units::gauss", + "wpi::units::gauss", + "wpi::units::kilotesla", + "wpi::units::kiloteslas", + "wpi::units::microtesla", + "wpi::units::microteslas", + "wpi::units::millitesla", + "wpi::units::milliteslas", + "wpi::units::nanotesla", + "wpi::units::nanoteslas", + "wpi::units::tesla", + "wpi::units::teslas", ] default_arg_cast = false [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_magnetic_flux_type_caster.h" types = [ - "units::kiloweber_t", - "units::maxwell_t", - "units::microweber_t", - "units::milliweber_t", - "units::nanoweber_t", - "units::weber_t", + "wpi::units::kiloweber_t", + "wpi::units::maxwell_t", + "wpi::units::microweber_t", + "wpi::units::milliweber_t", + "wpi::units::nanoweber_t", + "wpi::units::weber_t", ] default_arg_cast = true [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_magnetic_flux_type_caster.h" types = [ - "units::kiloweber", - "units::kilowebers", - "units::maxwell", - "units::maxwells", - "units::microweber", - "units::microwebers", - "units::milliweber", - "units::milliwebers", - "units::nanoweber", - "units::nanowebers", - "units::weber", - "units::webers", + "wpi::units::kiloweber", + "wpi::units::kilowebers", + "wpi::units::maxwell", + "wpi::units::maxwells", + "wpi::units::microweber", + "wpi::units::microwebers", + "wpi::units::milliweber", + "wpi::units::milliwebers", + "wpi::units::nanoweber", + "wpi::units::nanowebers", + "wpi::units::weber", + "wpi::units::webers", ] default_arg_cast = false [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_mass_type_caster.h" types = [ - "units::carat_t", - "units::gram_t", - "units::kilogram_t", - "units::long_ton_t", - "units::metric_ton_t", - "units::microgram_t", - "units::milligram_t", - "units::nanogram_t", - "units::ounce_t", - "units::pound_t", - "units::short_ton_t", - "units::slug_t", - "units::stone_t", + "wpi::units::carat_t", + "wpi::units::gram_t", + "wpi::units::kilogram_t", + "wpi::units::long_ton_t", + "wpi::units::metric_ton_t", + "wpi::units::microgram_t", + "wpi::units::milligram_t", + "wpi::units::nanogram_t", + "wpi::units::ounce_t", + "wpi::units::pound_t", + "wpi::units::short_ton_t", + "wpi::units::slug_t", + "wpi::units::stone_t", ] default_arg_cast = true [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_mass_type_caster.h" types = [ - "units::carat", - "units::carats", - "units::gram", - "units::grams", - "units::kilogram", - "units::kilograms", - "units::long_ton", - "units::long_tons", - "units::metric_ton", - "units::metric_tons", - "units::microgram", - "units::micrograms", - "units::milligram", - "units::milligrams", - "units::nanogram", - "units::nanograms", - "units::ounce", - "units::ounces", - "units::pound", - "units::pounds", - "units::short_ton", - "units::short_tons", - "units::slug", - "units::slugs", - "units::stone", - "units::stone", + "wpi::units::carat", + "wpi::units::carats", + "wpi::units::gram", + "wpi::units::grams", + "wpi::units::kilogram", + "wpi::units::kilograms", + "wpi::units::long_ton", + "wpi::units::long_tons", + "wpi::units::metric_ton", + "wpi::units::metric_tons", + "wpi::units::microgram", + "wpi::units::micrograms", + "wpi::units::milligram", + "wpi::units::milligrams", + "wpi::units::nanogram", + "wpi::units::nanograms", + "wpi::units::ounce", + "wpi::units::ounces", + "wpi::units::pound", + "wpi::units::pounds", + "wpi::units::short_ton", + "wpi::units::short_tons", + "wpi::units::slug", + "wpi::units::slugs", + "wpi::units::stone", + "wpi::units::stone", ] default_arg_cast = false [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_moment_of_inertia_type_caster.h" types = [ - "units::kilogram_square_meter_t", + "wpi::units::kilogram_square_meter_t", ] default_arg_cast = true [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_moment_of_inertia_type_caster.h" types = [ - "units::kilogram_square_meter", - "units::kilogram_square_meters", + "wpi::units::kilogram_square_meter", + "wpi::units::kilogram_square_meters", ] default_arg_cast = false [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_power_type_caster.h" types = [ - "units::horsepower_t", - "units::kilowatt_t", - "units::microwatt_t", - "units::milliwatt_t", - "units::nanowatt_t", - "units::watt_t", + "wpi::units::horsepower_t", + "wpi::units::kilowatt_t", + "wpi::units::microwatt_t", + "wpi::units::milliwatt_t", + "wpi::units::nanowatt_t", + "wpi::units::watt_t", ] default_arg_cast = true [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_power_type_caster.h" types = [ - "units::horsepower", - "units::horsepower", - "units::kilowatt", - "units::kilowatts", - "units::microwatt", - "units::microwatts", - "units::milliwatt", - "units::milliwatts", - "units::nanowatt", - "units::nanowatts", - "units::watt", - "units::watts", + "wpi::units::horsepower", + "wpi::units::horsepower", + "wpi::units::kilowatt", + "wpi::units::kilowatts", + "wpi::units::microwatt", + "wpi::units::microwatts", + "wpi::units::milliwatt", + "wpi::units::milliwatts", + "wpi::units::nanowatt", + "wpi::units::nanowatts", + "wpi::units::watt", + "wpi::units::watts", ] default_arg_cast = false [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_pressure_type_caster.h" types = [ - "units::atmosphere_t", - "units::bar_t", - "units::kilopascal_t", - "units::mbar_t", - "units::micropascal_t", - "units::millipascal_t", - "units::nanopascal_t", - "units::pascal_t", - "units::pounds_per_square_inch_t", - "units::torr_t", + "wpi::units::atmosphere_t", + "wpi::units::bar_t", + "wpi::units::kilopascal_t", + "wpi::units::mbar_t", + "wpi::units::micropascal_t", + "wpi::units::millipascal_t", + "wpi::units::nanopascal_t", + "wpi::units::pascal_t", + "wpi::units::pounds_per_square_inch_t", + "wpi::units::torr_t", ] default_arg_cast = true [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_pressure_type_caster.h" types = [ - "units::atmosphere", - "units::atmospheres", - "units::bar", - "units::bars", - "units::kilopascal", - "units::kilopascals", - "units::mbar", - "units::mbars", - "units::micropascal", - "units::micropascals", - "units::millipascal", - "units::millipascals", - "units::nanopascal", - "units::nanopascals", - "units::pascal", - "units::pascals", - "units::pounds_per_square_inch", - "units::pounds_per_square_inch", - "units::torr", - "units::torrs", + "wpi::units::atmosphere", + "wpi::units::atmospheres", + "wpi::units::bar", + "wpi::units::bars", + "wpi::units::kilopascal", + "wpi::units::kilopascals", + "wpi::units::mbar", + "wpi::units::mbars", + "wpi::units::micropascal", + "wpi::units::micropascals", + "wpi::units::millipascal", + "wpi::units::millipascals", + "wpi::units::nanopascal", + "wpi::units::nanopascals", + "wpi::units::pascal", + "wpi::units::pascals", + "wpi::units::pounds_per_square_inch", + "wpi::units::pounds_per_square_inch", + "wpi::units::torr", + "wpi::units::torrs", ] default_arg_cast = false [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_radiation_type_caster.h" types = [ - "units::becquerel_t", - "units::curie_t", - "units::gray_t", - "units::kilobecquerel_t", - "units::kilogray_t", - "units::kilosievert_t", - "units::microbecquerel_t", - "units::microgray_t", - "units::microsievert_t", - "units::millibecquerel_t", - "units::milligray_t", - "units::millisievert_t", - "units::nanobecquerel_t", - "units::nanogray_t", - "units::nanosievert_t", - "units::rad_t", - "units::rutherford_t", - "units::sievert_t", + "wpi::units::becquerel_t", + "wpi::units::curie_t", + "wpi::units::gray_t", + "wpi::units::kilobecquerel_t", + "wpi::units::kilogray_t", + "wpi::units::kilosievert_t", + "wpi::units::microbecquerel_t", + "wpi::units::microgray_t", + "wpi::units::microsievert_t", + "wpi::units::millibecquerel_t", + "wpi::units::milligray_t", + "wpi::units::millisievert_t", + "wpi::units::nanobecquerel_t", + "wpi::units::nanogray_t", + "wpi::units::nanosievert_t", + "wpi::units::rad_t", + "wpi::units::rutherford_t", + "wpi::units::sievert_t", ] default_arg_cast = true [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_radiation_type_caster.h" types = [ - "units::becquerel", - "units::becquerels", - "units::curie", - "units::curies", - "units::gray", - "units::grays", - "units::kilobecquerel", - "units::kilobecquerels", - "units::kilogray", - "units::kilograys", - "units::kilosievert", - "units::kilosieverts", - "units::microbecquerel", - "units::microbecquerels", - "units::microgray", - "units::micrograys", - "units::microsievert", - "units::microsieverts", - "units::millibecquerel", - "units::millibecquerels", - "units::milligray", - "units::milligrays", - "units::millisievert", - "units::millisieverts", - "units::nanobecquerel", - "units::nanobecquerels", - "units::nanogray", - "units::nanograys", - "units::nanosievert", - "units::nanosieverts", - "units::rad", - "units::rads", - "units::rutherford", - "units::rutherfords", - "units::sievert", - "units::sieverts", + "wpi::units::becquerel", + "wpi::units::becquerels", + "wpi::units::curie", + "wpi::units::curies", + "wpi::units::gray", + "wpi::units::grays", + "wpi::units::kilobecquerel", + "wpi::units::kilobecquerels", + "wpi::units::kilogray", + "wpi::units::kilograys", + "wpi::units::kilosievert", + "wpi::units::kilosieverts", + "wpi::units::microbecquerel", + "wpi::units::microbecquerels", + "wpi::units::microgray", + "wpi::units::micrograys", + "wpi::units::microsievert", + "wpi::units::microsieverts", + "wpi::units::millibecquerel", + "wpi::units::millibecquerels", + "wpi::units::milligray", + "wpi::units::milligrays", + "wpi::units::millisievert", + "wpi::units::millisieverts", + "wpi::units::nanobecquerel", + "wpi::units::nanobecquerels", + "wpi::units::nanogray", + "wpi::units::nanograys", + "wpi::units::nanosievert", + "wpi::units::nanosieverts", + "wpi::units::rad", + "wpi::units::rads", + "wpi::units::rutherford", + "wpi::units::rutherfords", + "wpi::units::sievert", + "wpi::units::sieverts", ] default_arg_cast = false [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_solid_angle_type_caster.h" types = [ - "units::degree_squared_t", - "units::kilosteradian_t", - "units::microsteradian_t", - "units::millisteradian_t", - "units::nanosteradian_t", - "units::spat_t", - "units::steradian_t", + "wpi::units::degree_squared_t", + "wpi::units::kilosteradian_t", + "wpi::units::microsteradian_t", + "wpi::units::millisteradian_t", + "wpi::units::nanosteradian_t", + "wpi::units::spat_t", + "wpi::units::steradian_t", ] default_arg_cast = true [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_solid_angle_type_caster.h" types = [ - "units::degree_squared", - "units::degrees_squared", - "units::kilosteradian", - "units::kilosteradians", - "units::microsteradian", - "units::microsteradians", - "units::millisteradian", - "units::millisteradians", - "units::nanosteradian", - "units::nanosteradians", - "units::spat", - "units::spats", - "units::steradian", - "units::steradians", + "wpi::units::degree_squared", + "wpi::units::degrees_squared", + "wpi::units::kilosteradian", + "wpi::units::kilosteradians", + "wpi::units::microsteradian", + "wpi::units::microsteradians", + "wpi::units::millisteradian", + "wpi::units::millisteradians", + "wpi::units::nanosteradian", + "wpi::units::nanosteradians", + "wpi::units::spat", + "wpi::units::spats", + "wpi::units::steradian", + "wpi::units::steradians", ] default_arg_cast = false [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_substance_type_caster.h" types = [ - "units::mole_t", + "wpi::units::mole_t", ] default_arg_cast = true [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_substance_type_caster.h" types = [ - "units::mole", - "units::moles", + "wpi::units::mole", + "wpi::units::moles", ] default_arg_cast = false [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_temperature_type_caster.h" types = [ - "units::celsius_t", - "units::fahrenheit_t", - "units::kelvin_t", - "units::rankine_t", - "units::reaumur_t", + "wpi::units::celsius_t", + "wpi::units::fahrenheit_t", + "wpi::units::kelvin_t", + "wpi::units::rankine_t", + "wpi::units::reaumur_t", ] default_arg_cast = true [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_temperature_type_caster.h" types = [ - "units::celsius", - "units::celsius", - "units::fahrenheit", - "units::fahrenheit", - "units::kelvin", - "units::kelvin", - "units::rankine", - "units::rankine", - "units::reaumur", - "units::reaumur", + "wpi::units::celsius", + "wpi::units::celsius", + "wpi::units::fahrenheit", + "wpi::units::fahrenheit", + "wpi::units::kelvin", + "wpi::units::kelvin", + "wpi::units::rankine", + "wpi::units::rankine", + "wpi::units::reaumur", + "wpi::units::reaumur", ] default_arg_cast = false [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_time_type_caster.h" types = [ - "units::day_t", - "units::gregorian_year_t", - "units::hour_t", - "units::julian_year_t", - "units::kilosecond_t", - "units::microsecond_t", - "units::millisecond_t", - "units::minute_t", - "units::nanosecond_t", - "units::second_t", - "units::week_t", - "units::year_t", + "wpi::units::day_t", + "wpi::units::gregorian_year_t", + "wpi::units::hour_t", + "wpi::units::julian_year_t", + "wpi::units::kilosecond_t", + "wpi::units::microsecond_t", + "wpi::units::millisecond_t", + "wpi::units::minute_t", + "wpi::units::nanosecond_t", + "wpi::units::second_t", + "wpi::units::week_t", + "wpi::units::year_t", ] default_arg_cast = true [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_time_type_caster.h" types = [ - "units::day", - "units::days", - "units::gregorian_year", - "units::gregorian_years", - "units::hour", - "units::hours", - "units::julian_year", - "units::julian_years", - "units::kilosecond", - "units::kiloseconds", - "units::microsecond", - "units::microseconds", - "units::millisecond", - "units::milliseconds", - "units::minute", - "units::minutes", - "units::nanosecond", - "units::nanoseconds", - "units::second", - "units::seconds", - "units::week", - "units::weeks", - "units::year", - "units::years", + "wpi::units::day", + "wpi::units::days", + "wpi::units::gregorian_year", + "wpi::units::gregorian_years", + "wpi::units::hour", + "wpi::units::hours", + "wpi::units::julian_year", + "wpi::units::julian_years", + "wpi::units::kilosecond", + "wpi::units::kiloseconds", + "wpi::units::microsecond", + "wpi::units::microseconds", + "wpi::units::millisecond", + "wpi::units::milliseconds", + "wpi::units::minute", + "wpi::units::minutes", + "wpi::units::nanosecond", + "wpi::units::nanoseconds", + "wpi::units::second", + "wpi::units::seconds", + "wpi::units::week", + "wpi::units::weeks", + "wpi::units::year", + "wpi::units::years", ] default_arg_cast = false [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_torque_type_caster.h" types = [ - "units::foot_pound_t", - "units::foot_poundal_t", - "units::inch_pound_t", - "units::meter_kilogram_t", - "units::newton_meter_t", + "wpi::units::foot_pound_t", + "wpi::units::foot_poundal_t", + "wpi::units::inch_pound_t", + "wpi::units::meter_kilogram_t", + "wpi::units::newton_meter_t", ] default_arg_cast = true [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_torque_type_caster.h" types = [ - "units::foot_pound", - "units::foot_poundal", - "units::foot_poundals", - "units::foot_pounds", - "units::inch_pound", - "units::inch_pounds", - "units::meter_kilogram", - "units::meter_kilograms", - "units::newton_meter", - "units::newton_meters", + "wpi::units::foot_pound", + "wpi::units::foot_poundal", + "wpi::units::foot_poundals", + "wpi::units::foot_pounds", + "wpi::units::inch_pound", + "wpi::units::inch_pounds", + "wpi::units::meter_kilogram", + "wpi::units::meter_kilograms", + "wpi::units::newton_meter", + "wpi::units::newton_meters", ] default_arg_cast = false [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_velocity_type_caster.h" types = [ - "units::feet_per_second_t", - "units::kilometers_per_hour_t", - "units::knot_t", - "units::meters_per_second_t", - "units::miles_per_hour_t", + "wpi::units::feet_per_second_t", + "wpi::units::kilometers_per_hour_t", + "wpi::units::knot_t", + "wpi::units::meters_per_second_t", + "wpi::units::miles_per_hour_t", ] default_arg_cast = true [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_velocity_type_caster.h" types = [ - "units::feet_per_second", - "units::feet_per_second", - "units::kilometers_per_hour", - "units::kilometers_per_hour", - "units::knot", - "units::knots", - "units::meters_per_second", - "units::meters_per_second", - "units::miles_per_hour", - "units::miles_per_hour", + "wpi::units::feet_per_second", + "wpi::units::feet_per_second", + "wpi::units::kilometers_per_hour", + "wpi::units::kilometers_per_hour", + "wpi::units::knot", + "wpi::units::knots", + "wpi::units::meters_per_second", + "wpi::units::meters_per_second", + "wpi::units::miles_per_hour", + "wpi::units::miles_per_hour", ] default_arg_cast = false [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_voltage_type_caster.h" types = [ - "units::abvolt_t", - "units::kilovolt_t", - "units::microvolt_t", - "units::millivolt_t", - "units::nanovolt_t", - "units::statvolt_t", - "units::volt_t", + "wpi::units::abvolt_t", + "wpi::units::kilovolt_t", + "wpi::units::microvolt_t", + "wpi::units::millivolt_t", + "wpi::units::nanovolt_t", + "wpi::units::statvolt_t", + "wpi::units::volt_t", ] default_arg_cast = true [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_voltage_type_caster.h" types = [ - "units::abvolt", - "units::abvolts", - "units::kilovolt", - "units::kilovolts", - "units::microvolt", - "units::microvolts", - "units::millivolt", - "units::millivolts", - "units::nanovolt", - "units::nanovolts", - "units::statvolt", - "units::statvolts", - "units::volt", - "units::volts", + "wpi::units::abvolt", + "wpi::units::abvolts", + "wpi::units::kilovolt", + "wpi::units::kilovolts", + "wpi::units::microvolt", + "wpi::units::microvolts", + "wpi::units::millivolt", + "wpi::units::millivolts", + "wpi::units::nanovolt", + "wpi::units::nanovolts", + "wpi::units::statvolt", + "wpi::units::statvolts", + "wpi::units::volt", + "wpi::units::volts", ] default_arg_cast = false [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_volume_type_caster.h" types = [ - "units::barrel_t", - "units::bushel_t", - "units::cord_t", - "units::cubic_fathom_t", - "units::cubic_foot_t", - "units::cubic_inch_t", - "units::cubic_kilometer_t", - "units::cubic_meter_t", - "units::cubic_mile_t", - "units::cubic_millimeter_t", - "units::cubic_yard_t", - "units::cup_t", - "units::dash_t", - "units::dram_t", - "units::drop_t", - "units::fifth_t", - "units::fluid_ounce_t", - "units::gallon_t", - "units::gill_t", - "units::kiloliter_t", - "units::liter_t", - "units::microliter_t", - "units::milliliter_t", - "units::nanoliter_t", - "units::peck_t", - "units::pinch_t", - "units::pint_t", - "units::quart_t", - "units::sack_t", - "units::shot_t", - "units::strike_t", - "units::tablespoon_t", - "units::teaspoon_t", + "wpi::units::barrel_t", + "wpi::units::bushel_t", + "wpi::units::cord_t", + "wpi::units::cubic_fathom_t", + "wpi::units::cubic_foot_t", + "wpi::units::cubic_inch_t", + "wpi::units::cubic_kilometer_t", + "wpi::units::cubic_meter_t", + "wpi::units::cubic_mile_t", + "wpi::units::cubic_millimeter_t", + "wpi::units::cubic_yard_t", + "wpi::units::cup_t", + "wpi::units::dash_t", + "wpi::units::dram_t", + "wpi::units::drop_t", + "wpi::units::fifth_t", + "wpi::units::fluid_ounce_t", + "wpi::units::gallon_t", + "wpi::units::gill_t", + "wpi::units::kiloliter_t", + "wpi::units::liter_t", + "wpi::units::microliter_t", + "wpi::units::milliliter_t", + "wpi::units::nanoliter_t", + "wpi::units::peck_t", + "wpi::units::pinch_t", + "wpi::units::pint_t", + "wpi::units::quart_t", + "wpi::units::sack_t", + "wpi::units::shot_t", + "wpi::units::strike_t", + "wpi::units::tablespoon_t", + "wpi::units::teaspoon_t", ] default_arg_cast = true [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_volume_type_caster.h" types = [ - "units::barrel", - "units::barrels", - "units::bushel", - "units::bushels", - "units::cord", - "units::cords", - "units::cubic_fathom", - "units::cubic_fathoms", - "units::cubic_feet", - "units::cubic_foot", - "units::cubic_inch", - "units::cubic_inches", - "units::cubic_kilometer", - "units::cubic_kilometers", - "units::cubic_meter", - "units::cubic_meters", - "units::cubic_mile", - "units::cubic_miles", - "units::cubic_millimeter", - "units::cubic_millimeters", - "units::cubic_yard", - "units::cubic_yards", - "units::cup", - "units::cups", - "units::dash", - "units::dashes", - "units::dram", - "units::drams", - "units::drop", - "units::drops", - "units::fifth", - "units::fifths", - "units::fluid_ounce", - "units::fluid_ounces", - "units::gallon", - "units::gallons", - "units::gill", - "units::gills", - "units::kiloliter", - "units::kiloliters", - "units::liter", - "units::liters", - "units::microliter", - "units::microliters", - "units::milliliter", - "units::milliliters", - "units::nanoliter", - "units::nanoliters", - "units::peck", - "units::pecks", - "units::pinch", - "units::pinches", - "units::pint", - "units::pints", - "units::quart", - "units::quarts", - "units::sack", - "units::sacks", - "units::shot", - "units::shots", - "units::strike", - "units::strikes", - "units::tablespoon", - "units::tablespoons", - "units::teaspoon", - "units::teaspoons", + "wpi::units::barrel", + "wpi::units::barrels", + "wpi::units::bushel", + "wpi::units::bushels", + "wpi::units::cord", + "wpi::units::cords", + "wpi::units::cubic_fathom", + "wpi::units::cubic_fathoms", + "wpi::units::cubic_feet", + "wpi::units::cubic_foot", + "wpi::units::cubic_inch", + "wpi::units::cubic_inches", + "wpi::units::cubic_kilometer", + "wpi::units::cubic_kilometers", + "wpi::units::cubic_meter", + "wpi::units::cubic_meters", + "wpi::units::cubic_mile", + "wpi::units::cubic_miles", + "wpi::units::cubic_millimeter", + "wpi::units::cubic_millimeters", + "wpi::units::cubic_yard", + "wpi::units::cubic_yards", + "wpi::units::cup", + "wpi::units::cups", + "wpi::units::dash", + "wpi::units::dashes", + "wpi::units::dram", + "wpi::units::drams", + "wpi::units::drop", + "wpi::units::drops", + "wpi::units::fifth", + "wpi::units::fifths", + "wpi::units::fluid_ounce", + "wpi::units::fluid_ounces", + "wpi::units::gallon", + "wpi::units::gallons", + "wpi::units::gill", + "wpi::units::gills", + "wpi::units::kiloliter", + "wpi::units::kiloliters", + "wpi::units::liter", + "wpi::units::liters", + "wpi::units::microliter", + "wpi::units::microliters", + "wpi::units::milliliter", + "wpi::units::milliliters", + "wpi::units::nanoliter", + "wpi::units::nanoliters", + "wpi::units::peck", + "wpi::units::pecks", + "wpi::units::pinch", + "wpi::units::pinches", + "wpi::units::pint", + "wpi::units::pints", + "wpi::units::quart", + "wpi::units::quarts", + "wpi::units::sack", + "wpi::units::sacks", + "wpi::units::shot", + "wpi::units::shots", + "wpi::units::strike", + "wpi::units::strikes", + "wpi::units::tablespoon", + "wpi::units::tablespoons", + "wpi::units::teaspoon", + "wpi::units::teaspoons", ] default_arg_cast = false [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_compound_type_caster.h" types = [ - "units::curvature_t", + "wpi::units::curvature_t", ] default_arg_cast = true [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_compound_type_caster.h" types = [ - "units::compound_unit", - "units::inverse", + "wpi::units::compound_unit", + "wpi::units::inverse", ] default_arg_cast = false [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_misc_type_caster.h" types = [ - "units::dimensionless_t", - "units::dimensionless::dimensionless_t", - "units::scalar_t", - "units::dimensionless::scalar_t", + "wpi::units::dimensionless_t", + "wpi::units::dimensionless::dimensionless_t", + "wpi::units::scalar_t", + "wpi::units::dimensionless::scalar_t", ] default_arg_cast = true [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "units_misc_type_caster.h" types = [ - "units::dimensionless", - "units::dimensionless::dimensionless", - "units::scalar", - "units::dimensionless::scalar", + "wpi::units::dimensionless", + "wpi::units::dimensionless::dimensionless", + "wpi::units::scalar", + "wpi::units::dimensionless::scalar", ] default_arg_cast = false [[tool.semiwrap.export_type_casters.wpimath-casters.headers]] header = "frc_eigen.h" types = [ - "frc::Vectord", - "frc::Matrixd", + "wpi::math::Vectord", + "wpi::math::Matrixd", ] [tool.semiwrap.extension_modules."wpimath._wpimath"] diff --git a/wpimath/src/main/python/semiwrap/MathUtil.yml b/wpimath/src/main/python/semiwrap/MathUtil.yml index 8408fa5af9..04fa04bc0e 100644 --- a/wpimath/src/main/python/semiwrap/MathUtil.yml +++ b/wpimath/src/main/python/semiwrap/MathUtil.yml @@ -33,8 +33,8 @@ functions: - [double] SlewRateLimit: overloads: - const Translation2d&, const Translation2d&, units::second_t, units::meters_per_second_t: - const Translation3d&, const Translation3d&, units::second_t, units::meters_per_second_t: + const Translation2d&, const Translation2d&, wpi::units::second_t, wpi::units::meters_per_second_t: + const Translation3d&, const Translation3d&, wpi::units::second_t, wpi::units::meters_per_second_t: CopyDirectionPow: overloads: T, double, T: diff --git a/wpimath/src/main/python/semiwrap/controls/ArmFeedforward.yml b/wpimath/src/main/python/semiwrap/controls/ArmFeedforward.yml index 3c34a97d14..65d3920dfc 100644 --- a/wpimath/src/main/python/semiwrap/controls/ArmFeedforward.yml +++ b/wpimath/src/main/python/semiwrap/controls/ArmFeedforward.yml @@ -2,26 +2,26 @@ defaults: subpackage: controller classes: - frc::ArmFeedforward: + wpi::math::ArmFeedforward: force_type_casters: - - units::radians_per_second_squared + - wpi::units::radians_per_second_squared typealias: - - frc::ArmFeedforward::Acceleration - - frc::ArmFeedforward::kv_unit - - frc::ArmFeedforward::ka_unit + - wpi::math::ArmFeedforward::Acceleration + - wpi::math::ArmFeedforward::kv_unit + - wpi::math::ArmFeedforward::ka_unit methods: ArmFeedforward: overloads: '': - units::volt_t, units::volt_t, units::unit_t, units::unit_t: + wpi::units::volt_t, wpi::units::volt_t, wpi::units::unit_t, wpi::units::unit_t: Calculate: overloads: - units::unit_t, units::unit_t, units::unit_t [const]: + wpi::units::unit_t, wpi::units::unit_t, wpi::units::unit_t [const]: ignore: true - units::unit_t, units::unit_t, units::unit_t, units::second_t [const]: + wpi::units::unit_t, wpi::units::unit_t, wpi::units::unit_t, wpi::units::second_t [const]: ignore: true - units::unit_t, units::unit_t [const]: - units::unit_t, units::unit_t, units::unit_t [const]: + wpi::units::unit_t, wpi::units::unit_t [const]: + wpi::units::unit_t, wpi::units::unit_t, wpi::units::unit_t [const]: MaxAchievableVelocity: MinAchievableVelocity: MaxAchievableAcceleration: @@ -39,4 +39,4 @@ extra_includes: - wpystruct.h inline_code: | - SetupWPyStruct(cls_ArmFeedforward); + SetupWPyStruct(cls_ArmFeedforward); diff --git a/wpimath/src/main/python/semiwrap/controls/BangBangController.yml b/wpimath/src/main/python/semiwrap/controls/BangBangController.yml index 3fd20d7e74..daf522a642 100644 --- a/wpimath/src/main/python/semiwrap/controls/BangBangController.yml +++ b/wpimath/src/main/python/semiwrap/controls/BangBangController.yml @@ -2,9 +2,9 @@ defaults: subpackage: controller classes: - frc::BangBangController: + wpi::math::BangBangController: ignored_bases: - - wpi::SendableHelper + - wpi::util::SendableHelper methods: BangBangController: SetSetpoint: diff --git a/wpimath/src/main/python/semiwrap/controls/CentripetalAccelerationConstraint.yml b/wpimath/src/main/python/semiwrap/controls/CentripetalAccelerationConstraint.yml index d93fada353..5de0cacf8d 100644 --- a/wpimath/src/main/python/semiwrap/controls/CentripetalAccelerationConstraint.yml +++ b/wpimath/src/main/python/semiwrap/controls/CentripetalAccelerationConstraint.yml @@ -2,9 +2,9 @@ defaults: subpackage: constraint classes: - frc::CentripetalAccelerationConstraint: + wpi::math::CentripetalAccelerationConstraint: typealias: - - frc::TrajectoryConstraint::MinMax + - wpi::math::TrajectoryConstraint::MinMax methods: CentripetalAccelerationConstraint: MaxVelocity: @@ -12,6 +12,6 @@ classes: inline_code: |- cls_CentripetalAccelerationConstraint - .def_static("fromFps", [](units::feet_per_second_squared_t maxCentripetalAcceleration) { + .def_static("fromFps", [](wpi::units::feet_per_second_squared_t maxCentripetalAcceleration) { return std::make_shared(maxCentripetalAcceleration); }, py::arg("maxCentripetalAcceleration")); diff --git a/wpimath/src/main/python/semiwrap/controls/ControlAffinePlantInversionFeedforward.yml b/wpimath/src/main/python/semiwrap/controls/ControlAffinePlantInversionFeedforward.yml index 32451caed2..d765af91fd 100644 --- a/wpimath/src/main/python/semiwrap/controls/ControlAffinePlantInversionFeedforward.yml +++ b/wpimath/src/main/python/semiwrap/controls/ControlAffinePlantInversionFeedforward.yml @@ -2,15 +2,15 @@ defaults: subpackage: controller classes: - frc::ControlAffinePlantInversionFeedforward: + wpi::math::ControlAffinePlantInversionFeedforward: template_params: - int States - int Inputs methods: ControlAffinePlantInversionFeedforward: overloads: - std::function, units::second_t: - std::function, const Matrixd&, units::second_t: + std::function, wpi::units::second_t: + std::function, const Matrixd&, wpi::units::second_t: Uff: overloads: '[const]': @@ -30,17 +30,17 @@ classes: templates: ControlAffinePlantInversionFeedforward_1_1: - qualname: frc::ControlAffinePlantInversionFeedforward + qualname: wpi::math::ControlAffinePlantInversionFeedforward params: - 1 - 1 ControlAffinePlantInversionFeedforward_2_1: - qualname: frc::ControlAffinePlantInversionFeedforward + qualname: wpi::math::ControlAffinePlantInversionFeedforward params: - 2 - 1 ControlAffinePlantInversionFeedforward_2_2: - qualname: frc::ControlAffinePlantInversionFeedforward + qualname: wpi::math::ControlAffinePlantInversionFeedforward params: - 2 - 2 diff --git a/wpimath/src/main/python/semiwrap/controls/DCMotor.yml b/wpimath/src/main/python/semiwrap/controls/DCMotor.yml index 68c659a083..c5fd38711e 100644 --- a/wpimath/src/main/python/semiwrap/controls/DCMotor.yml +++ b/wpimath/src/main/python/semiwrap/controls/DCMotor.yml @@ -5,7 +5,7 @@ extra_includes: - wpystruct.h classes: - frc::DCMotor: + wpi::math::DCMotor: attributes: nominalVoltage: stallTorque: @@ -19,8 +19,8 @@ classes: DCMotor: Current: overloads: - units::radians_per_second_t, units::volt_t [const]: - units::newton_meter_t [const]: + wpi::units::radians_per_second_t, wpi::units::volt_t [const]: + wpi::units::newton_meter_t [const]: Torque: Voltage: Speed: @@ -46,4 +46,4 @@ classes: Minion: inline_code: | - SetupWPyStruct(cls_DCMotor); + SetupWPyStruct(cls_DCMotor); diff --git a/wpimath/src/main/python/semiwrap/controls/DifferentialDriveAccelerationLimiter.yml b/wpimath/src/main/python/semiwrap/controls/DifferentialDriveAccelerationLimiter.yml index bd8864415c..76ee6fa0e9 100644 --- a/wpimath/src/main/python/semiwrap/controls/DifferentialDriveAccelerationLimiter.yml +++ b/wpimath/src/main/python/semiwrap/controls/DifferentialDriveAccelerationLimiter.yml @@ -2,11 +2,11 @@ defaults: subpackage: controller classes: - frc::DifferentialDriveAccelerationLimiter: + wpi::math::DifferentialDriveAccelerationLimiter: methods: DifferentialDriveAccelerationLimiter: overloads: - LinearSystem<2, 2, 2>, units::meter_t, units::meters_per_second_squared_t, units::radians_per_second_squared_t: - ? LinearSystem<2, 2, 2>, units::meter_t, units::meters_per_second_squared_t, units::meters_per_second_squared_t, units::radians_per_second_squared_t + LinearSystem<2, 2, 2>, wpi::units::meter_t, wpi::units::meters_per_second_squared_t, wpi::units::radians_per_second_squared_t: + ? LinearSystem<2, 2, 2>, wpi::units::meter_t, wpi::units::meters_per_second_squared_t, wpi::units::meters_per_second_squared_t, wpi::units::radians_per_second_squared_t : Calculate: diff --git a/wpimath/src/main/python/semiwrap/controls/DifferentialDriveFeedforward.yml b/wpimath/src/main/python/semiwrap/controls/DifferentialDriveFeedforward.yml index ac8a9d1c8a..edd1d33bad 100644 --- a/wpimath/src/main/python/semiwrap/controls/DifferentialDriveFeedforward.yml +++ b/wpimath/src/main/python/semiwrap/controls/DifferentialDriveFeedforward.yml @@ -2,13 +2,13 @@ defaults: subpackage: controller classes: - frc::DifferentialDriveFeedforward: + wpi::math::DifferentialDriveFeedforward: force_type_casters: - - units::meters_per_second - - units::meters_per_second_squared - - units::radians_per_second - - units::radians_per_second_squared - - units::compound_unit + - wpi::units::meters_per_second + - wpi::units::meters_per_second_squared + - wpi::units::radians_per_second + - wpi::units::radians_per_second_squared + - wpi::units::compound_unit attributes: m_kVLinear: m_kALinear: @@ -17,10 +17,10 @@ classes: methods: DifferentialDriveFeedforward: overloads: - decltype(1_V/1_mps), decltype(1_V/1_mps_sq), decltype(1_V/1_rad_per_s), decltype(1_V/1_rad_per_s_sq), units::meter_t: + decltype(1_V/1_mps), decltype(1_V/1_mps_sq), decltype(1_V/1_rad_per_s), decltype(1_V/1_rad_per_s_sq), wpi::units::meter_t: decltype(1_V/1_mps), decltype(1_V/1_mps_sq), decltype(1_V/1_mps), decltype(1_V/1_mps_sq): # ? decltype ( 1 _V / 1 _mps ), decltype ( 1 _V / 1 _mps_sq ), decltype ( - # 1 _V / 1 _rad_per_s ), decltype ( 1 _V / 1 _rad_per_s_sq ), units::meter_t + # 1 _V / 1 _rad_per_s ), decltype ( 1 _V / 1 _rad_per_s_sq ), wpi::units::meter_t # : # param_override: # kVLinear: diff --git a/wpimath/src/main/python/semiwrap/controls/DifferentialDriveKinematicsConstraint.yml b/wpimath/src/main/python/semiwrap/controls/DifferentialDriveKinematicsConstraint.yml index f3dffbf1ba..9a74332425 100644 --- a/wpimath/src/main/python/semiwrap/controls/DifferentialDriveKinematicsConstraint.yml +++ b/wpimath/src/main/python/semiwrap/controls/DifferentialDriveKinematicsConstraint.yml @@ -2,9 +2,9 @@ defaults: subpackage: constraint classes: - frc::DifferentialDriveKinematicsConstraint: + wpi::math::DifferentialDriveKinematicsConstraint: typealias: - - frc::TrajectoryConstraint::MinMax + - wpi::math::TrajectoryConstraint::MinMax methods: DifferentialDriveKinematicsConstraint: MaxVelocity: @@ -13,7 +13,7 @@ classes: inline_code: |- cls_DifferentialDriveKinematicsConstraint .def_static("fromFps", [](const DifferentialDriveKinematics& kinematics, - units::feet_per_second_t maxSpeed) { + wpi::units::feet_per_second_t maxSpeed) { return std::make_shared(kinematics, maxSpeed); }, py::arg("kinematics"), py::arg("maxSpeed")) ; diff --git a/wpimath/src/main/python/semiwrap/controls/DifferentialDrivePoseEstimator.yml b/wpimath/src/main/python/semiwrap/controls/DifferentialDrivePoseEstimator.yml index a99a28dffc..f765ca54c2 100644 --- a/wpimath/src/main/python/semiwrap/controls/DifferentialDrivePoseEstimator.yml +++ b/wpimath/src/main/python/semiwrap/controls/DifferentialDrivePoseEstimator.yml @@ -2,7 +2,7 @@ defaults: subpackage: estimator classes: - frc::DifferentialDrivePoseEstimator: + wpi::math::DifferentialDrivePoseEstimator: force_no_trampoline: true doc: | This class wraps an Unscented Kalman Filter to fuse latency-compensated @@ -40,8 +40,8 @@ classes: methods: DifferentialDrivePoseEstimator: overloads: - DifferentialDriveKinematics&, const Rotation2d&, units::meter_t, units::meter_t, const Pose2d&: - ? DifferentialDriveKinematics&, const Rotation2d&, units::meter_t, units::meter_t, const Pose2d&, const wpi::array&, const wpi::array& + DifferentialDriveKinematics&, const Rotation2d&, wpi::units::meter_t, wpi::units::meter_t, const Pose2d&: + ? DifferentialDriveKinematics&, const Rotation2d&, wpi::units::meter_t, wpi::units::meter_t, const Pose2d&, const wpi::util::array&, const wpi::util::array& : ResetPosition: Update: diff --git a/wpimath/src/main/python/semiwrap/controls/DifferentialDrivePoseEstimator3d.yml b/wpimath/src/main/python/semiwrap/controls/DifferentialDrivePoseEstimator3d.yml index 847cf4a799..3466dbef79 100644 --- a/wpimath/src/main/python/semiwrap/controls/DifferentialDrivePoseEstimator3d.yml +++ b/wpimath/src/main/python/semiwrap/controls/DifferentialDrivePoseEstimator3d.yml @@ -2,13 +2,13 @@ defaults: subpackage: estimator classes: - frc::DifferentialDrivePoseEstimator3d: + wpi::math::DifferentialDrivePoseEstimator3d: force_no_trampoline: true methods: DifferentialDrivePoseEstimator3d: overloads: - DifferentialDriveKinematics&, const Rotation3d&, units::meter_t, units::meter_t, const Pose3d&: - ? DifferentialDriveKinematics&, const Rotation3d&, units::meter_t, units::meter_t, const Pose3d&, const wpi::array&, const wpi::array& + DifferentialDriveKinematics&, const Rotation3d&, wpi::units::meter_t, wpi::units::meter_t, const Pose3d&: + ? DifferentialDriveKinematics&, const Rotation3d&, wpi::units::meter_t, wpi::units::meter_t, const Pose3d&, const wpi::util::array&, const wpi::util::array& : ResetPosition: Update: diff --git a/wpimath/src/main/python/semiwrap/controls/DifferentialDriveVoltageConstraint.yml b/wpimath/src/main/python/semiwrap/controls/DifferentialDriveVoltageConstraint.yml index 2107520b50..e8720f9865 100644 --- a/wpimath/src/main/python/semiwrap/controls/DifferentialDriveVoltageConstraint.yml +++ b/wpimath/src/main/python/semiwrap/controls/DifferentialDriveVoltageConstraint.yml @@ -2,9 +2,9 @@ defaults: subpackage: constraint classes: - frc::DifferentialDriveVoltageConstraint: + wpi::math::DifferentialDriveVoltageConstraint: typealias: - - frc::TrajectoryConstraint::MinMax + - wpi::math::TrajectoryConstraint::MinMax methods: DifferentialDriveVoltageConstraint: MaxVelocity: diff --git a/wpimath/src/main/python/semiwrap/controls/DifferentialDriveWheelVoltages.yml b/wpimath/src/main/python/semiwrap/controls/DifferentialDriveWheelVoltages.yml index e199e03161..f2c0f5c4d7 100644 --- a/wpimath/src/main/python/semiwrap/controls/DifferentialDriveWheelVoltages.yml +++ b/wpimath/src/main/python/semiwrap/controls/DifferentialDriveWheelVoltages.yml @@ -3,7 +3,7 @@ defaults: classes: - frc::DifferentialDriveWheelVoltages: + wpi::math::DifferentialDriveWheelVoltages: force_no_default_constructor: true attributes: left: @@ -14,7 +14,7 @@ extra_includes: inline_code: | cls_DifferentialDriveWheelVoltages - .def(py::init(), + .def(py::init(), py::arg("left") = 0, py::arg("right") = 0) .def("__repr__", [](const DifferentialDriveWheelVoltages *self) { return "DifferentialDriveWheelVoltages(" @@ -23,4 +23,4 @@ inline_code: | }) ; - SetupWPyStruct(cls_DifferentialDriveWheelVoltages); + SetupWPyStruct(cls_DifferentialDriveWheelVoltages); diff --git a/wpimath/src/main/python/semiwrap/controls/ElevatorFeedforward.yml b/wpimath/src/main/python/semiwrap/controls/ElevatorFeedforward.yml index e44d36584f..974d22b42e 100644 --- a/wpimath/src/main/python/semiwrap/controls/ElevatorFeedforward.yml +++ b/wpimath/src/main/python/semiwrap/controls/ElevatorFeedforward.yml @@ -2,23 +2,23 @@ defaults: subpackage: controller classes: - frc::ElevatorFeedforward: + wpi::math::ElevatorFeedforward: force_type_casters: - - units::meters_per_second + - wpi::units::meters_per_second - meters_per_second_squared methods: ElevatorFeedforward: overloads: '': - units::volt_t, units::volt_t, units::unit_t, units::unit_t: + wpi::units::volt_t, wpi::units::volt_t, wpi::units::unit_t, wpi::units::unit_t: Calculate: overloads: - units::unit_t, units::unit_t [const]: + wpi::units::unit_t, wpi::units::unit_t [const]: ignore: true - units::unit_t, units::unit_t, units::second_t [const]: + wpi::units::unit_t, wpi::units::unit_t, wpi::units::second_t [const]: ignore: true - units::unit_t [const]: - units::unit_t, units::unit_t [const]: + wpi::units::unit_t [const]: + wpi::units::unit_t, wpi::units::unit_t [const]: MaxAchievableVelocity: MinAchievableVelocity: MaxAchievableAcceleration: @@ -36,4 +36,4 @@ extra_includes: - wpystruct.h inline_code: | - SetupWPyStruct(cls_ElevatorFeedforward); + SetupWPyStruct(cls_ElevatorFeedforward); diff --git a/wpimath/src/main/python/semiwrap/controls/EllipticalRegionConstraint.yml b/wpimath/src/main/python/semiwrap/controls/EllipticalRegionConstraint.yml index d48f5c2112..d8c8dadbf8 100644 --- a/wpimath/src/main/python/semiwrap/controls/EllipticalRegionConstraint.yml +++ b/wpimath/src/main/python/semiwrap/controls/EllipticalRegionConstraint.yml @@ -5,23 +5,23 @@ extra_includes: - PyTrajectoryConstraint.h classes: - frc::EllipticalRegionConstraint: + wpi::math::EllipticalRegionConstraint: template_params: - typename Constraint typealias: - - frc::TrajectoryConstraint::MinMax + - wpi::math::TrajectoryConstraint::MinMax methods: EllipticalRegionConstraint: overloads: - const Translation2d&, units::meter_t, units::meter_t, const Rotation2d&, const Constraint&: + const Translation2d&, wpi::units::meter_t, wpi::units::meter_t, const Rotation2d&, const Constraint&: const Ellipse2d&, const Constraint&: MaxVelocity: MinMaxAcceleration: template_inline_code: | cls_EllipticalRegionConstraint - .def_static("fromFeet", [](const Translation2d& center, units::foot_t xWidth, - units::foot_t yWidth, const Rotation2d& rotation, + .def_static("fromFeet", [](const Translation2d& center, wpi::units::foot_t xWidth, + wpi::units::foot_t yWidth, const Rotation2d& rotation, const Constraint& constraint) { return std::make_shared>(center, xWidth, yWidth, rotation, constraint); }, py::arg("center"), py::arg("xWidth"), py::arg("yWidth"), py::arg("rotation"), py::arg("constraint")) @@ -29,6 +29,6 @@ classes: templates: EllipticalRegionConstraint: - qualname: frc::EllipticalRegionConstraint + qualname: wpi::math::EllipticalRegionConstraint params: - - frc::PyTrajectoryConstraint + - wpi::math::PyTrajectoryConstraint diff --git a/wpimath/src/main/python/semiwrap/controls/ExponentialProfile.yml b/wpimath/src/main/python/semiwrap/controls/ExponentialProfile.yml index eff51e3d04..96532b038f 100644 --- a/wpimath/src/main/python/semiwrap/controls/ExponentialProfile.yml +++ b/wpimath/src/main/python/semiwrap/controls/ExponentialProfile.yml @@ -2,9 +2,9 @@ defaults: subpackage: trajectory classes: - frc::ExponentialProfile: + wpi::math::ExponentialProfile: force_type_casters: - - units::meters_per_second_t + - wpi::units::meters_per_second_t template_params: - Distance - Input @@ -18,7 +18,7 @@ classes: CalculateProfileTiming: overloads: const State&, const State& [const]: - frc::ExponentialProfile::Constraints: + wpi::math::ExponentialProfile::Constraints: attributes: maxInput: A: @@ -33,13 +33,13 @@ classes: MaxVelocity: inline_code: | .def_static("fromStateSpace", [](Input_t maxInput, A_t a, B_t b) { - return typename frc::ExponentialProfile::Constraints(maxInput, a, b); + return typename wpi::math::ExponentialProfile::Constraints(maxInput, a, b); }, py::arg("maxInput"), py::arg("a"), py::arg("b")) .def_static("fromCharacteristics", [](Input_t maxInput, kV_t kv, kA_t ka) { - return typename frc::ExponentialProfile::Constraints(maxInput, kv, ka); + return typename wpi::math::ExponentialProfile::Constraints(maxInput, kv, ka); }, py::arg("maxInput"), py::arg("kV"), py::arg("kA")) - frc::ExponentialProfile::State: + wpi::math::ExponentialProfile::State: force_no_default_constructor: true attributes: position: @@ -48,7 +48,7 @@ classes: operator==: inline_code: | .def(py::init()) - frc::ExponentialProfile::ProfileTiming: + wpi::math::ExponentialProfile::ProfileTiming: attributes: inflectionTime: totalTime: @@ -57,7 +57,7 @@ classes: templates: ExponentialProfileMeterVolts: - qualname: frc::ExponentialProfile + qualname: wpi::math::ExponentialProfile params: - - units::meter - - units::volt + - wpi::units::meter + - wpi::units::volt diff --git a/wpimath/src/main/python/semiwrap/controls/ExtendedKalmanFilter.yml b/wpimath/src/main/python/semiwrap/controls/ExtendedKalmanFilter.yml index 27eae06003..95338b6999 100644 --- a/wpimath/src/main/python/semiwrap/controls/ExtendedKalmanFilter.yml +++ b/wpimath/src/main/python/semiwrap/controls/ExtendedKalmanFilter.yml @@ -2,7 +2,7 @@ defaults: subpackage: estimator classes: - frc::ExtendedKalmanFilter: + wpi::math::ExtendedKalmanFilter: template_params: - int States - int Inputs @@ -10,9 +10,9 @@ classes: methods: ExtendedKalmanFilter: overloads: - ? std::function, std::function, const StateArray&, const OutputArray&, units::second_t + ? std::function, std::function, const StateArray&, const OutputArray&, wpi::units::second_t : - ? std::function, std::function, const StateArray&, const OutputArray&, std::function, std::function, units::second_t + ? std::function, std::function, const StateArray&, const OutputArray&, std::function, std::function, wpi::units::second_t : P: overloads: @@ -41,25 +41,25 @@ classes: templates: ExtendedKalmanFilter_1_1_1: - qualname: frc::ExtendedKalmanFilter + qualname: wpi::math::ExtendedKalmanFilter params: - 1 - 1 - 1 ExtendedKalmanFilter_2_1_1: - qualname: frc::ExtendedKalmanFilter + qualname: wpi::math::ExtendedKalmanFilter params: - 2 - 1 - 1 ExtendedKalmanFilter_2_1_2: - qualname: frc::ExtendedKalmanFilter + qualname: wpi::math::ExtendedKalmanFilter params: - 2 - 1 - 2 ExtendedKalmanFilter_2_2_2: - qualname: frc::ExtendedKalmanFilter + qualname: wpi::math::ExtendedKalmanFilter params: - 2 - 2 diff --git a/wpimath/src/main/python/semiwrap/controls/ImplicitModelFollower.yml b/wpimath/src/main/python/semiwrap/controls/ImplicitModelFollower.yml index e1bf7563b3..f1d240a3c2 100644 --- a/wpimath/src/main/python/semiwrap/controls/ImplicitModelFollower.yml +++ b/wpimath/src/main/python/semiwrap/controls/ImplicitModelFollower.yml @@ -2,7 +2,7 @@ defaults: subpackage: controller classes: - frc::ImplicitModelFollower: + wpi::math::ImplicitModelFollower: template_params: - int States - int Inputs @@ -22,27 +22,27 @@ classes: template_inline_code: | cls_ImplicitModelFollower - .def(py::init&, const frc::LinearSystem&>(), + .def(py::init&, const wpi::math::LinearSystem&>(), py::arg("plant"), py::arg("plantRef")) - .def(py::init&, const frc::LinearSystem&>(), + .def(py::init&, const wpi::math::LinearSystem&>(), py::arg("plant"), py::arg("plantRef")) - .def(py::init&, const frc::LinearSystem&>(), + .def(py::init&, const wpi::math::LinearSystem&>(), py::arg("plant"), py::arg("plantRef")) ; templates: ImplicitModelFollower_1_1: - qualname: frc::ImplicitModelFollower + qualname: wpi::math::ImplicitModelFollower params: - 1 - 1 ImplicitModelFollower_2_1: - qualname: frc::ImplicitModelFollower + qualname: wpi::math::ImplicitModelFollower params: - 2 - 1 ImplicitModelFollower_2_2: - qualname: frc::ImplicitModelFollower + qualname: wpi::math::ImplicitModelFollower params: - 2 - 2 diff --git a/wpimath/src/main/python/semiwrap/controls/KalmanFilter.yml b/wpimath/src/main/python/semiwrap/controls/KalmanFilter.yml index 6ea53930fd..94b780203c 100644 --- a/wpimath/src/main/python/semiwrap/controls/KalmanFilter.yml +++ b/wpimath/src/main/python/semiwrap/controls/KalmanFilter.yml @@ -2,7 +2,7 @@ defaults: subpackage: estimator classes: - frc::KalmanFilter: + wpi::math::KalmanFilter: template_params: - int States - int Inputs @@ -31,31 +31,31 @@ classes: templates: KalmanFilter_1_1_1: - qualname: frc::KalmanFilter + qualname: wpi::math::KalmanFilter params: - 1 - 1 - 1 KalmanFilter_2_1_1: - qualname: frc::KalmanFilter + qualname: wpi::math::KalmanFilter params: - 2 - 1 - 1 KalmanFilter_2_1_2: - qualname: frc::KalmanFilter + qualname: wpi::math::KalmanFilter params: - 2 - 1 - 2 KalmanFilter_2_2_2: - qualname: frc::KalmanFilter + qualname: wpi::math::KalmanFilter params: - 2 - 2 - 2 KalmanFilter_3_2_3: - qualname: frc::KalmanFilter + qualname: wpi::math::KalmanFilter params: - 3 - 2 diff --git a/wpimath/src/main/python/semiwrap/controls/LTVDifferentialDriveController.yml b/wpimath/src/main/python/semiwrap/controls/LTVDifferentialDriveController.yml index 36abca332f..5b63d020f4 100644 --- a/wpimath/src/main/python/semiwrap/controls/LTVDifferentialDriveController.yml +++ b/wpimath/src/main/python/semiwrap/controls/LTVDifferentialDriveController.yml @@ -2,13 +2,13 @@ defaults: subpackage: controller classes: - frc::LTVDifferentialDriveController: + wpi::math::LTVDifferentialDriveController: methods: LTVDifferentialDriveController: AtReference: SetTolerance: Calculate: overloads: - ? const Pose2d&, units::meters_per_second_t, units::meters_per_second_t, const Pose2d&, units::meters_per_second_t, units::meters_per_second_t + ? const Pose2d&, wpi::units::meters_per_second_t, wpi::units::meters_per_second_t, const Pose2d&, wpi::units::meters_per_second_t, wpi::units::meters_per_second_t : - const Pose2d&, units::meters_per_second_t, units::meters_per_second_t, const Trajectory::State&: + const Pose2d&, wpi::units::meters_per_second_t, wpi::units::meters_per_second_t, const Trajectory::State&: diff --git a/wpimath/src/main/python/semiwrap/controls/LTVUnicycleController.yml b/wpimath/src/main/python/semiwrap/controls/LTVUnicycleController.yml index 6611e474f7..0c94264d05 100644 --- a/wpimath/src/main/python/semiwrap/controls/LTVUnicycleController.yml +++ b/wpimath/src/main/python/semiwrap/controls/LTVUnicycleController.yml @@ -2,12 +2,12 @@ defaults: subpackage: controller classes: - frc::LTVUnicycleController: + wpi::math::LTVUnicycleController: methods: LTVUnicycleController: overloads: - units::second_t: - const wpi::array&, const wpi::array&, units::second_t: + wpi::units::second_t: + const wpi::util::array&, const wpi::util::array&, wpi::units::second_t: # param_override: # maxVelocity: # default: 9_mps @@ -15,6 +15,6 @@ classes: SetTolerance: Calculate: overloads: - const Pose2d&, const Pose2d&, units::meters_per_second_t, units::radians_per_second_t: + const Pose2d&, const Pose2d&, wpi::units::meters_per_second_t, wpi::units::radians_per_second_t: const Pose2d&, const Trajectory::State&: SetEnabled: diff --git a/wpimath/src/main/python/semiwrap/controls/LinearPlantInversionFeedforward.yml b/wpimath/src/main/python/semiwrap/controls/LinearPlantInversionFeedforward.yml index 93deccc6de..4e6743d348 100644 --- a/wpimath/src/main/python/semiwrap/controls/LinearPlantInversionFeedforward.yml +++ b/wpimath/src/main/python/semiwrap/controls/LinearPlantInversionFeedforward.yml @@ -2,16 +2,16 @@ defaults: subpackage: controller classes: - frc::LinearPlantInversionFeedforward: + wpi::math::LinearPlantInversionFeedforward: template_params: - int States - int Inputs methods: LinearPlantInversionFeedforward: overloads: - const LinearSystem&, units::second_t: + const LinearSystem&, wpi::units::second_t: ignore: true - const Matrixd&, const Matrixd&, units::second_t: + const Matrixd&, const Matrixd&, wpi::units::second_t: Uff: overloads: '[const]': @@ -31,22 +31,22 @@ classes: templates: LinearPlantInversionFeedforward_1_1: - qualname: frc::LinearPlantInversionFeedforward + qualname: wpi::math::LinearPlantInversionFeedforward params: - 1 - 1 LinearPlantInversionFeedforward_2_1: - qualname: frc::LinearPlantInversionFeedforward + qualname: wpi::math::LinearPlantInversionFeedforward params: - 2 - 1 LinearPlantInversionFeedforward_2_2: - qualname: frc::LinearPlantInversionFeedforward + qualname: wpi::math::LinearPlantInversionFeedforward params: - 2 - 2 LinearPlantInversionFeedforward_3_2: - qualname: frc::LinearPlantInversionFeedforward + qualname: wpi::math::LinearPlantInversionFeedforward params: - 3 - 2 diff --git a/wpimath/src/main/python/semiwrap/controls/LinearQuadraticRegulator.yml b/wpimath/src/main/python/semiwrap/controls/LinearQuadraticRegulator.yml index addb967db2..025b5c0cf6 100644 --- a/wpimath/src/main/python/semiwrap/controls/LinearQuadraticRegulator.yml +++ b/wpimath/src/main/python/semiwrap/controls/LinearQuadraticRegulator.yml @@ -2,19 +2,19 @@ defaults: subpackage: controller classes: - frc::LinearQuadraticRegulator: + wpi::math::LinearQuadraticRegulator: template_params: - int States - int Inputs methods: LinearQuadraticRegulator: overloads: - const LinearSystem&, const StateArray&, const InputArray&, units::second_t: + const LinearSystem&, const StateArray&, const InputArray&, wpi::units::second_t: ignore: true - const Matrixd&, const Matrixd&, const StateArray&, const InputArray&, units::second_t: - ? const Matrixd&, const Matrixd&, const Matrixd&, const Matrixd&, units::second_t + const Matrixd&, const Matrixd&, const StateArray&, const InputArray&, wpi::units::second_t: + ? const Matrixd&, const Matrixd&, const Matrixd&, const Matrixd&, wpi::units::second_t : - ? const Matrixd&, const Matrixd&, const Matrixd&, const Matrixd&, const Matrixd&, units::second_t + ? const Matrixd&, const Matrixd&, const Matrixd&, const Matrixd&, const Matrixd&, wpi::units::second_t : K: overloads: @@ -39,28 +39,28 @@ classes: - ['2'] template_inline_code: | cls_LinearQuadraticRegulator - .def(py::init&, const wpi::array&, const wpi::array&, units::second_t>()) - .def(py::init&, const wpi::array&, const wpi::array&, units::second_t>()) - .def(py::init&, const wpi::array&, const wpi::array&, units::second_t>()); + .def(py::init&, const wpi::util::array&, const wpi::util::array&, wpi::units::second_t>()) + .def(py::init&, const wpi::util::array&, const wpi::util::array&, wpi::units::second_t>()) + .def(py::init&, const wpi::util::array&, const wpi::util::array&, wpi::units::second_t>()); templates: LinearQuadraticRegulator_1_1: - qualname: frc::LinearQuadraticRegulator + qualname: wpi::math::LinearQuadraticRegulator params: - 1 - 1 LinearQuadraticRegulator_2_1: - qualname: frc::LinearQuadraticRegulator + qualname: wpi::math::LinearQuadraticRegulator params: - 2 - 1 LinearQuadraticRegulator_2_2: - qualname: frc::LinearQuadraticRegulator + qualname: wpi::math::LinearQuadraticRegulator params: - 2 - 2 LinearQuadraticRegulator_3_2: - qualname: frc::LinearQuadraticRegulator + qualname: wpi::math::LinearQuadraticRegulator params: - 3 - 2 diff --git a/wpimath/src/main/python/semiwrap/controls/LinearSystem.yml b/wpimath/src/main/python/semiwrap/controls/LinearSystem.yml index a96d320ebd..52ccfd459d 100644 --- a/wpimath/src/main/python/semiwrap/controls/LinearSystem.yml +++ b/wpimath/src/main/python/semiwrap/controls/LinearSystem.yml @@ -2,7 +2,7 @@ defaults: subpackage: system classes: - frc::LinearSystem: + wpi::math::LinearSystem: template_params: - int States - int Inputs @@ -33,73 +33,73 @@ classes: templates: LinearSystem_1_1_1: - qualname: frc::LinearSystem + qualname: wpi::math::LinearSystem params: - 1 - 1 - 1 LinearSystem_1_1_2: - qualname: frc::LinearSystem + qualname: wpi::math::LinearSystem params: - 1 - 1 - 2 LinearSystem_1_1_3: - qualname: frc::LinearSystem + qualname: wpi::math::LinearSystem params: - 1 - 1 - 3 LinearSystem_2_1_1: - qualname: frc::LinearSystem + qualname: wpi::math::LinearSystem params: - 2 - 1 - 1 LinearSystem_2_1_2: - qualname: frc::LinearSystem + qualname: wpi::math::LinearSystem params: - 2 - 1 - 2 LinearSystem_2_1_3: - qualname: frc::LinearSystem + qualname: wpi::math::LinearSystem params: - 2 - 1 - 3 LinearSystem_2_2_1: - qualname: frc::LinearSystem + qualname: wpi::math::LinearSystem params: - 2 - 2 - 1 LinearSystem_2_2_2: - qualname: frc::LinearSystem + qualname: wpi::math::LinearSystem params: - 2 - 2 - 2 LinearSystem_2_2_3: - qualname: frc::LinearSystem + qualname: wpi::math::LinearSystem params: - 2 - 2 - 3 LinearSystem_3_2_1: - qualname: frc::LinearSystem + qualname: wpi::math::LinearSystem params: - 3 - 2 - 1 LinearSystem_3_2_2: - qualname: frc::LinearSystem + qualname: wpi::math::LinearSystem params: - 3 - 2 - 2 LinearSystem_3_2_3: - qualname: frc::LinearSystem + qualname: wpi::math::LinearSystem params: - 3 - 2 diff --git a/wpimath/src/main/python/semiwrap/controls/LinearSystemId.yml b/wpimath/src/main/python/semiwrap/controls/LinearSystemId.yml index 52874e4dd4..052bddddc3 100644 --- a/wpimath/src/main/python/semiwrap/controls/LinearSystemId.yml +++ b/wpimath/src/main/python/semiwrap/controls/LinearSystemId.yml @@ -2,12 +2,12 @@ defaults: subpackage: plant classes: - frc::LinearSystemId: + wpi::math::LinearSystemId: typealias: - - kv_meters = units::unit_t>> - - kv_radians = units::unit_t>> - - ka_meters = units::unit_t>> - - ka_radians = units::unit_t>> + - kv_meters = wpi::units::unit_t>> + - kv_radians = wpi::units::unit_t>> + - ka_meters = wpi::units::unit_t>> + - ka_radians = wpi::units::unit_t>> methods: ElevatorSystem: SingleJointedArmSystem: @@ -15,48 +15,48 @@ classes: rename: identifyVelocitySystemMeters cpp_code: | [](kv_meters kV, ka_meters kA) { - return frc::LinearSystemId::IdentifyVelocitySystem(kV, kA); + return wpi::math::LinearSystemId::IdentifyVelocitySystem(kV, kA); } IdentifyPositionSystem: rename: identifyPositionSystemMeters cpp_code: | [](kv_meters kV, ka_meters kA) { - return frc::LinearSystemId::IdentifyPositionSystem(kV, kA); + return wpi::math::LinearSystemId::IdentifyPositionSystem(kV, kA); } IdentifyDrivetrainSystem: overloads: decltype(1_V/1_mps), decltype(1_V/1_mps_sq), decltype(1_V/1_mps), decltype(1_V/1_mps_sq): cpp_code: | [](kv_meters kVlinear, ka_meters kAlinear, kv_meters kVangular, ka_meters kAangular) { - return frc::LinearSystemId::IdentifyDrivetrainSystem(kVlinear, kAlinear, kVangular, kAangular); + return wpi::math::LinearSystemId::IdentifyDrivetrainSystem(kVlinear, kAlinear, kVangular, kAangular); } - decltype(1_V/1_mps), decltype(1_V/1_mps_sq), decltype(1_V/1_rad_per_s), decltype(1_V/1_rad_per_s_sq), units::meter_t: + decltype(1_V/1_mps), decltype(1_V/1_mps_sq), decltype(1_V/1_rad_per_s), decltype(1_V/1_rad_per_s_sq), wpi::units::meter_t: cpp_code: | - [](kv_meters kVlinear, ka_meters kAlinear, kv_radians kVangular, ka_radians kAangular, units::meter_t trackWidth) { - return frc::LinearSystemId::IdentifyDrivetrainSystem(kVlinear, kAlinear, kVangular, kAangular, trackWidth); + [](kv_meters kVlinear, ka_meters kAlinear, kv_radians kVangular, ka_radians kAangular, wpi::units::meter_t trackWidth) { + return wpi::math::LinearSystemId::IdentifyDrivetrainSystem(kVlinear, kAlinear, kVangular, kAangular, trackWidth); } FlywheelSystem: DCMotorSystem: overloads: - DCMotor, units::kilogram_square_meter_t, double: + DCMotor, wpi::units::kilogram_square_meter_t, double: decltype(1_V/Velocity_t (1)), decltype(1_V/Acceleration_t (1)): cpp_code: | [](kv_meters kv, ka_meters ka) { - return frc::LinearSystemId::DCMotorSystem(kv, ka); + return wpi::math::LinearSystemId::DCMotorSystem(kv, ka); } DrivetrainVelocitySystem: inline_code: | .def_static("DCMotorSystemRadians", [](kv_radians kV, ka_radians kA) { - return frc::LinearSystemId::DCMotorSystem(kV, kA); + return wpi::math::LinearSystemId::DCMotorSystem(kV, kA); }, py::arg("kV"), py::arg("kA"), release_gil() ) .def_static("identifyVelocitySystemRadians", [](kv_radians kV, ka_radians kA) { - return frc::LinearSystemId::IdentifyVelocitySystem(kV, kA); + return wpi::math::LinearSystemId::IdentifyVelocitySystem(kV, kA); }, py::arg("kV"), py::arg("kA"), release_gil() ) .def_static("identifyPositionSystemRadians", [](kv_radians kV, ka_radians kA) { - return frc::LinearSystemId::IdentifyPositionSystem(kV, kA); + return wpi::math::LinearSystemId::IdentifyPositionSystem(kV, kA); }, py::arg("kV"), py::arg("kA"), release_gil() ) diff --git a/wpimath/src/main/python/semiwrap/controls/LinearSystemLoop.yml b/wpimath/src/main/python/semiwrap/controls/LinearSystemLoop.yml index 09d0bc2b91..00a6897c84 100644 --- a/wpimath/src/main/python/semiwrap/controls/LinearSystemLoop.yml +++ b/wpimath/src/main/python/semiwrap/controls/LinearSystemLoop.yml @@ -2,7 +2,7 @@ defaults: subpackage: system classes: - frc::LinearSystemLoop: + wpi::math::LinearSystemLoop: template_params: - int States - int Inputs @@ -10,11 +10,11 @@ classes: methods: LinearSystemLoop: overloads: - ? LinearSystem&, LinearQuadraticRegulator&, KalmanFilter&, units::volt_t, units::second_t + ? LinearSystem&, LinearQuadraticRegulator&, KalmanFilter&, wpi::units::volt_t, wpi::units::second_t : - ? LinearSystem&, LinearQuadraticRegulator&, KalmanFilter&, std::function, units::second_t + ? LinearSystem&, LinearQuadraticRegulator&, KalmanFilter&, std::function, wpi::units::second_t : - ? LinearQuadraticRegulator&, const LinearPlantInversionFeedforward&, KalmanFilter&, units::volt_t + ? LinearQuadraticRegulator&, const LinearPlantInversionFeedforward&, KalmanFilter&, wpi::units::volt_t : ? LinearQuadraticRegulator&, const LinearPlantInversionFeedforward&, KalmanFilter&, std::function : @@ -48,31 +48,31 @@ classes: ClampInput: templates: LinearSystemLoop_1_1_1: - qualname: frc::LinearSystemLoop + qualname: wpi::math::LinearSystemLoop params: - 1 - 1 - 1 LinearSystemLoop_2_1_1: - qualname: frc::LinearSystemLoop + qualname: wpi::math::LinearSystemLoop params: - 2 - 1 - 1 LinearSystemLoop_2_1_2: - qualname: frc::LinearSystemLoop + qualname: wpi::math::LinearSystemLoop params: - 2 - 1 - 2 LinearSystemLoop_2_2_2: - qualname: frc::LinearSystemLoop + qualname: wpi::math::LinearSystemLoop params: - 2 - 2 - 2 LinearSystemLoop_3_2_3: - qualname: frc::LinearSystemLoop + qualname: wpi::math::LinearSystemLoop params: - 3 - 2 diff --git a/wpimath/src/main/python/semiwrap/controls/MaxVelocityConstraint.yml b/wpimath/src/main/python/semiwrap/controls/MaxVelocityConstraint.yml index 45053558a1..b6a2c94f31 100644 --- a/wpimath/src/main/python/semiwrap/controls/MaxVelocityConstraint.yml +++ b/wpimath/src/main/python/semiwrap/controls/MaxVelocityConstraint.yml @@ -2,9 +2,9 @@ defaults: subpackage: constraint classes: - frc::MaxVelocityConstraint: + wpi::math::MaxVelocityConstraint: typealias: - - frc::TrajectoryConstraint::MinMax + - wpi::math::TrajectoryConstraint::MinMax methods: MaxVelocityConstraint: MaxVelocity: @@ -12,7 +12,7 @@ classes: inline_code: |- cls_MaxVelocityConstraint - .def_static("fromFps", [](units::feet_per_second_t maxVelocity) { - return std::make_shared(maxVelocity); + .def_static("fromFps", [](wpi::units::feet_per_second_t maxVelocity) { + return std::make_shared(maxVelocity); }, py::arg("maxVelocity")) ; diff --git a/wpimath/src/main/python/semiwrap/controls/MecanumDriveKinematicsConstraint.yml b/wpimath/src/main/python/semiwrap/controls/MecanumDriveKinematicsConstraint.yml index 051b732356..acf677b0a3 100644 --- a/wpimath/src/main/python/semiwrap/controls/MecanumDriveKinematicsConstraint.yml +++ b/wpimath/src/main/python/semiwrap/controls/MecanumDriveKinematicsConstraint.yml @@ -2,9 +2,9 @@ defaults: subpackage: constraint classes: - frc::MecanumDriveKinematicsConstraint: + wpi::math::MecanumDriveKinematicsConstraint: typealias: - - frc::TrajectoryConstraint::MinMax + - wpi::math::TrajectoryConstraint::MinMax methods: MecanumDriveKinematicsConstraint: MaxVelocity: @@ -12,8 +12,8 @@ classes: inline_code: |- cls_MecanumDriveKinematicsConstraint - .def_static("fromFps", [](const frc::MecanumDriveKinematics& kinematics, - units::feet_per_second_t maxSpeed) { - return std::make_shared(kinematics, maxSpeed); + .def_static("fromFps", [](const wpi::math::MecanumDriveKinematics& kinematics, + wpi::units::feet_per_second_t maxSpeed) { + return std::make_shared(kinematics, maxSpeed); }, py::arg("kinematics"), py::arg("maxSpeed")) ; diff --git a/wpimath/src/main/python/semiwrap/controls/MecanumDrivePoseEstimator.yml b/wpimath/src/main/python/semiwrap/controls/MecanumDrivePoseEstimator.yml index f666b31874..48c27ad85c 100644 --- a/wpimath/src/main/python/semiwrap/controls/MecanumDrivePoseEstimator.yml +++ b/wpimath/src/main/python/semiwrap/controls/MecanumDrivePoseEstimator.yml @@ -2,7 +2,7 @@ defaults: subpackage: estimator classes: - frc::MecanumDrivePoseEstimator: + wpi::math::MecanumDrivePoseEstimator: force_no_trampoline: true doc: | This class wraps an Unscented Kalman Filter to fuse latency-compensated @@ -34,5 +34,5 @@ classes: MecanumDrivePoseEstimator: overloads: MecanumDriveKinematics&, const Rotation2d&, const MecanumDriveWheelPositions&, const Pose2d&: - ? MecanumDriveKinematics&, const Rotation2d&, const MecanumDriveWheelPositions&, const Pose2d&, const wpi::array&, const wpi::array& + ? MecanumDriveKinematics&, const Rotation2d&, const MecanumDriveWheelPositions&, const Pose2d&, const wpi::util::array&, const wpi::util::array& : diff --git a/wpimath/src/main/python/semiwrap/controls/MecanumDrivePoseEstimator3d.yml b/wpimath/src/main/python/semiwrap/controls/MecanumDrivePoseEstimator3d.yml index 3cac61fb3c..66a08e5f38 100644 --- a/wpimath/src/main/python/semiwrap/controls/MecanumDrivePoseEstimator3d.yml +++ b/wpimath/src/main/python/semiwrap/controls/MecanumDrivePoseEstimator3d.yml @@ -2,11 +2,11 @@ defaults: subpackage: estimator classes: - frc::MecanumDrivePoseEstimator3d: + wpi::math::MecanumDrivePoseEstimator3d: force_no_trampoline: true methods: MecanumDrivePoseEstimator3d: overloads: MecanumDriveKinematics&, const Rotation3d&, const MecanumDriveWheelPositions&, const Pose3d&: - ? MecanumDriveKinematics&, const Rotation3d&, const MecanumDriveWheelPositions&, const Pose3d&, const wpi::array&, const wpi::array& + ? MecanumDriveKinematics&, const Rotation3d&, const MecanumDriveWheelPositions&, const Pose3d&, const wpi::util::array&, const wpi::util::array& : diff --git a/wpimath/src/main/python/semiwrap/controls/PIDController.yml b/wpimath/src/main/python/semiwrap/controls/PIDController.yml index 4da68d4f73..00b2b07bc8 100644 --- a/wpimath/src/main/python/semiwrap/controls/PIDController.yml +++ b/wpimath/src/main/python/semiwrap/controls/PIDController.yml @@ -2,9 +2,9 @@ defaults: subpackage: controller classes: - frc::PIDController: + wpi::math::PIDController: ignored_bases: - - wpi::SendableHelper + - wpi::util::SendableHelper methods: PIDController: param_override: diff --git a/wpimath/src/main/python/semiwrap/controls/PoseEstimator.yml b/wpimath/src/main/python/semiwrap/controls/PoseEstimator.yml index 52ce29a3a1..5e95d1dde3 100644 --- a/wpimath/src/main/python/semiwrap/controls/PoseEstimator.yml +++ b/wpimath/src/main/python/semiwrap/controls/PoseEstimator.yml @@ -10,7 +10,7 @@ extra_includes: classes: - frc::PoseEstimator: + wpi::math::PoseEstimator: template_params: - WheelSpeeds - WheelPositions @@ -25,39 +25,39 @@ classes: SampleAt: AddVisionMeasurement: overloads: - const Pose2d&, units::second_t: - const Pose2d&, units::second_t, const wpi::array&: + const Pose2d&, wpi::units::second_t: + const Pose2d&, wpi::units::second_t, const wpi::util::array&: Update: UpdateWithTime: templates: DifferentialDrivePoseEstimatorBase: - qualname: frc::PoseEstimator + qualname: wpi::math::PoseEstimator params: - - frc::DifferentialDriveWheelSpeeds - - frc::DifferentialDriveWheelPositions + - wpi::math::DifferentialDriveWheelSpeeds + - wpi::math::DifferentialDriveWheelPositions MecanumDrivePoseEstimatorBase: - qualname: frc::PoseEstimator + qualname: wpi::math::PoseEstimator params: - - frc::MecanumDriveWheelSpeeds - - frc::MecanumDriveWheelPositions + - wpi::math::MecanumDriveWheelSpeeds + - wpi::math::MecanumDriveWheelPositions SwerveDrive2PoseEstimatorBase: - qualname: frc::PoseEstimator + qualname: wpi::math::PoseEstimator params: - - wpi::array - - wpi::array + - wpi::util::array + - wpi::util::array SwerveDrive3PoseEstimatorBase: - qualname: frc::PoseEstimator + qualname: wpi::math::PoseEstimator params: - - wpi::array - - wpi::array + - wpi::util::array + - wpi::util::array SwerveDrive4PoseEstimatorBase: - qualname: frc::PoseEstimator + qualname: wpi::math::PoseEstimator params: - - wpi::array - - wpi::array + - wpi::util::array + - wpi::util::array SwerveDrive6PoseEstimatorBase: - qualname: frc::PoseEstimator + qualname: wpi::math::PoseEstimator params: - - wpi::array - - wpi::array + - wpi::util::array + - wpi::util::array diff --git a/wpimath/src/main/python/semiwrap/controls/PoseEstimator3d.yml b/wpimath/src/main/python/semiwrap/controls/PoseEstimator3d.yml index 3ad301abb3..69cd62b6e6 100644 --- a/wpimath/src/main/python/semiwrap/controls/PoseEstimator3d.yml +++ b/wpimath/src/main/python/semiwrap/controls/PoseEstimator3d.yml @@ -9,7 +9,7 @@ extra_includes: - wpi/math/kinematics/SwerveDriveKinematics.hpp classes: - frc::PoseEstimator3d: + wpi::math::PoseEstimator3d: template_params: - WheelSpeeds - WheelPositions @@ -24,40 +24,40 @@ classes: SampleAt: AddVisionMeasurement: overloads: - const Pose3d&, units::second_t: - const Pose3d&, units::second_t, const wpi::array&: + const Pose3d&, wpi::units::second_t: + const Pose3d&, wpi::units::second_t, const wpi::util::array&: Update: UpdateWithTime: templates: DifferentialDrivePoseEstimator3dBase: - qualname: frc::PoseEstimator3d + qualname: wpi::math::PoseEstimator3d params: - - frc::DifferentialDriveWheelSpeeds - - frc::DifferentialDriveWheelPositions + - wpi::math::DifferentialDriveWheelSpeeds + - wpi::math::DifferentialDriveWheelPositions MecanumDrivePoseEstimator3dBase: - qualname: frc::PoseEstimator3d + qualname: wpi::math::PoseEstimator3d params: - - frc::MecanumDriveWheelSpeeds - - frc::MecanumDriveWheelPositions + - wpi::math::MecanumDriveWheelSpeeds + - wpi::math::MecanumDriveWheelPositions SwerveDrive2PoseEstimator3dBase: - qualname: frc::PoseEstimator3d + qualname: wpi::math::PoseEstimator3d params: - - wpi::array - - wpi::array + - wpi::util::array + - wpi::util::array SwerveDrive3PoseEstimator3dBase: - qualname: frc::PoseEstimator3d + qualname: wpi::math::PoseEstimator3d params: - - wpi::array - - wpi::array + - wpi::util::array + - wpi::util::array SwerveDrive4PoseEstimator3dBase: - qualname: frc::PoseEstimator3d + qualname: wpi::math::PoseEstimator3d params: - - wpi::array - - wpi::array + - wpi::util::array + - wpi::util::array SwerveDrive6PoseEstimator3dBase: - qualname: frc::PoseEstimator3d + qualname: wpi::math::PoseEstimator3d params: - - wpi::array - - wpi::array + - wpi::util::array + - wpi::util::array diff --git a/wpimath/src/main/python/semiwrap/controls/ProfiledPIDController.yml b/wpimath/src/main/python/semiwrap/controls/ProfiledPIDController.yml index 71cf286a0b..f814482a9d 100644 --- a/wpimath/src/main/python/semiwrap/controls/ProfiledPIDController.yml +++ b/wpimath/src/main/python/semiwrap/controls/ProfiledPIDController.yml @@ -5,16 +5,16 @@ functions: IncrementAndGetProfiledPIDControllerInstances: ignore: true classes: - frc::ProfiledPIDController: + wpi::math::ProfiledPIDController: force_type_casters: - - units::radians_per_second + - wpi::units::radians_per_second template_params: - Distance ignored_bases: - - wpi::SendableHelper> + - wpi::util::SendableHelper> typealias: - - typename frc::ProfiledPIDController::Velocity - - typename frc::ProfiledPIDController::Velocity_t + - typename wpi::math::ProfiledPIDController::Velocity + - typename wpi::math::ProfiledPIDController::Velocity_t methods: ProfiledPIDController: param_override: @@ -56,7 +56,7 @@ classes: Distance_t: Distance_t, State: Distance_t, Distance_t: - Distance_t, Distance_t, typename frc::TrapezoidProfile::Constraints: + Distance_t, Distance_t, typename wpi::math::TrapezoidProfile::Constraints: param_override: constraints: x_type: typename TrapezoidProfile::Constraints @@ -69,12 +69,12 @@ classes: templates: ProfiledPIDController: - qualname: frc::ProfiledPIDController + qualname: wpi::math::ProfiledPIDController params: - - units::dimensionless::scalar + - wpi::units::dimensionless::scalar # needed for HolonomicDriveController ProfiledPIDControllerRadians: - qualname: frc::ProfiledPIDController + qualname: wpi::math::ProfiledPIDController params: - - units::radian + - wpi::units::radian diff --git a/wpimath/src/main/python/semiwrap/controls/RectangularRegionConstraint.yml b/wpimath/src/main/python/semiwrap/controls/RectangularRegionConstraint.yml index 153423ae98..6aec5b8931 100644 --- a/wpimath/src/main/python/semiwrap/controls/RectangularRegionConstraint.yml +++ b/wpimath/src/main/python/semiwrap/controls/RectangularRegionConstraint.yml @@ -5,11 +5,11 @@ extra_includes: - PyTrajectoryConstraint.h classes: - frc::RectangularRegionConstraint: + wpi::math::RectangularRegionConstraint: template_params: - typename Constraint typealias: - - frc::TrajectoryConstraint::MinMax + - wpi::math::TrajectoryConstraint::MinMax methods: RectangularRegionConstraint: overloads: @@ -20,6 +20,6 @@ classes: templates: RectangularRegionConstraint: - qualname: frc::RectangularRegionConstraint + qualname: wpi::math::RectangularRegionConstraint params: - - frc::PyTrajectoryConstraint + - wpi::math::PyTrajectoryConstraint diff --git a/wpimath/src/main/python/semiwrap/controls/SimpleMotorFeedforward.yml b/wpimath/src/main/python/semiwrap/controls/SimpleMotorFeedforward.yml index 156613020b..2bab307c39 100644 --- a/wpimath/src/main/python/semiwrap/controls/SimpleMotorFeedforward.yml +++ b/wpimath/src/main/python/semiwrap/controls/SimpleMotorFeedforward.yml @@ -5,28 +5,28 @@ extra_includes: - wpi/units/dimensionless.hpp classes: - frc::SimpleMotorFeedforward: + wpi::math::SimpleMotorFeedforward: force_type_casters: - - units::meters_per_second - - units::meters_per_second_squared - - units::radians_per_second - - units::radians_per_second_squared + - wpi::units::meters_per_second + - wpi::units::meters_per_second_squared + - wpi::units::radians_per_second + - wpi::units::radians_per_second_squared typealias: - - typename frc::SimpleMotorFeedforward::Velocity - - typename frc::SimpleMotorFeedforward::Acceleration - - typename frc::SimpleMotorFeedforward::kv_unit - - typename frc::SimpleMotorFeedforward::ka_unit + - typename wpi::math::SimpleMotorFeedforward::Velocity + - typename wpi::math::SimpleMotorFeedforward::Acceleration + - typename wpi::math::SimpleMotorFeedforward::kv_unit + - typename wpi::math::SimpleMotorFeedforward::ka_unit template_params: - Distance methods: SimpleMotorFeedforward: overloads: '': - units::volt_t, units::unit_t, units::unit_t: + wpi::units::volt_t, wpi::units::unit_t, wpi::units::unit_t: Calculate: overloads: - units::unit_t [const]: - units::unit_t, units::unit_t [const]: + wpi::units::unit_t [const]: + wpi::units::unit_t, wpi::units::unit_t [const]: MaxAchievableVelocity: MinAchievableVelocity: MaxAchievableAcceleration: @@ -42,16 +42,16 @@ classes: templates: # Unfortunately this is broken because calculate requires an SI unit # SimpleMotorFeedforward: - # qualname: frc::SimpleMotorFeedforward + # qualname: wpi::math::SimpleMotorFeedforward # params: - # - units::dimensionless::scalar + # - wpi::units::dimensionless::scalar SimpleMotorFeedforwardMeters: - qualname: frc::SimpleMotorFeedforward + qualname: wpi::math::SimpleMotorFeedforward params: - - units::meter + - wpi::units::meter SimpleMotorFeedforwardRadians: - qualname: frc::SimpleMotorFeedforward + qualname: wpi::math::SimpleMotorFeedforward params: - - units::radian + - wpi::units::radian diff --git a/wpimath/src/main/python/semiwrap/controls/SimulatedAnnealing.yml b/wpimath/src/main/python/semiwrap/controls/SimulatedAnnealing.yml index b13e812cea..eac432a109 100644 --- a/wpimath/src/main/python/semiwrap/controls/SimulatedAnnealing.yml +++ b/wpimath/src/main/python/semiwrap/controls/SimulatedAnnealing.yml @@ -5,7 +5,7 @@ extra_includes: - gilsafe_object.h classes: - frc::SimulatedAnnealing: + wpi::math::SimulatedAnnealing: template_params: - State methods: @@ -14,6 +14,6 @@ classes: templates: SimulatedAnnealing: - qualname: frc::SimulatedAnnealing + qualname: wpi::math::SimulatedAnnealing params: - semiwrap::gilsafe_object diff --git a/wpimath/src/main/python/semiwrap/controls/SwerveDriveKinematicsConstraint.yml b/wpimath/src/main/python/semiwrap/controls/SwerveDriveKinematicsConstraint.yml index b9107a469b..4f53b57a28 100644 --- a/wpimath/src/main/python/semiwrap/controls/SwerveDriveKinematicsConstraint.yml +++ b/wpimath/src/main/python/semiwrap/controls/SwerveDriveKinematicsConstraint.yml @@ -2,37 +2,37 @@ defaults: subpackage: constraint classes: - frc::SwerveDriveKinematicsConstraint: + wpi::math::SwerveDriveKinematicsConstraint: template_params: - size_t NumModules typealias: - - frc::TrajectoryConstraint::MinMax + - wpi::math::TrajectoryConstraint::MinMax methods: SwerveDriveKinematicsConstraint: MaxVelocity: MinMaxAcceleration: template_inline_code: | cls_SwerveDriveKinematicsConstraint - .def_static("fromFps", [](const frc::SwerveDriveKinematics& kinematics, - units::feet_per_second_t maxSpeed) { - return std::make_shared>(kinematics, maxSpeed); + .def_static("fromFps", [](const wpi::math::SwerveDriveKinematics& kinematics, + wpi::units::feet_per_second_t maxSpeed) { + return std::make_shared>(kinematics, maxSpeed); }, py::arg("kinematics"), py::arg("maxSpeed")) ; templates: SwerveDrive2KinematicsConstraint: - qualname: frc::SwerveDriveKinematicsConstraint + qualname: wpi::math::SwerveDriveKinematicsConstraint params: - 2 SwerveDrive3KinematicsConstraint: - qualname: frc::SwerveDriveKinematicsConstraint + qualname: wpi::math::SwerveDriveKinematicsConstraint params: - 3 SwerveDrive4KinematicsConstraint: - qualname: frc::SwerveDriveKinematicsConstraint + qualname: wpi::math::SwerveDriveKinematicsConstraint params: - 4 SwerveDrive6KinematicsConstraint: - qualname: frc::SwerveDriveKinematicsConstraint + qualname: wpi::math::SwerveDriveKinematicsConstraint params: - 6 diff --git a/wpimath/src/main/python/semiwrap/controls/SwerveDrivePoseEstimator.yml b/wpimath/src/main/python/semiwrap/controls/SwerveDrivePoseEstimator.yml index 5f8d1cd8c7..774ead2191 100644 --- a/wpimath/src/main/python/semiwrap/controls/SwerveDrivePoseEstimator.yml +++ b/wpimath/src/main/python/semiwrap/controls/SwerveDrivePoseEstimator.yml @@ -5,7 +5,7 @@ extra_includes: - wpi/math/kinematics/SwerveModuleState.hpp classes: - frc::SwerveDrivePoseEstimator: + wpi::math::SwerveDrivePoseEstimator: force_no_trampoline: true doc: | This class wraps Swerve Drive Odometry to fuse latency-compensated @@ -30,24 +30,24 @@ classes: methods: SwerveDrivePoseEstimator: overloads: - SwerveDriveKinematics&, const Rotation2d&, const wpi::array&, const Pose2d&: - ? SwerveDriveKinematics&, const Rotation2d&, const wpi::array&, const Pose2d&, const wpi::array&, const wpi::array& + SwerveDriveKinematics&, const Rotation2d&, const wpi::util::array&, const Pose2d&: + ? SwerveDriveKinematics&, const Rotation2d&, const wpi::util::array&, const Pose2d&, const wpi::util::array&, const wpi::util::array& : templates: SwerveDrive2PoseEstimator: - qualname: frc::SwerveDrivePoseEstimator + qualname: wpi::math::SwerveDrivePoseEstimator params: - 2 SwerveDrive3PoseEstimator: - qualname: frc::SwerveDrivePoseEstimator + qualname: wpi::math::SwerveDrivePoseEstimator params: - 3 SwerveDrive4PoseEstimator: - qualname: frc::SwerveDrivePoseEstimator + qualname: wpi::math::SwerveDrivePoseEstimator params: - 4 SwerveDrive6PoseEstimator: - qualname: frc::SwerveDrivePoseEstimator + qualname: wpi::math::SwerveDrivePoseEstimator params: - 6 diff --git a/wpimath/src/main/python/semiwrap/controls/SwerveDrivePoseEstimator3d.yml b/wpimath/src/main/python/semiwrap/controls/SwerveDrivePoseEstimator3d.yml index 48115a785d..d7b0794719 100644 --- a/wpimath/src/main/python/semiwrap/controls/SwerveDrivePoseEstimator3d.yml +++ b/wpimath/src/main/python/semiwrap/controls/SwerveDrivePoseEstimator3d.yml @@ -5,32 +5,32 @@ extra_includes: - wpi/math/kinematics/SwerveModuleState.hpp classes: - frc::SwerveDrivePoseEstimator3d: + wpi::math::SwerveDrivePoseEstimator3d: force_no_trampoline: true template_params: - size_t NumModules methods: SwerveDrivePoseEstimator3d: overloads: - SwerveDriveKinematics&, const Rotation3d&, const wpi::array&, const Pose3d&: - ? SwerveDriveKinematics&, const Rotation3d&, const wpi::array&, const Pose3d&, const wpi::array&, const wpi::array& + SwerveDriveKinematics&, const Rotation3d&, const wpi::util::array&, const Pose3d&: + ? SwerveDriveKinematics&, const Rotation3d&, const wpi::util::array&, const Pose3d&, const wpi::util::array&, const wpi::util::array& : templates: SwerveDrive2PoseEstimator3d: - qualname: frc::SwerveDrivePoseEstimator3d + qualname: wpi::math::SwerveDrivePoseEstimator3d params: - 2 SwerveDrive3PoseEstimator3d: - qualname: frc::SwerveDrivePoseEstimator3d + qualname: wpi::math::SwerveDrivePoseEstimator3d params: - 3 SwerveDrive4PoseEstimator3d: - qualname: frc::SwerveDrivePoseEstimator3d + qualname: wpi::math::SwerveDrivePoseEstimator3d params: - 4 SwerveDrive6PoseEstimator3d: - qualname: frc::SwerveDrivePoseEstimator3d + qualname: wpi::math::SwerveDrivePoseEstimator3d params: - 6 diff --git a/wpimath/src/main/python/semiwrap/controls/Trajectory.yml b/wpimath/src/main/python/semiwrap/controls/Trajectory.yml index d806263936..30e2debe2f 100644 --- a/wpimath/src/main/python/semiwrap/controls/Trajectory.yml +++ b/wpimath/src/main/python/semiwrap/controls/Trajectory.yml @@ -10,9 +10,9 @@ functions: from_json: ignore: true classes: - frc::Trajectory: + wpi::math::Trajectory: force_type_casters: - - units::curvature_t + - wpi::units::curvature_t methods: Trajectory: overloads: @@ -26,7 +26,7 @@ classes: InitialPose: operator+: operator==: - frc::Trajectory::State: + wpi::math::Trajectory::State: force_no_default_constructor: true attributes: t: @@ -42,11 +42,11 @@ inline_code: | cls_State .def( py::init< - units::second_t, - units::meters_per_second_t, - units::meters_per_second_squared_t, + wpi::units::second_t, + wpi::units::meters_per_second_t, + wpi::units::meters_per_second_squared_t, Pose2d, - units::curvature_t + wpi::units::curvature_t >(), py::arg("t") = 0_s, py::arg("velocity") = 0_mps, @@ -54,13 +54,13 @@ inline_code: | py::arg("pose") = Pose2d(), py::arg("curvature") = 0.0 ) - .def_property_readonly("velocity_fps", [](frc::Trajectory::State * self) -> units::feet_per_second_t { + .def_property_readonly("velocity_fps", [](wpi::math::Trajectory::State * self) -> wpi::units::feet_per_second_t { return self->velocity; }) - .def_property_readonly("acceleration_fps", [](frc::Trajectory::State * self) -> units::feet_per_second_squared_t { + .def_property_readonly("acceleration_fps", [](wpi::math::Trajectory::State * self) -> wpi::units::feet_per_second_squared_t { return self->acceleration; }) - .def("__repr__", [](frc::Trajectory::State *self) { + .def("__repr__", [](wpi::math::Trajectory::State *self) { return "Trajectory.State(" "t=" + std::to_string(self->t()) + ", " "velocity=" + std::to_string(self->velocity()) + ", " @@ -68,4 +68,4 @@ inline_code: | "pose=" + rpy::toString(self->pose) + ", " "curvature=" + std::to_string(self->curvature()) + ")"; }) - .def_readwrite("curvature", &frc::Trajectory::State::curvature); + .def_readwrite("curvature", &wpi::math::Trajectory::State::curvature); diff --git a/wpimath/src/main/python/semiwrap/controls/TrajectoryConfig.yml b/wpimath/src/main/python/semiwrap/controls/TrajectoryConfig.yml index ca1d09d828..6622f8bf2d 100644 --- a/wpimath/src/main/python/semiwrap/controls/TrajectoryConfig.yml +++ b/wpimath/src/main/python/semiwrap/controls/TrajectoryConfig.yml @@ -5,7 +5,7 @@ extra_includes: - PyTrajectoryConstraint.h classes: - frc::TrajectoryConfig: + wpi::math::TrajectoryConfig: methods: TrajectoryConfig: SetStartVelocity: @@ -30,14 +30,14 @@ classes: inline_code: |- cls_TrajectoryConfig - .def_static("fromFps", [](units::feet_per_second_t maxVelocity, units::feet_per_second_squared_t maxAcceleration) { + .def_static("fromFps", [](wpi::units::feet_per_second_t maxVelocity, wpi::units::feet_per_second_squared_t maxAcceleration) { return std::make_shared(maxVelocity, maxAcceleration); }, py::arg("maxVelocity"), py::arg("maxAcceleration")) // TODO: robotpy-build bug - .def("setKinematics", static_cast&)>( - &frc::TrajectoryConfig::SetKinematics<2>), + .def("setKinematics", static_cast&)>( + &wpi::math::TrajectoryConfig::SetKinematics<2>), py::arg("kinematics"), release_gil(), py::doc( "Adds a swerve drive kinematics constraint to ensure that\n" "no wheel velocity of a swerve drive goes above the max velocity.\n" @@ -45,8 +45,8 @@ inline_code: |- ":param kinematics: The swerve drive kinematics.") ) - .def("setKinematics", static_cast&)>( - &frc::TrajectoryConfig::SetKinematics<3>), + .def("setKinematics", static_cast&)>( + &wpi::math::TrajectoryConfig::SetKinematics<3>), py::arg("kinematics"), release_gil(), py::doc( "Adds a swerve drive kinematics constraint to ensure that\n" "no wheel velocity of a swerve drive goes above the max velocity.\n" @@ -54,8 +54,8 @@ inline_code: |- ":param kinematics: The swerve drive kinematics.") ) - .def("setKinematics", static_cast&)>( - &frc::TrajectoryConfig::SetKinematics<4>), + .def("setKinematics", static_cast&)>( + &wpi::math::TrajectoryConfig::SetKinematics<4>), py::arg("kinematics"), release_gil(), py::doc( "Adds a swerve drive kinematics constraint to ensure that\n" "no wheel velocity of a swerve drive goes above the max velocity.\n" @@ -63,8 +63,8 @@ inline_code: |- ":param kinematics: The swerve drive kinematics.") ) - .def("setKinematics", static_cast&)>( - &frc::TrajectoryConfig::SetKinematics<6>), + .def("setKinematics", static_cast&)>( + &wpi::math::TrajectoryConfig::SetKinematics<6>), py::arg("kinematics"), release_gil(), py::doc( "Adds a swerve drive kinematics constraint to ensure that\n" "no wheel velocity of a swerve drive goes above the max velocity.\n" diff --git a/wpimath/src/main/python/semiwrap/controls/TrajectoryConstraint.yml b/wpimath/src/main/python/semiwrap/controls/TrajectoryConstraint.yml index 73af5eced4..e905595f80 100644 --- a/wpimath/src/main/python/semiwrap/controls/TrajectoryConstraint.yml +++ b/wpimath/src/main/python/semiwrap/controls/TrajectoryConstraint.yml @@ -2,26 +2,26 @@ defaults: subpackage: constraint classes: - frc::TrajectoryConstraint: + wpi::math::TrajectoryConstraint: force_type_casters: - - units::meters_per_second_squared + - wpi::units::meters_per_second_squared methods: TrajectoryConstraint: MaxVelocity: MinMaxAcceleration: - frc::TrajectoryConstraint::MinMax: + wpi::math::TrajectoryConstraint::MinMax: attributes: minAcceleration: maxAcceleration: inline_code: | .def(py::init([]( - units::meters_per_second_squared_t minAcceleration, - units::meters_per_second_squared_t maxAcceleration) { - return frc::TrajectoryConstraint::MinMax{minAcceleration, maxAcceleration}; + wpi::units::meters_per_second_squared_t minAcceleration, + wpi::units::meters_per_second_squared_t maxAcceleration) { + return wpi::math::TrajectoryConstraint::MinMax{minAcceleration, maxAcceleration}; }), py::arg("minAcceleration"), py::arg("maxAcceleration")) - .def("__len__", [](const frc::TrajectoryConstraint::MinMax& self) { return 2; }) - .def("__getitem__", [](const frc::TrajectoryConstraint::MinMax& self, int index) { + .def("__len__", [](const wpi::math::TrajectoryConstraint::MinMax& self) { return 2; }) + .def("__getitem__", [](const wpi::math::TrajectoryConstraint::MinMax& self, int index) { switch (index) { case 0: return self.minAcceleration; @@ -32,7 +32,7 @@ classes: } }) - .def("__repr__", [](const frc::TrajectoryConstraint::MinMax &self) { + .def("__repr__", [](const wpi::math::TrajectoryConstraint::MinMax &self) { return py::str("TrajectoryConstraint.MinMax(minAcceleration={}, maxAcceleration={})").format( self.minAcceleration, self.maxAcceleration); }) diff --git a/wpimath/src/main/python/semiwrap/controls/TrajectoryGenerator.yml b/wpimath/src/main/python/semiwrap/controls/TrajectoryGenerator.yml index 91ab346f3f..585af5ea69 100644 --- a/wpimath/src/main/python/semiwrap/controls/TrajectoryGenerator.yml +++ b/wpimath/src/main/python/semiwrap/controls/TrajectoryGenerator.yml @@ -6,10 +6,10 @@ extra_includes: - wpi/math/spline/QuinticHermiteSpline.hpp classes: - frc::TrajectoryGenerator: + wpi::math::TrajectoryGenerator: force_type_casters: - - units::unit_t - - units::curvature_t + - wpi::units::unit_t + - wpi::units::curvature_t methods: GenerateTrajectory: overloads: diff --git a/wpimath/src/main/python/semiwrap/controls/TrajectoryParameterizer.yml b/wpimath/src/main/python/semiwrap/controls/TrajectoryParameterizer.yml index 97f4b524c1..b102e527b1 100644 --- a/wpimath/src/main/python/semiwrap/controls/TrajectoryParameterizer.yml +++ b/wpimath/src/main/python/semiwrap/controls/TrajectoryParameterizer.yml @@ -2,9 +2,9 @@ defaults: subpackage: trajectory classes: - frc::TrajectoryParameterizer: + wpi::math::TrajectoryParameterizer: force_type_casters: - - units::unit_t - - units::curvature_t + - wpi::units::unit_t + - wpi::units::curvature_t methods: TimeParameterizeTrajectory: diff --git a/wpimath/src/main/python/semiwrap/controls/TrapezoidProfile.yml b/wpimath/src/main/python/semiwrap/controls/TrapezoidProfile.yml index 2122c9f1e7..8eea00a1a2 100644 --- a/wpimath/src/main/python/semiwrap/controls/TrapezoidProfile.yml +++ b/wpimath/src/main/python/semiwrap/controls/TrapezoidProfile.yml @@ -2,11 +2,11 @@ defaults: subpackage: trajectory classes: - frc::TrapezoidProfile: + wpi::math::TrapezoidProfile: force_type_casters: - - units::second_t - - units::radians_per_second - - units::radians_per_second_squared + - wpi::units::second_t + - wpi::units::radians_per_second + - wpi::units::radians_per_second_squared template_params: - Distance doc: | @@ -70,7 +70,7 @@ classes: "velocity=" + std::to_string(self.velocity()) + ")"; }); } - frc::TrapezoidProfile::Constraints: + wpi::math::TrapezoidProfile::Constraints: attributes: maxVelocity: maxAcceleration: @@ -85,7 +85,7 @@ classes: default: '0' maxAcceleration: default: '0' - frc::TrapezoidProfile::State: + wpi::math::TrapezoidProfile::State: force_no_default_constructor: true attributes: position: @@ -95,12 +95,12 @@ classes: cpp_code: py::self == State() templates: TrapezoidProfile: - qualname: frc::TrapezoidProfile + qualname: wpi::math::TrapezoidProfile params: - - units::dimensionless::scalar + - wpi::units::dimensionless::scalar # needed for HolonomicDriveController TrapezoidProfileRadians: - qualname: frc::TrapezoidProfile + qualname: wpi::math::TrapezoidProfile params: - - units::radian + - wpi::units::radian diff --git a/wpimath/src/main/python/semiwrap/controls/TravelingSalesman.yml b/wpimath/src/main/python/semiwrap/controls/TravelingSalesman.yml index ad40d99f46..de8af84b2b 100644 --- a/wpimath/src/main/python/semiwrap/controls/TravelingSalesman.yml +++ b/wpimath/src/main/python/semiwrap/controls/TravelingSalesman.yml @@ -2,7 +2,7 @@ defaults: subpackage: path classes: - frc::TravelingSalesman: + wpi::math::TravelingSalesman: methods: TravelingSalesman: overloads: @@ -10,6 +10,6 @@ classes: std::function: Solve: overloads: - const wpi::array&, int: + const wpi::util::array&, int: ignore: true std::span, int: diff --git a/wpimath/src/main/python/semiwrap/filter/Debouncer.yml b/wpimath/src/main/python/semiwrap/filter/Debouncer.yml index fd98a0a50f..205b1a9630 100644 --- a/wpimath/src/main/python/semiwrap/filter/Debouncer.yml +++ b/wpimath/src/main/python/semiwrap/filter/Debouncer.yml @@ -1,12 +1,12 @@ classes: - frc::Debouncer: + wpi::math::Debouncer: enums: DebounceType: methods: Debouncer: param_override: type: - default: frc::Debouncer::DebounceType::kRising + default: wpi::math::Debouncer::DebounceType::kRising Calculate: SetDebounceTime: GetDebounceTime: diff --git a/wpimath/src/main/python/semiwrap/filter/LinearFilter.yml b/wpimath/src/main/python/semiwrap/filter/LinearFilter.yml index 98b044af4f..11bdb90cad 100644 --- a/wpimath/src/main/python/semiwrap/filter/LinearFilter.yml +++ b/wpimath/src/main/python/semiwrap/filter/LinearFilter.yml @@ -1,5 +1,5 @@ classes: - frc::LinearFilter: + wpi::math::LinearFilter: template_params: - T methods: @@ -24,6 +24,6 @@ classes: templates: LinearFilter: - qualname: frc::LinearFilter + qualname: wpi::math::LinearFilter params: - double diff --git a/wpimath/src/main/python/semiwrap/filter/MedianFilter.yml b/wpimath/src/main/python/semiwrap/filter/MedianFilter.yml index 28f21609f4..13f3e1f2ad 100644 --- a/wpimath/src/main/python/semiwrap/filter/MedianFilter.yml +++ b/wpimath/src/main/python/semiwrap/filter/MedianFilter.yml @@ -1,5 +1,5 @@ classes: - frc::MedianFilter: + wpi::math::MedianFilter: template_params: - T methods: @@ -10,6 +10,6 @@ classes: templates: MedianFilter: - qualname: frc::MedianFilter + qualname: wpi::math::MedianFilter params: - double diff --git a/wpimath/src/main/python/semiwrap/filter/SlewRateLimiter.yml b/wpimath/src/main/python/semiwrap/filter/SlewRateLimiter.yml index f174c90762..401604fe76 100644 --- a/wpimath/src/main/python/semiwrap/filter/SlewRateLimiter.yml +++ b/wpimath/src/main/python/semiwrap/filter/SlewRateLimiter.yml @@ -1,10 +1,10 @@ classes: - frc::SlewRateLimiter: + wpi::math::SlewRateLimiter: template_params: - Unit typealias: - - Unit_t = units::unit_t - - Rate = units::compound_unit> + - Unit_t = wpi::units::unit_t + - Rate = wpi::units::compound_unit> methods: SlewRateLimiter: overloads: @@ -16,6 +16,6 @@ classes: templates: SlewRateLimiter: - qualname: frc::SlewRateLimiter + qualname: wpi::math::SlewRateLimiter params: - - units::dimensionless::scalar + - wpi::units::dimensionless::scalar diff --git a/wpimath/src/main/python/semiwrap/geometry/CoordinateAxis.yml b/wpimath/src/main/python/semiwrap/geometry/CoordinateAxis.yml index 98f03e5d72..5a5664254c 100644 --- a/wpimath/src/main/python/semiwrap/geometry/CoordinateAxis.yml +++ b/wpimath/src/main/python/semiwrap/geometry/CoordinateAxis.yml @@ -1,5 +1,5 @@ classes: - frc::CoordinateAxis: + wpi::math::CoordinateAxis: methods: CoordinateAxis: N: diff --git a/wpimath/src/main/python/semiwrap/geometry/CoordinateSystem.yml b/wpimath/src/main/python/semiwrap/geometry/CoordinateSystem.yml index b633e9e34b..5e251abd9b 100644 --- a/wpimath/src/main/python/semiwrap/geometry/CoordinateSystem.yml +++ b/wpimath/src/main/python/semiwrap/geometry/CoordinateSystem.yml @@ -1,5 +1,5 @@ classes: - frc::CoordinateSystem: + wpi::math::CoordinateSystem: methods: CoordinateSystem: NWU: diff --git a/wpimath/src/main/python/semiwrap/geometry/Ellipse2d.yml b/wpimath/src/main/python/semiwrap/geometry/Ellipse2d.yml index 1d9bb7ed76..bf717940f3 100644 --- a/wpimath/src/main/python/semiwrap/geometry/Ellipse2d.yml +++ b/wpimath/src/main/python/semiwrap/geometry/Ellipse2d.yml @@ -3,14 +3,14 @@ extra_includes: - wpystruct.h classes: - frc::Ellipse2d: + wpi::math::Ellipse2d: force_type_casters: - - units::foot_t - - units::meter_t + - wpi::units::foot_t + - wpi::units::meter_t methods: Ellipse2d: overloads: - const Pose2d&, units::meter_t, units::meter_t: + const Pose2d&, wpi::units::meter_t, wpi::units::meter_t: const Translation2d&, double: Center: Rotation: @@ -29,18 +29,18 @@ classes: inline_code: |- cls_Ellipse2d - .def_static("fromFeet", [](const Pose2d& center, units::foot_t xSemiAxis, units::foot_t ySemiAxis) { + .def_static("fromFeet", [](const Pose2d& center, wpi::units::foot_t xSemiAxis, wpi::units::foot_t ySemiAxis) { return std::make_unique(center, xSemiAxis, ySemiAxis); }, py::arg("center"), py::arg("xSemiAxis"), py::arg("ySemiAxis")) .def_property_readonly("xsemiaxis", &Ellipse2d::XSemiAxis) .def_property_readonly("ysemiaxis", &Ellipse2d::YSemiAxis) - .def_property_readonly("xsemiaxis_feet", [](Ellipse2d &self) -> units::foot_t { + .def_property_readonly("xsemiaxis_feet", [](Ellipse2d &self) -> wpi::units::foot_t { return self.XSemiAxis(); }) - .def_property_readonly("ysemiaxis_feet", [](Ellipse2d &self) -> units::foot_t { + .def_property_readonly("ysemiaxis_feet", [](Ellipse2d &self) -> wpi::units::foot_t { return self.YSemiAxis(); }) .def("__repr__", py::overload_cast(&rpy::toString)); - SetupWPyStruct(cls_Ellipse2d); + SetupWPyStruct(cls_Ellipse2d); diff --git a/wpimath/src/main/python/semiwrap/geometry/Pose2d.yml b/wpimath/src/main/python/semiwrap/geometry/Pose2d.yml index 6d294640e0..2cc1c8ecff 100644 --- a/wpimath/src/main/python/semiwrap/geometry/Pose2d.yml +++ b/wpimath/src/main/python/semiwrap/geometry/Pose2d.yml @@ -8,17 +8,17 @@ functions: from_json: ignore: true classes: - frc::Pose2d: + wpi::math::Pose2d: force_type_casters: - - units::foot_t - - units::meter_t - - units::radian_t + - wpi::units::foot_t + - wpi::units::meter_t + - wpi::units::radian_t methods: Pose2d: overloads: '': Translation2d, Rotation2d: - units::meter_t, units::meter_t, Rotation2d: + wpi::units::meter_t, wpi::units::meter_t, Rotation2d: const Eigen::Matrix3d&: rename: fromMatrix keepalive: [] @@ -44,23 +44,23 @@ classes: inline_code: | cls_Pose2d - .def_static("fromFeet", [](units::foot_t x, units::foot_t y, Rotation2d r) { + .def_static("fromFeet", [](wpi::units::foot_t x, wpi::units::foot_t y, Rotation2d r) { return std::make_unique(x, y, r); }, py::arg("x"), py::arg("y"), py::arg("r")) - .def_static("fromFeet", [](units::foot_t x, units::foot_t y, units::radian_t angle) { + .def_static("fromFeet", [](wpi::units::foot_t x, wpi::units::foot_t y, wpi::units::radian_t angle) { return std::make_unique(x, y, Rotation2d(angle)); }, py::arg("x"), py::arg("y"), py::arg("angle")) - .def(py::init([](units::meter_t x, units::meter_t y, units::radian_t angle) { + .def(py::init([](wpi::units::meter_t x, wpi::units::meter_t y, wpi::units::radian_t angle) { return std::make_unique(x, y, angle); }), py::arg("x"), py::arg("y"), py::arg("angle")) .def_property_readonly("x", &Pose2d::X) .def_property_readonly("y", &Pose2d::Y) - .def_property_readonly("x_feet", [](Pose2d * self) -> units::foot_t { + .def_property_readonly("x_feet", [](Pose2d * self) -> wpi::units::foot_t { return self->X(); }) - .def_property_readonly("y_feet", [](Pose2d * self) -> units::foot_t { + .def_property_readonly("y_feet", [](Pose2d * self) -> wpi::units::foot_t { return self->Y(); }) .def("__repr__", py::overload_cast(&rpy::toString)); - SetupWPyStruct(cls_Pose2d); + SetupWPyStruct(cls_Pose2d); diff --git a/wpimath/src/main/python/semiwrap/geometry/Pose3d.yml b/wpimath/src/main/python/semiwrap/geometry/Pose3d.yml index d55a93e8e4..93f6755bae 100644 --- a/wpimath/src/main/python/semiwrap/geometry/Pose3d.yml +++ b/wpimath/src/main/python/semiwrap/geometry/Pose3d.yml @@ -8,13 +8,13 @@ functions: from_json: ignore: true classes: - frc::Pose3d: + wpi::math::Pose3d: methods: Pose3d: overloads: '': Translation3d, Rotation3d: - units::meter_t, units::meter_t, units::meter_t, Rotation3d: + wpi::units::meter_t, wpi::units::meter_t, wpi::units::meter_t, Rotation3d: const Pose2d&: keepalive: [] const Eigen::Matrix4d&: @@ -44,21 +44,21 @@ classes: inline_code: | cls_Pose3d - .def_static("fromFeet", [](units::foot_t x, units::foot_t y, units::foot_t z, Rotation3d r) { + .def_static("fromFeet", [](wpi::units::foot_t x, wpi::units::foot_t y, wpi::units::foot_t z, Rotation3d r) { return std::make_unique(x, y, z, r); }, py::arg("x"), py::arg("y"), py::arg("z"), py::arg("r")) .def_property_readonly("x", &Pose3d::X) .def_property_readonly("y", &Pose3d::Y) .def_property_readonly("z", &Pose3d::Z) - .def_property_readonly("x_feet", [](const Pose3d * self) -> units::foot_t { + .def_property_readonly("x_feet", [](const Pose3d * self) -> wpi::units::foot_t { return self->X(); }) - .def_property_readonly("y_feet", [](const Pose3d * self) -> units::foot_t { + .def_property_readonly("y_feet", [](const Pose3d * self) -> wpi::units::foot_t { return self->Y(); }) - .def_property_readonly("z_feet", [](const Pose3d * self) -> units::foot_t { + .def_property_readonly("z_feet", [](const Pose3d * self) -> wpi::units::foot_t { return self->Z(); }) .def("__repr__", py::overload_cast(&rpy::toString)); - SetupWPyStruct(cls_Pose3d); + SetupWPyStruct(cls_Pose3d); diff --git a/wpimath/src/main/python/semiwrap/geometry/Quaternion.yml b/wpimath/src/main/python/semiwrap/geometry/Quaternion.yml index 74886f4d76..717305bc06 100644 --- a/wpimath/src/main/python/semiwrap/geometry/Quaternion.yml +++ b/wpimath/src/main/python/semiwrap/geometry/Quaternion.yml @@ -8,7 +8,7 @@ functions: from_json: ignore: true classes: - frc::Quaternion: + wpi::math::Quaternion: methods: Quaternion: overloads: @@ -47,4 +47,4 @@ inline_code: | cls_Quaternion .def("__repr__", py::overload_cast(&rpy::toString)); - SetupWPyStruct(cls_Quaternion); + SetupWPyStruct(cls_Quaternion); diff --git a/wpimath/src/main/python/semiwrap/geometry/Rectangle2d.yml b/wpimath/src/main/python/semiwrap/geometry/Rectangle2d.yml index bb8c895f77..f02d69100a 100644 --- a/wpimath/src/main/python/semiwrap/geometry/Rectangle2d.yml +++ b/wpimath/src/main/python/semiwrap/geometry/Rectangle2d.yml @@ -3,14 +3,14 @@ extra_includes: - wpystruct.h classes: - frc::Rectangle2d: + wpi::math::Rectangle2d: force_type_casters: - - units::foot_t - - units::meter_t + - wpi::units::foot_t + - wpi::units::meter_t methods: Rectangle2d: overloads: - const Pose2d&, units::meter_t, units::meter_t: + const Pose2d&, wpi::units::meter_t, wpi::units::meter_t: const Translation2d&, const Translation2d&: Center: Rotation: @@ -28,18 +28,18 @@ classes: inline_code: |- cls_Rectangle2d - .def_static("fromFeet", [](const Pose2d& center, units::foot_t xWidth, units::foot_t yWidth) { + .def_static("fromFeet", [](const Pose2d& center, wpi::units::foot_t xWidth, wpi::units::foot_t yWidth) { return std::make_unique(center, xWidth, yWidth); }, py::arg("center"), py::arg("xWidth"), py::arg("yWidth")) .def_property_readonly("xwidth", &Rectangle2d::XWidth) .def_property_readonly("ywidth", &Rectangle2d::YWidth) - .def_property_readonly("xwidth_feet", [](Rectangle2d &self) -> units::foot_t { + .def_property_readonly("xwidth_feet", [](Rectangle2d &self) -> wpi::units::foot_t { return self.XWidth(); }) - .def_property_readonly("ywidth_feet", [](Rectangle2d &self) -> units::foot_t { + .def_property_readonly("ywidth_feet", [](Rectangle2d &self) -> wpi::units::foot_t { return self.YWidth(); }) .def("__repr__", py::overload_cast(&rpy::toString)); - SetupWPyStruct(cls_Rectangle2d); + SetupWPyStruct(cls_Rectangle2d); diff --git a/wpimath/src/main/python/semiwrap/geometry/Rotation2d.yml b/wpimath/src/main/python/semiwrap/geometry/Rotation2d.yml index 162c1a77c6..51c9489d58 100644 --- a/wpimath/src/main/python/semiwrap/geometry/Rotation2d.yml +++ b/wpimath/src/main/python/semiwrap/geometry/Rotation2d.yml @@ -8,7 +8,7 @@ functions: from_json: ignore: true classes: - frc::Rotation2d: + wpi::math::Rotation2d: methods: Rotation2d: overloads: @@ -19,9 +19,9 @@ classes: :param value: The value of the angle in radians. param_override: value: - x_type: units::radian_t + x_type: wpi::units::radian_t template_impls: - - [units::radian_t] + - [wpi::units::radian_t] double, double: const Eigen::Matrix2d&: rename: fromMatrix @@ -44,12 +44,12 @@ classes: inline_code: | cls_Rotation2d - .def_static("fromDegrees", [](units::degree_t value) { + .def_static("fromDegrees", [](wpi::units::degree_t value) { return std::make_unique(value); }, py::arg("value")) - .def_static("fromRotations", [](units::turn_t value) { + .def_static("fromRotations", [](wpi::units::turn_t value) { return std::make_unique(value); }) .def("__repr__", py::overload_cast(&rpy::toString)); - SetupWPyStruct(cls_Rotation2d); + SetupWPyStruct(cls_Rotation2d); diff --git a/wpimath/src/main/python/semiwrap/geometry/Rotation3d.yml b/wpimath/src/main/python/semiwrap/geometry/Rotation3d.yml index 881a995710..8e2f469b1a 100644 --- a/wpimath/src/main/python/semiwrap/geometry/Rotation3d.yml +++ b/wpimath/src/main/python/semiwrap/geometry/Rotation3d.yml @@ -8,15 +8,15 @@ functions: from_json: ignore: true classes: - frc::Rotation3d: + wpi::math::Rotation3d: methods: Rotation3d: overloads: '': const Quaternion&: keepalive: [] - units::radian_t, units::radian_t, units::radian_t: - const Eigen::Vector3d&, units::radian_t: + wpi::units::radian_t, wpi::units::radian_t, wpi::units::radian_t: + const Eigen::Vector3d&, wpi::units::radian_t: keepalive: [] const Eigen::Vector3d&: keepalive: [] @@ -47,25 +47,25 @@ classes: inline_code: | cls_Rotation3d - .def_static("fromDegrees", [](units::degree_t roll, units::degree_t pitch, units::degree_t yaw) { + .def_static("fromDegrees", [](wpi::units::degree_t roll, wpi::units::degree_t pitch, wpi::units::degree_t yaw) { return std::make_unique(roll, pitch, yaw); }, py::arg("roll"), py::arg("pitch"), py::arg("yaw")) .def_property_readonly("x", &Rotation3d::X) .def_property_readonly("y", &Rotation3d::Y) .def_property_readonly("z", &Rotation3d::Z) .def_property_readonly("angle", &Rotation3d::Angle) - .def_property_readonly("x_degrees", [](const Rotation3d * self) -> units::degree_t { + .def_property_readonly("x_degrees", [](const Rotation3d * self) -> wpi::units::degree_t { return self->X(); }) - .def_property_readonly("y_degrees", [](const Rotation3d * self) -> units::degree_t { + .def_property_readonly("y_degrees", [](const Rotation3d * self) -> wpi::units::degree_t { return self->Y(); }) - .def_property_readonly("z_degrees", [](const Rotation3d * self) -> units::degree_t { + .def_property_readonly("z_degrees", [](const Rotation3d * self) -> wpi::units::degree_t { return self->Z(); }) - .def_property_readonly("angle_degrees", [](const Rotation3d * self) -> units::degree_t { + .def_property_readonly("angle_degrees", [](const Rotation3d * self) -> wpi::units::degree_t { return self->Angle(); }) .def("__repr__", py::overload_cast(&rpy::toString)); - SetupWPyStruct(cls_Rotation3d); + SetupWPyStruct(cls_Rotation3d); diff --git a/wpimath/src/main/python/semiwrap/geometry/Transform2d.yml b/wpimath/src/main/python/semiwrap/geometry/Transform2d.yml index 20f40e76cf..ce14e4833b 100644 --- a/wpimath/src/main/python/semiwrap/geometry/Transform2d.yml +++ b/wpimath/src/main/python/semiwrap/geometry/Transform2d.yml @@ -4,18 +4,18 @@ extra_includes: - wpystruct.h classes: - frc::Transform2d: + wpi::math::Transform2d: force_type_casters: - - units::foot_t - - units::meter_t - - units::radian_t + - wpi::units::foot_t + - wpi::units::meter_t + - wpi::units::radian_t methods: Transform2d: overloads: const Pose2d&, const Pose2d&: keepalive: [] Translation2d, Rotation2d: - units::meter_t, units::meter_t, Rotation2d: + wpi::units::meter_t, wpi::units::meter_t, Rotation2d: const Eigen::Matrix3d&: rename: fromMatrix keepalive: [] @@ -34,21 +34,21 @@ classes: inline_code: | cls_Transform2d - .def_static("fromFeet", [](units::foot_t x, units::foot_t y, units::radian_t angle){ + .def_static("fromFeet", [](wpi::units::foot_t x, wpi::units::foot_t y, wpi::units::radian_t angle){ return std::make_unique(Translation2d(x, y), Rotation2d(angle)); }, py::arg("x"), py::arg("y"), py::arg("angle")) - .def(py::init([](units::meter_t x, units::meter_t y, units::radian_t angle) { + .def(py::init([](wpi::units::meter_t x, wpi::units::meter_t y, wpi::units::radian_t angle) { return std::make_unique(Translation2d(x, y), Rotation2d(angle)); }), py::arg("x"), py::arg("y"), py::arg("angle")) .def_property_readonly("x", &Transform2d::X) .def_property_readonly("y", &Transform2d::Y) - .def_property_readonly("x_feet", [](Transform2d * self) -> units::foot_t { + .def_property_readonly("x_feet", [](Transform2d * self) -> wpi::units::foot_t { return self->X(); }) - .def_property_readonly("y_feet", [](Transform2d * self) -> units::foot_t { + .def_property_readonly("y_feet", [](Transform2d * self) -> wpi::units::foot_t { return self->Y(); }) .def("__repr__", py::overload_cast(&rpy::toString)); ; - SetupWPyStruct(cls_Transform2d); + SetupWPyStruct(cls_Transform2d); diff --git a/wpimath/src/main/python/semiwrap/geometry/Transform3d.yml b/wpimath/src/main/python/semiwrap/geometry/Transform3d.yml index 9a9bb27736..d45d6d78d0 100644 --- a/wpimath/src/main/python/semiwrap/geometry/Transform3d.yml +++ b/wpimath/src/main/python/semiwrap/geometry/Transform3d.yml @@ -3,19 +3,19 @@ extra_includes: - wpystruct.h classes: - frc::Transform3d: + wpi::math::Transform3d: methods: Transform3d: overloads: const Pose3d&, const Pose3d&: keepalive: [] Translation3d, Rotation3d: - units::meter_t, units::meter_t, units::meter_t, Rotation3d: + wpi::units::meter_t, wpi::units::meter_t, wpi::units::meter_t, Rotation3d: const Eigen::Matrix4d&: rename: fromMatrix keepalive: [] '': - const frc::Transform2d&: + const wpi::math::Transform2d&: keepalive: [] Translation: X: @@ -36,15 +36,15 @@ inline_code: | .def_property_readonly("x", &Transform3d::X) .def_property_readonly("y", &Transform3d::Y) .def_property_readonly("z", &Transform3d::Z) - .def_property_readonly("x_feet", [](const Transform3d * self) -> units::foot_t { + .def_property_readonly("x_feet", [](const Transform3d * self) -> wpi::units::foot_t { return self->X(); }) - .def_property_readonly("y_feet", [](const Transform3d * self) -> units::foot_t { + .def_property_readonly("y_feet", [](const Transform3d * self) -> wpi::units::foot_t { return self->Y(); }) - .def_property_readonly("z_feet", [](const Transform3d * self) -> units::foot_t { + .def_property_readonly("z_feet", [](const Transform3d * self) -> wpi::units::foot_t { return self->Z(); }) .def("__repr__", py::overload_cast(&rpy::toString)); - SetupWPyStruct(cls_Transform3d); + SetupWPyStruct(cls_Transform3d); diff --git a/wpimath/src/main/python/semiwrap/geometry/Translation2d.yml b/wpimath/src/main/python/semiwrap/geometry/Translation2d.yml index ed8d689dda..a00387586b 100644 --- a/wpimath/src/main/python/semiwrap/geometry/Translation2d.yml +++ b/wpimath/src/main/python/semiwrap/geometry/Translation2d.yml @@ -9,13 +9,13 @@ functions: from_json: ignore: true classes: - frc::Translation2d: + wpi::math::Translation2d: methods: Translation2d: overloads: '': - units::meter_t, units::meter_t: - units::meter_t, const Rotation2d&: + wpi::units::meter_t, wpi::units::meter_t: + wpi::units::meter_t, const Rotation2d&: const Eigen::Vector2d&: Distance: X: @@ -45,24 +45,24 @@ classes: inline_code: | cls_Translation2d - .def_static("fromFeet", [](units::foot_t x, units::foot_t y){ + .def_static("fromFeet", [](wpi::units::foot_t x, wpi::units::foot_t y){ return std::make_unique(x, y); }, py::arg("x"), py::arg("y")) - .def_static("fromFeet", [](units::foot_t distance, const Rotation2d &angle) { + .def_static("fromFeet", [](wpi::units::foot_t distance, const Rotation2d &angle) { return std::make_unique(distance, angle); }, py::arg("distance"), py::arg("angle")) .def_property_readonly("x", &Translation2d::X) .def_property_readonly("y", &Translation2d::Y) - .def_property_readonly("x_feet", [](Translation2d * self) -> units::foot_t { + .def_property_readonly("x_feet", [](Translation2d * self) -> wpi::units::foot_t { return self->X(); }) - .def_property_readonly("y_feet", [](Translation2d * self) -> units::foot_t { + .def_property_readonly("y_feet", [](Translation2d * self) -> wpi::units::foot_t { return self->Y(); }) - .def("distanceFeet", [](Translation2d * self, const Translation2d &other) -> units::foot_t { + .def("distanceFeet", [](Translation2d * self, const Translation2d &other) -> wpi::units::foot_t { return self->Distance(other); }) - .def("normFeet", [](Translation2d * self) -> units::foot_t { + .def("normFeet", [](Translation2d * self) -> wpi::units::foot_t { return self->Norm(); }) .def("__abs__", &Translation2d::Norm) @@ -79,4 +79,4 @@ inline_code: | }) .def("__repr__", py::overload_cast(&rpy::toString)); - SetupWPyStruct(cls_Translation2d); + SetupWPyStruct(cls_Translation2d); diff --git a/wpimath/src/main/python/semiwrap/geometry/Translation3d.yml b/wpimath/src/main/python/semiwrap/geometry/Translation3d.yml index e2cfdf53e2..6a1d8379e8 100644 --- a/wpimath/src/main/python/semiwrap/geometry/Translation3d.yml +++ b/wpimath/src/main/python/semiwrap/geometry/Translation3d.yml @@ -9,13 +9,13 @@ functions: from_json: ignore: true classes: - frc::Translation3d: + wpi::math::Translation3d: methods: Translation3d: overloads: '': - units::meter_t, units::meter_t, units::meter_t: - units::meter_t, const Rotation3d&: + wpi::units::meter_t, wpi::units::meter_t, wpi::units::meter_t: + wpi::units::meter_t, const Rotation3d&: const Eigen::Vector3d&: const Translation2d&: Distance: @@ -47,25 +47,25 @@ classes: Cross: inline_code: | cls_Translation3d - .def_static("fromFeet", [](units::foot_t x, units::foot_t y, units::foot_t z){ + .def_static("fromFeet", [](wpi::units::foot_t x, wpi::units::foot_t y, wpi::units::foot_t z){ return std::make_unique(x, y, z); }, py::arg("x"), py::arg("y"), py::arg("z")) .def_property_readonly("x", &Translation3d::X) .def_property_readonly("y", &Translation3d::Y) .def_property_readonly("z", &Translation3d::Z) - .def_property_readonly("x_feet", [](const Translation3d * self) -> units::foot_t { + .def_property_readonly("x_feet", [](const Translation3d * self) -> wpi::units::foot_t { return self->X(); }) - .def_property_readonly("y_feet", [](const Translation3d * self) -> units::foot_t { + .def_property_readonly("y_feet", [](const Translation3d * self) -> wpi::units::foot_t { return self->Y(); }) - .def_property_readonly("z_feet", [](const Translation3d * self) -> units::foot_t { + .def_property_readonly("z_feet", [](const Translation3d * self) -> wpi::units::foot_t { return self->Z(); }) - .def("distanceFeet", [](Translation3d * self, const Translation3d &other) -> units::foot_t { + .def("distanceFeet", [](Translation3d * self, const Translation3d &other) -> wpi::units::foot_t { return self->Distance(other); }) - .def("normFeet", [](const Translation3d * self) -> units::foot_t { + .def("normFeet", [](const Translation3d * self) -> wpi::units::foot_t { return self->Norm(); }) .def("__abs__", &Translation3d::Norm) @@ -84,4 +84,4 @@ inline_code: | }) .def("__repr__", py::overload_cast(&rpy::toString)); - SetupWPyStruct(cls_Translation3d); + SetupWPyStruct(cls_Translation3d); diff --git a/wpimath/src/main/python/semiwrap/geometry/Twist2d.yml b/wpimath/src/main/python/semiwrap/geometry/Twist2d.yml index 2963a01145..149815bbd0 100644 --- a/wpimath/src/main/python/semiwrap/geometry/Twist2d.yml +++ b/wpimath/src/main/python/semiwrap/geometry/Twist2d.yml @@ -2,7 +2,7 @@ extra_includes: - wpystruct.h classes: - frc::Twist2d: + wpi::math::Twist2d: force_no_default_constructor: true attributes: dx: @@ -16,33 +16,33 @@ classes: inline_code: | cls_Twist2d .def( - py::init(), + py::init(), py::arg("dx") = 0, py::arg("dy") = 0, py::arg("dtheta") = 0 ) - .def_static("fromFeet", [](units::foot_t dx, units::foot_t dy, units::radian_t dtheta){ + .def_static("fromFeet", [](wpi::units::foot_t dx, wpi::units::foot_t dy, wpi::units::radian_t dtheta){ return Twist2d{dx, dy, dtheta}; }, py::arg("dx") = 0, py::arg("dy") = 0, py::arg("dtheta") = 0) .def_property("dx_feet", - [](Twist2d * self) -> units::foot_t { + [](Twist2d * self) -> wpi::units::foot_t { return self->dx; }, - [](Twist2d * self, units::foot_t dx) { + [](Twist2d * self, wpi::units::foot_t dx) { self->dx = dx; } ) .def_property("dy_feet", - [](Twist2d * self) -> units::foot_t { + [](Twist2d * self) -> wpi::units::foot_t { return self->dy; }, - [](Twist2d * self, units::foot_t dy) { + [](Twist2d * self, wpi::units::foot_t dy) { self->dy = dy; } ) .def_property("dtheta_degrees", - [](Twist2d * self) -> units::degree_t { + [](Twist2d * self) -> wpi::units::degree_t { return self->dtheta; }, - [](Twist2d * self, units::degree_t dtheta) { + [](Twist2d * self, wpi::units::degree_t dtheta) { self->dtheta = dtheta; } ) @@ -53,4 +53,4 @@ inline_code: | }) ; - SetupWPyStruct(cls_Twist2d); + SetupWPyStruct(cls_Twist2d); diff --git a/wpimath/src/main/python/semiwrap/geometry/Twist3d.yml b/wpimath/src/main/python/semiwrap/geometry/Twist3d.yml index 8d8cd6af90..d2fece48e0 100644 --- a/wpimath/src/main/python/semiwrap/geometry/Twist3d.yml +++ b/wpimath/src/main/python/semiwrap/geometry/Twist3d.yml @@ -2,7 +2,7 @@ extra_includes: - wpystruct.h classes: - frc::Twist3d: + wpi::math::Twist3d: force_no_default_constructor: true attributes: dx: @@ -19,62 +19,62 @@ classes: inline_code: |- cls_Twist3d .def( - py::init(), + py::init(), py::arg("dx") = 0, py::arg("dy") = 0, py::arg("dz") = 0, py::arg("rx") = 0, py::arg("ry") = 0, py::arg("rz") = 0) .def_static("fromFeet", []( - units::foot_t dx, units::foot_t dy, units::foot_t dz, - units::radian_t rx, units::radian_t ry, units::radian_t rz){ + wpi::units::foot_t dx, wpi::units::foot_t dy, wpi::units::foot_t dz, + wpi::units::radian_t rx, wpi::units::radian_t ry, wpi::units::radian_t rz){ return Twist3d{dx, dy, dz, rx, ry, rz}; }, py::arg("dx") = 0, py::arg("dy") = 0, py::arg("dz") = 0, py::arg("rx") = 0, py::arg("ry") = 0, py::arg("rz") = 0) .def_property("dx_feet", - [](Twist3d * self) -> units::foot_t { + [](Twist3d * self) -> wpi::units::foot_t { return self->dx; }, - [](Twist3d * self, units::foot_t dx) { + [](Twist3d * self, wpi::units::foot_t dx) { self->dx = dx; } ) .def_property("dy_feet", - [](Twist3d * self) -> units::foot_t { + [](Twist3d * self) -> wpi::units::foot_t { return self->dy; }, - [](Twist3d * self, units::foot_t dy) { + [](Twist3d * self, wpi::units::foot_t dy) { self->dy = dy; } ) .def_property("dz_feet", - [](Twist3d * self) -> units::foot_t { + [](Twist3d * self) -> wpi::units::foot_t { return self->dz; }, - [](Twist3d * self, units::foot_t dz) { + [](Twist3d * self, wpi::units::foot_t dz) { self->dz = dz; } ) .def_property("rx_degrees", - [](Twist3d * self) -> units::degree_t { + [](Twist3d * self) -> wpi::units::degree_t { return self->rx; }, - [](Twist3d * self, units::degree_t rx) { + [](Twist3d * self, wpi::units::degree_t rx) { self->rx = rx; } ) .def_property("ry_degrees", - [](Twist3d * self) -> units::degree_t { + [](Twist3d * self) -> wpi::units::degree_t { return self->ry; }, - [](Twist3d * self, units::degree_t ry) { + [](Twist3d * self, wpi::units::degree_t ry) { self->ry = ry; } ) .def_property("rz_degrees", - [](Twist3d * self) -> units::degree_t { + [](Twist3d * self) -> wpi::units::degree_t { return self->rz; }, - [](Twist3d * self, units::degree_t rz) { + [](Twist3d * self, wpi::units::degree_t rz) { self->rz = rz; } ) @@ -88,4 +88,4 @@ inline_code: |- }) ; - SetupWPyStruct(cls_Twist3d); + SetupWPyStruct(cls_Twist3d); diff --git a/wpimath/src/main/python/semiwrap/interpolation/TimeInterpolatableBuffer.yml b/wpimath/src/main/python/semiwrap/interpolation/TimeInterpolatableBuffer.yml index 7141466337..f02c04c0d5 100644 --- a/wpimath/src/main/python/semiwrap/interpolation/TimeInterpolatableBuffer.yml +++ b/wpimath/src/main/python/semiwrap/interpolation/TimeInterpolatableBuffer.yml @@ -2,14 +2,14 @@ extra_includes: - "wpi/math/geometry/Pose3d.hpp" classes: - frc::TimeInterpolatableBuffer: + wpi::math::TimeInterpolatableBuffer: template_params: - T methods: TimeInterpolatableBuffer: overloads: - units::second_t, std::function: - units::second_t: + wpi::units::second_t, std::function: + wpi::units::second_t: AddSample: Clear: Sample: @@ -21,30 +21,30 @@ classes: templates: TimeInterpolatablePose2dBuffer: - qualname: frc::TimeInterpolatableBuffer + qualname: wpi::math::TimeInterpolatableBuffer params: - - frc::Pose2d + - wpi::math::Pose2d TimeInterpolatablePose3dBuffer: - qualname: frc::TimeInterpolatableBuffer + qualname: wpi::math::TimeInterpolatableBuffer params: - - frc::Pose3d + - wpi::math::Pose3d TimeInterpolatableRotation2dBuffer: - qualname: frc::TimeInterpolatableBuffer + qualname: wpi::math::TimeInterpolatableBuffer params: - - frc::Rotation2d + - wpi::math::Rotation2d TimeInterpolatableRotation3dBuffer: - qualname: frc::TimeInterpolatableBuffer + qualname: wpi::math::TimeInterpolatableBuffer params: - - frc::Rotation3d + - wpi::math::Rotation3d TimeInterpolatableTranslation2dBuffer: - qualname: frc::TimeInterpolatableBuffer + qualname: wpi::math::TimeInterpolatableBuffer params: - - frc::Translation2d + - wpi::math::Translation2d TimeInterpolatableTranslation3dBuffer: - qualname: frc::TimeInterpolatableBuffer + qualname: wpi::math::TimeInterpolatableBuffer params: - - frc::Translation3d + - wpi::math::Translation3d TimeInterpolatableFloatBuffer: - qualname: frc::TimeInterpolatableBuffer + qualname: wpi::math::TimeInterpolatableBuffer params: - double diff --git a/wpimath/src/main/python/semiwrap/kinematics/ChassisSpeeds.yml b/wpimath/src/main/python/semiwrap/kinematics/ChassisSpeeds.yml index d673289965..beef1c6445 100644 --- a/wpimath/src/main/python/semiwrap/kinematics/ChassisSpeeds.yml +++ b/wpimath/src/main/python/semiwrap/kinematics/ChassisSpeeds.yml @@ -2,7 +2,7 @@ extra_includes: - wpystruct.h classes: - frc::ChassisSpeeds: + wpi::math::ChassisSpeeds: force_no_default_constructor: true attributes: vx: @@ -12,8 +12,8 @@ classes: ToTwist2d: Discretize: overloads: - units::meters_per_second_t, units::meters_per_second_t, units::radians_per_second_t, units::second_t: - const ChassisSpeeds&, units::second_t: + wpi::units::meters_per_second_t, wpi::units::meters_per_second_t, wpi::units::radians_per_second_t, wpi::units::second_t: + const ChassisSpeeds&, wpi::units::second_t: operator+: operator-: overloads: @@ -29,35 +29,35 @@ inline_code: | cls_ChassisSpeeds .def( py::init< - units::meters_per_second_t, units::meters_per_second_t, - units::radians_per_second_t + wpi::units::meters_per_second_t, wpi::units::meters_per_second_t, + wpi::units::radians_per_second_t >(), py::arg("vx") = 0, py::arg("vy") = 0, py::arg("omega") = 0 ) - .def_static("fromFeet", [](units::feet_per_second_t vx, units::feet_per_second_t vy, units::radians_per_second_t omega){ + .def_static("fromFeet", [](wpi::units::feet_per_second_t vx, wpi::units::feet_per_second_t vy, wpi::units::radians_per_second_t omega){ return ChassisSpeeds{vx, vy, omega}; }, py::arg("vx") = 0, py::arg("vy") = 0, py::arg("omega") = 0) .def_property("vx_fps", - [](ChassisSpeeds * self) -> units::feet_per_second_t { + [](ChassisSpeeds * self) -> wpi::units::feet_per_second_t { return self->vx; }, - [](ChassisSpeeds * self, units::feet_per_second_t vx) { + [](ChassisSpeeds * self, wpi::units::feet_per_second_t vx) { self->vx = vx; } ) .def_property("vy_fps", - [](ChassisSpeeds * self) -> units::feet_per_second_t { + [](ChassisSpeeds * self) -> wpi::units::feet_per_second_t { return self->vy; }, - [](ChassisSpeeds * self, units::feet_per_second_t vy) { + [](ChassisSpeeds * self, wpi::units::feet_per_second_t vy) { self->vy = vy; } ) .def_property("omega_dps", - [](ChassisSpeeds * self) -> units::degrees_per_second_t { + [](ChassisSpeeds * self) -> wpi::units::degrees_per_second_t { return self->omega; }, - [](ChassisSpeeds * self, units::degrees_per_second_t omega) { + [](ChassisSpeeds * self, wpi::units::degrees_per_second_t omega) { self->omega = omega; } ) @@ -81,4 +81,4 @@ inline_code: | }) ; - SetupWPyStruct(cls_ChassisSpeeds); + SetupWPyStruct(cls_ChassisSpeeds); diff --git a/wpimath/src/main/python/semiwrap/kinematics/DifferentialDriveKinematics.yml b/wpimath/src/main/python/semiwrap/kinematics/DifferentialDriveKinematics.yml index 24b8c460d2..04b2ee336b 100644 --- a/wpimath/src/main/python/semiwrap/kinematics/DifferentialDriveKinematics.yml +++ b/wpimath/src/main/python/semiwrap/kinematics/DifferentialDriveKinematics.yml @@ -2,7 +2,7 @@ extra_includes: - wpystruct.h classes: - frc::DifferentialDriveKinematics: + wpi::math::DifferentialDriveKinematics: attributes: trackwidth: methods: @@ -11,9 +11,9 @@ classes: ToWheelSpeeds: ToTwist2d: overloads: - const units::meter_t, const units::meter_t [const]: + const wpi::units::meter_t, const wpi::units::meter_t [const]: const DifferentialDriveWheelPositions&, const DifferentialDriveWheelPositions& [const]: Interpolate: inline_code: | - SetupWPyStruct(cls_DifferentialDriveKinematics); + SetupWPyStruct(cls_DifferentialDriveKinematics); diff --git a/wpimath/src/main/python/semiwrap/kinematics/DifferentialDriveOdometry.yml b/wpimath/src/main/python/semiwrap/kinematics/DifferentialDriveOdometry.yml index 687e53a0aa..55f1649385 100644 --- a/wpimath/src/main/python/semiwrap/kinematics/DifferentialDriveOdometry.yml +++ b/wpimath/src/main/python/semiwrap/kinematics/DifferentialDriveOdometry.yml @@ -1,5 +1,5 @@ classes: - frc::DifferentialDriveOdometry: + wpi::math::DifferentialDriveOdometry: force_no_trampoline: true methods: DifferentialDriveOdometry: diff --git a/wpimath/src/main/python/semiwrap/kinematics/DifferentialDriveOdometry3d.yml b/wpimath/src/main/python/semiwrap/kinematics/DifferentialDriveOdometry3d.yml index 9048eb7f16..485f23f7cf 100644 --- a/wpimath/src/main/python/semiwrap/kinematics/DifferentialDriveOdometry3d.yml +++ b/wpimath/src/main/python/semiwrap/kinematics/DifferentialDriveOdometry3d.yml @@ -1,5 +1,5 @@ classes: - frc::DifferentialDriveOdometry3d: + wpi::math::DifferentialDriveOdometry3d: force_no_trampoline: true methods: DifferentialDriveOdometry3d: diff --git a/wpimath/src/main/python/semiwrap/kinematics/DifferentialDriveWheelPositions.yml b/wpimath/src/main/python/semiwrap/kinematics/DifferentialDriveWheelPositions.yml index a50e54f79b..55c6f38673 100644 --- a/wpimath/src/main/python/semiwrap/kinematics/DifferentialDriveWheelPositions.yml +++ b/wpimath/src/main/python/semiwrap/kinematics/DifferentialDriveWheelPositions.yml @@ -1,5 +1,5 @@ classes: - frc::DifferentialDriveWheelPositions: + wpi::math::DifferentialDriveWheelPositions: attributes: left: right: diff --git a/wpimath/src/main/python/semiwrap/kinematics/DifferentialDriveWheelSpeeds.yml b/wpimath/src/main/python/semiwrap/kinematics/DifferentialDriveWheelSpeeds.yml index 7b4040c477..cfb96dd9ba 100644 --- a/wpimath/src/main/python/semiwrap/kinematics/DifferentialDriveWheelSpeeds.yml +++ b/wpimath/src/main/python/semiwrap/kinematics/DifferentialDriveWheelSpeeds.yml @@ -2,7 +2,7 @@ extra_includes: - wpystruct.h classes: - frc::DifferentialDriveWheelSpeeds: + wpi::math::DifferentialDriveWheelSpeeds: force_no_default_constructor: true attributes: left: @@ -21,25 +21,25 @@ classes: inline_code: | cls_DifferentialDriveWheelSpeeds .def( - py::init(), + py::init(), py::arg("left") = 0, py::arg("right") = 0 ) - .def_static("fromFeet", [](units::feet_per_second_t left, units::feet_per_second_t right){ + .def_static("fromFeet", [](wpi::units::feet_per_second_t left, wpi::units::feet_per_second_t right){ return DifferentialDriveWheelSpeeds{left, right}; }, py::arg("left"), py::arg("right")) .def_property("left_fps", - [](DifferentialDriveWheelSpeeds * self) -> units::feet_per_second_t { + [](DifferentialDriveWheelSpeeds * self) -> wpi::units::feet_per_second_t { return self->left; }, - [](DifferentialDriveWheelSpeeds * self, units::feet_per_second_t left) { + [](DifferentialDriveWheelSpeeds * self, wpi::units::feet_per_second_t left) { self->left = left; } ) .def_property("right_fps", - [](DifferentialDriveWheelSpeeds * self) -> units::feet_per_second_t { + [](DifferentialDriveWheelSpeeds * self) -> wpi::units::feet_per_second_t { return self->right; }, - [](DifferentialDriveWheelSpeeds * self, units::feet_per_second_t right) { + [](DifferentialDriveWheelSpeeds * self, wpi::units::feet_per_second_t right) { self->right = right; } ) @@ -49,5 +49,5 @@ inline_code: | }) ; - SetupWPyStruct(cls_DifferentialDriveWheelSpeeds); + SetupWPyStruct(cls_DifferentialDriveWheelSpeeds); diff --git a/wpimath/src/main/python/semiwrap/kinematics/Kinematics.yml b/wpimath/src/main/python/semiwrap/kinematics/Kinematics.yml index 77da465c25..57b87c12e2 100644 --- a/wpimath/src/main/python/semiwrap/kinematics/Kinematics.yml +++ b/wpimath/src/main/python/semiwrap/kinematics/Kinematics.yml @@ -7,9 +7,9 @@ extra_includes: classes: - frc::Kinematics: + wpi::math::Kinematics: force_type_casters: - - wpi::array + - wpi::util::array template_params: - WheelSpeeds - WheelPositions @@ -22,32 +22,32 @@ classes: templates: DifferentialDriveKinematicsBase: - qualname: frc::Kinematics + qualname: wpi::math::Kinematics params: - - frc::DifferentialDriveWheelSpeeds - - frc::DifferentialDriveWheelPositions + - wpi::math::DifferentialDriveWheelSpeeds + - wpi::math::DifferentialDriveWheelPositions MecanumDriveKinematicsBase: - qualname: frc::Kinematics + qualname: wpi::math::Kinematics params: - - frc::MecanumDriveWheelSpeeds - - frc::MecanumDriveWheelPositions + - wpi::math::MecanumDriveWheelSpeeds + - wpi::math::MecanumDriveWheelPositions SwerveDrive2KinematicsBase: - qualname: frc::Kinematics + qualname: wpi::math::Kinematics params: - - wpi::array - - wpi::array + - wpi::util::array + - wpi::util::array SwerveDrive3KinematicsBase: - qualname: frc::Kinematics + qualname: wpi::math::Kinematics params: - - wpi::array - - wpi::array + - wpi::util::array + - wpi::util::array SwerveDrive4KinematicsBase: - qualname: frc::Kinematics + qualname: wpi::math::Kinematics params: - - wpi::array - - wpi::array + - wpi::util::array + - wpi::util::array SwerveDrive6KinematicsBase: - qualname: frc::Kinematics + qualname: wpi::math::Kinematics params: - - wpi::array - - wpi::array + - wpi::util::array + - wpi::util::array diff --git a/wpimath/src/main/python/semiwrap/kinematics/MecanumDriveKinematics.yml b/wpimath/src/main/python/semiwrap/kinematics/MecanumDriveKinematics.yml index 17fcfe2532..b97bf4ee4e 100644 --- a/wpimath/src/main/python/semiwrap/kinematics/MecanumDriveKinematics.yml +++ b/wpimath/src/main/python/semiwrap/kinematics/MecanumDriveKinematics.yml @@ -2,7 +2,7 @@ extra_includes: - wpystruct.h classes: - frc::MecanumDriveKinematics: + wpi::math::MecanumDriveKinematics: methods: MecanumDriveKinematics: ToWheelSpeeds: @@ -47,4 +47,4 @@ classes: Interpolate: inline_code: | - SetupWPyStruct(cls_MecanumDriveKinematics); + SetupWPyStruct(cls_MecanumDriveKinematics); diff --git a/wpimath/src/main/python/semiwrap/kinematics/MecanumDriveOdometry.yml b/wpimath/src/main/python/semiwrap/kinematics/MecanumDriveOdometry.yml index 929e3e2570..6f56a97a1f 100644 --- a/wpimath/src/main/python/semiwrap/kinematics/MecanumDriveOdometry.yml +++ b/wpimath/src/main/python/semiwrap/kinematics/MecanumDriveOdometry.yml @@ -1,5 +1,5 @@ classes: - frc::MecanumDriveOdometry: + wpi::math::MecanumDriveOdometry: force_no_trampoline: true methods: MecanumDriveOdometry: diff --git a/wpimath/src/main/python/semiwrap/kinematics/MecanumDriveOdometry3d.yml b/wpimath/src/main/python/semiwrap/kinematics/MecanumDriveOdometry3d.yml index a53f0d75eb..9ac6114049 100644 --- a/wpimath/src/main/python/semiwrap/kinematics/MecanumDriveOdometry3d.yml +++ b/wpimath/src/main/python/semiwrap/kinematics/MecanumDriveOdometry3d.yml @@ -1,5 +1,5 @@ classes: - frc::MecanumDriveOdometry3d: + wpi::math::MecanumDriveOdometry3d: force_no_trampoline: true methods: MecanumDriveOdometry3d: diff --git a/wpimath/src/main/python/semiwrap/kinematics/MecanumDriveWheelPositions.yml b/wpimath/src/main/python/semiwrap/kinematics/MecanumDriveWheelPositions.yml index 82be5f55ef..5eafa4fc0f 100644 --- a/wpimath/src/main/python/semiwrap/kinematics/MecanumDriveWheelPositions.yml +++ b/wpimath/src/main/python/semiwrap/kinematics/MecanumDriveWheelPositions.yml @@ -1,5 +1,5 @@ classes: - frc::MecanumDriveWheelPositions: + wpi::math::MecanumDriveWheelPositions: attributes: frontLeft: frontRight: diff --git a/wpimath/src/main/python/semiwrap/kinematics/MecanumDriveWheelSpeeds.yml b/wpimath/src/main/python/semiwrap/kinematics/MecanumDriveWheelSpeeds.yml index fff03df0d8..1e90ba3400 100644 --- a/wpimath/src/main/python/semiwrap/kinematics/MecanumDriveWheelSpeeds.yml +++ b/wpimath/src/main/python/semiwrap/kinematics/MecanumDriveWheelSpeeds.yml @@ -2,7 +2,7 @@ extra_includes: - wpystruct.h classes: - frc::MecanumDriveWheelSpeeds: + wpi::math::MecanumDriveWheelSpeeds: force_no_default_constructor: true attributes: frontLeft: @@ -23,50 +23,50 @@ inline_code: | cls_MecanumDriveWheelSpeeds .def( py::init< - units::meters_per_second_t, units::meters_per_second_t, - units::meters_per_second_t, units::meters_per_second_t + wpi::units::meters_per_second_t, wpi::units::meters_per_second_t, + wpi::units::meters_per_second_t, wpi::units::meters_per_second_t >(), py::arg("frontLeft") = 0, py::arg("frontRight") = 0, py::arg("rearLeft") = 0, py::arg("rearRight") = 0 ) .def_static("fromFeet", []( - units::feet_per_second_t frontLeft, - units::feet_per_second_t frontRight, - units::feet_per_second_t rearLeft, - units::feet_per_second_t rearRight + wpi::units::feet_per_second_t frontLeft, + wpi::units::feet_per_second_t frontRight, + wpi::units::feet_per_second_t rearLeft, + wpi::units::feet_per_second_t rearRight ){ return MecanumDriveWheelSpeeds{frontLeft, frontRight, rearLeft, rearRight}; }, py::arg("frontLeft"), py::arg("frontRight"), py::arg("rearLeft"), py::arg("rearRight")) .def_property("frontLeft_fps", - [](MecanumDriveWheelSpeeds * self) -> units::feet_per_second_t { + [](MecanumDriveWheelSpeeds * self) -> wpi::units::feet_per_second_t { return self->frontLeft; }, - [](MecanumDriveWheelSpeeds * self, units::feet_per_second_t fps) { + [](MecanumDriveWheelSpeeds * self, wpi::units::feet_per_second_t fps) { self->frontLeft = fps; } ) .def_property("frontRight_fps", - [](MecanumDriveWheelSpeeds * self) -> units::feet_per_second_t { + [](MecanumDriveWheelSpeeds * self) -> wpi::units::feet_per_second_t { return self->frontRight; }, - [](MecanumDriveWheelSpeeds * self, units::feet_per_second_t fps) { + [](MecanumDriveWheelSpeeds * self, wpi::units::feet_per_second_t fps) { self->frontRight = fps; } ) .def_property("rearLeft_fps", - [](MecanumDriveWheelSpeeds * self) -> units::feet_per_second_t { + [](MecanumDriveWheelSpeeds * self) -> wpi::units::feet_per_second_t { return self->rearLeft; }, - [](MecanumDriveWheelSpeeds * self, units::feet_per_second_t fps) { + [](MecanumDriveWheelSpeeds * self, wpi::units::feet_per_second_t fps) { self->rearLeft = fps; } ) .def_property("rearRight_fps", - [](MecanumDriveWheelSpeeds * self) -> units::feet_per_second_t { + [](MecanumDriveWheelSpeeds * self) -> wpi::units::feet_per_second_t { return self->rearRight; }, - [](MecanumDriveWheelSpeeds * self, units::feet_per_second_t fps) { + [](MecanumDriveWheelSpeeds * self, wpi::units::feet_per_second_t fps) { self->rearRight = fps; } ) @@ -78,4 +78,4 @@ inline_code: | }) ; - SetupWPyStruct(cls_MecanumDriveWheelSpeeds); + SetupWPyStruct(cls_MecanumDriveWheelSpeeds); diff --git a/wpimath/src/main/python/semiwrap/kinematics/Odometry.yml b/wpimath/src/main/python/semiwrap/kinematics/Odometry.yml index 84ff9fa136..d144ac62ad 100644 --- a/wpimath/src/main/python/semiwrap/kinematics/Odometry.yml +++ b/wpimath/src/main/python/semiwrap/kinematics/Odometry.yml @@ -6,7 +6,7 @@ extra_includes: - wpi/math/kinematics/SwerveDriveKinematics.hpp classes: - frc::Odometry: + wpi::math::Odometry: template_params: - WheelSpeeds - WheelPositions @@ -21,32 +21,32 @@ classes: templates: DifferentialDriveOdometryBase: - qualname: frc::Odometry + qualname: wpi::math::Odometry params: - - frc::DifferentialDriveWheelSpeeds - - frc::DifferentialDriveWheelPositions + - wpi::math::DifferentialDriveWheelSpeeds + - wpi::math::DifferentialDriveWheelPositions MecanumDriveOdometryBase: - qualname: frc::Odometry + qualname: wpi::math::Odometry params: - - frc::MecanumDriveWheelSpeeds - - frc::MecanumDriveWheelPositions + - wpi::math::MecanumDriveWheelSpeeds + - wpi::math::MecanumDriveWheelPositions SwerveDrive2OdometryBase: - qualname: frc::Odometry + qualname: wpi::math::Odometry params: - - wpi::array - - wpi::array + - wpi::util::array + - wpi::util::array SwerveDrive3OdometryBase: - qualname: frc::Odometry + qualname: wpi::math::Odometry params: - - wpi::array - - wpi::array + - wpi::util::array + - wpi::util::array SwerveDrive4OdometryBase: - qualname: frc::Odometry + qualname: wpi::math::Odometry params: - - wpi::array - - wpi::array + - wpi::util::array + - wpi::util::array SwerveDrive6OdometryBase: - qualname: frc::Odometry + qualname: wpi::math::Odometry params: - - wpi::array - - wpi::array + - wpi::util::array + - wpi::util::array diff --git a/wpimath/src/main/python/semiwrap/kinematics/Odometry3d.yml b/wpimath/src/main/python/semiwrap/kinematics/Odometry3d.yml index f68f512703..6b1657f5f4 100644 --- a/wpimath/src/main/python/semiwrap/kinematics/Odometry3d.yml +++ b/wpimath/src/main/python/semiwrap/kinematics/Odometry3d.yml @@ -6,7 +6,7 @@ extra_includes: - wpi/math/kinematics/SwerveDriveKinematics.hpp classes: - frc::Odometry3d: + wpi::math::Odometry3d: template_params: - WheelSpeeds - WheelPositions @@ -22,32 +22,32 @@ classes: templates: DifferentialDriveOdometry3dBase: - qualname: frc::Odometry3d + qualname: wpi::math::Odometry3d params: - - frc::DifferentialDriveWheelSpeeds - - frc::DifferentialDriveWheelPositions + - wpi::math::DifferentialDriveWheelSpeeds + - wpi::math::DifferentialDriveWheelPositions MecanumDriveOdometry3dBase: - qualname: frc::Odometry3d + qualname: wpi::math::Odometry3d params: - - frc::MecanumDriveWheelSpeeds - - frc::MecanumDriveWheelPositions + - wpi::math::MecanumDriveWheelSpeeds + - wpi::math::MecanumDriveWheelPositions SwerveDrive2Odometry3dBase: - qualname: frc::Odometry3d + qualname: wpi::math::Odometry3d params: - - wpi::array - - wpi::array + - wpi::util::array + - wpi::util::array SwerveDrive3Odometry3dBase: - qualname: frc::Odometry3d + qualname: wpi::math::Odometry3d params: - - wpi::array - - wpi::array + - wpi::util::array + - wpi::util::array SwerveDrive4Odometry3dBase: - qualname: frc::Odometry3d + qualname: wpi::math::Odometry3d params: - - wpi::array - - wpi::array + - wpi::util::array + - wpi::util::array SwerveDrive6Odometry3dBase: - qualname: frc::Odometry3d + qualname: wpi::math::Odometry3d params: - - wpi::array - - wpi::array + - wpi::util::array + - wpi::util::array diff --git a/wpimath/src/main/python/semiwrap/kinematics/SwerveDriveKinematics.yml b/wpimath/src/main/python/semiwrap/kinematics/SwerveDriveKinematics.yml index aa14d190f0..a4bd38be46 100644 --- a/wpimath/src/main/python/semiwrap/kinematics/SwerveDriveKinematics.yml +++ b/wpimath/src/main/python/semiwrap/kinematics/SwerveDriveKinematics.yml @@ -1,7 +1,7 @@ classes: - frc::SwerveDriveKinematics: + wpi::math::SwerveDriveKinematics: force_type_casters: - - wpi::array + - wpi::util::array template_params: - size_t NumModules methods: @@ -9,14 +9,14 @@ classes: overloads: ModuleTranslations&&...: ignore: true - const wpi::array&: + const wpi::util::array&: ignore: true ResetHeadings: overloads: ModuleHeadings&&...: ignore: true - wpi::array: + wpi::util::array: ToSwerveModuleStates: doc: | @@ -48,29 +48,29 @@ classes: overloads: ModuleStates&&... [const]: ignore: true - const wpi::array& [const]: + const wpi::util::array& [const]: ToTwist2d: overloads: ModuleDeltas&&... [const]: ignore: true - wpi::array [const]: - const wpi::array&, const wpi::array& [const]: + wpi::util::array [const]: + const wpi::util::array&, const wpi::util::array& [const]: DesaturateWheelSpeeds: overloads: - wpi::array*, units::meters_per_second_t: + wpi::util::array*, wpi::units::meters_per_second_t: cpp_code: | - [](wpi::array moduleStates, units::meters_per_second_t attainableMaxSpeed) { - frc::SwerveDriveKinematics::DesaturateWheelSpeeds(&moduleStates, attainableMaxSpeed); + [](wpi::util::array moduleStates, wpi::units::meters_per_second_t attainableMaxSpeed) { + wpi::math::SwerveDriveKinematics::DesaturateWheelSpeeds(&moduleStates, attainableMaxSpeed); return moduleStates; } - ? wpi::array*, ChassisSpeeds, units::meters_per_second_t, units::meters_per_second_t, units::radians_per_second_t + ? wpi::util::array*, ChassisSpeeds, wpi::units::meters_per_second_t, wpi::units::meters_per_second_t, wpi::units::radians_per_second_t : cpp_code: | - [](wpi::array moduleStates, + [](wpi::util::array moduleStates, ChassisSpeeds currentChassisSpeed, - units::meters_per_second_t attainableMaxModuleSpeed, - units::meters_per_second_t attainableMaxRobotTranslationSpeed, - units::radians_per_second_t attainableMaxRobotRotationSpeed) { - frc::SwerveDriveKinematics::DesaturateWheelSpeeds(&moduleStates, currentChassisSpeed, attainableMaxModuleSpeed, attainableMaxRobotTranslationSpeed, attainableMaxRobotRotationSpeed); + wpi::units::meters_per_second_t attainableMaxModuleSpeed, + wpi::units::meters_per_second_t attainableMaxRobotTranslationSpeed, + wpi::units::radians_per_second_t attainableMaxRobotRotationSpeed) { + wpi::math::SwerveDriveKinematics::DesaturateWheelSpeeds(&moduleStates, currentChassisSpeed, attainableMaxModuleSpeed, attainableMaxRobotTranslationSpeed, attainableMaxRobotRotationSpeed); return moduleStates; } @@ -91,18 +91,18 @@ classes: templates: SwerveDrive2Kinematics: - qualname: frc::SwerveDriveKinematics + qualname: wpi::math::SwerveDriveKinematics params: - 2 SwerveDrive3Kinematics: - qualname: frc::SwerveDriveKinematics + qualname: wpi::math::SwerveDriveKinematics params: - 3 SwerveDrive4Kinematics: - qualname: frc::SwerveDriveKinematics + qualname: wpi::math::SwerveDriveKinematics params: - 4 SwerveDrive6Kinematics: - qualname: frc::SwerveDriveKinematics + qualname: wpi::math::SwerveDriveKinematics params: - 6 diff --git a/wpimath/src/main/python/semiwrap/kinematics/SwerveDriveOdometry.yml b/wpimath/src/main/python/semiwrap/kinematics/SwerveDriveOdometry.yml index 072f0cfac8..32e7ad3dc8 100644 --- a/wpimath/src/main/python/semiwrap/kinematics/SwerveDriveOdometry.yml +++ b/wpimath/src/main/python/semiwrap/kinematics/SwerveDriveOdometry.yml @@ -1,5 +1,5 @@ classes: - frc::SwerveDriveOdometry: + wpi::math::SwerveDriveOdometry: force_no_trampoline: true template_params: - size_t NumModules @@ -7,18 +7,18 @@ classes: SwerveDriveOdometry: templates: SwerveDrive2Odometry: - qualname: frc::SwerveDriveOdometry + qualname: wpi::math::SwerveDriveOdometry params: - 2 SwerveDrive3Odometry: - qualname: frc::SwerveDriveOdometry + qualname: wpi::math::SwerveDriveOdometry params: - 3 SwerveDrive4Odometry: - qualname: frc::SwerveDriveOdometry + qualname: wpi::math::SwerveDriveOdometry params: - 4 SwerveDrive6Odometry: - qualname: frc::SwerveDriveOdometry + qualname: wpi::math::SwerveDriveOdometry params: - 6 diff --git a/wpimath/src/main/python/semiwrap/kinematics/SwerveDriveOdometry3d.yml b/wpimath/src/main/python/semiwrap/kinematics/SwerveDriveOdometry3d.yml index 63752d4685..c76351210e 100644 --- a/wpimath/src/main/python/semiwrap/kinematics/SwerveDriveOdometry3d.yml +++ b/wpimath/src/main/python/semiwrap/kinematics/SwerveDriveOdometry3d.yml @@ -1,5 +1,5 @@ classes: - frc::SwerveDriveOdometry3d: + wpi::math::SwerveDriveOdometry3d: force_no_trampoline: true template_params: - size_t NumModules @@ -8,18 +8,18 @@ classes: templates: SwerveDrive2Odometry3d: - qualname: frc::SwerveDriveOdometry3d + qualname: wpi::math::SwerveDriveOdometry3d params: - 2 SwerveDrive3Odometry3d: - qualname: frc::SwerveDriveOdometry3d + qualname: wpi::math::SwerveDriveOdometry3d params: - 3 SwerveDrive4Odometry3d: - qualname: frc::SwerveDriveOdometry3d + qualname: wpi::math::SwerveDriveOdometry3d params: - 4 SwerveDrive6Odometry3d: - qualname: frc::SwerveDriveOdometry3d + qualname: wpi::math::SwerveDriveOdometry3d params: - 6 diff --git a/wpimath/src/main/python/semiwrap/kinematics/SwerveModulePosition.yml b/wpimath/src/main/python/semiwrap/kinematics/SwerveModulePosition.yml index aaa7130feb..637475a57f 100644 --- a/wpimath/src/main/python/semiwrap/kinematics/SwerveModulePosition.yml +++ b/wpimath/src/main/python/semiwrap/kinematics/SwerveModulePosition.yml @@ -2,7 +2,7 @@ extra_includes: - wpystruct.h classes: - frc::SwerveModulePosition: + wpi::math::SwerveModulePosition: force_no_default_constructor: true attributes: distance: @@ -13,15 +13,15 @@ classes: inline_code: | .def( py::init< - units::meter_t, frc::Rotation2d + wpi::units::meter_t, wpi::math::Rotation2d >(), - py::arg("distance") = 0, py::arg("angle") = frc::Rotation2d() + py::arg("distance") = 0, py::arg("angle") = wpi::math::Rotation2d() ) .def_property("distance_ft", - [](SwerveModulePosition * self) -> units::foot_t { + [](SwerveModulePosition * self) -> wpi::units::foot_t { return self->distance; }, - [](SwerveModulePosition * self, units::foot_t distance) { + [](SwerveModulePosition * self, wpi::units::foot_t distance) { self->distance = distance; } ) @@ -31,4 +31,4 @@ classes: }) inline_code: | - SetupWPyStruct(cls_SwerveModulePosition); + SetupWPyStruct(cls_SwerveModulePosition); diff --git a/wpimath/src/main/python/semiwrap/kinematics/SwerveModuleState.yml b/wpimath/src/main/python/semiwrap/kinematics/SwerveModuleState.yml index 9ba68ee960..70b6478265 100644 --- a/wpimath/src/main/python/semiwrap/kinematics/SwerveModuleState.yml +++ b/wpimath/src/main/python/semiwrap/kinematics/SwerveModuleState.yml @@ -2,7 +2,7 @@ extra_includes: - wpystruct.h classes: - frc::SwerveModuleState: + wpi::math::SwerveModuleState: force_no_default_constructor: true attributes: speed: @@ -20,15 +20,15 @@ inline_code: | cls_SwerveModuleState .def( py::init< - units::meters_per_second_t, frc::Rotation2d + wpi::units::meters_per_second_t, wpi::math::Rotation2d >(), - py::arg("speed") = 0, py::arg("angle") = frc::Rotation2d() + py::arg("speed") = 0, py::arg("angle") = wpi::math::Rotation2d() ) .def_property("speed_fps", - [](SwerveModuleState * self) -> units::feet_per_second_t { + [](SwerveModuleState * self) -> wpi::units::feet_per_second_t { return self->speed; }, - [](SwerveModuleState * self, units::feet_per_second_t speed) { + [](SwerveModuleState * self, wpi::units::feet_per_second_t speed) { self->speed = speed; } ) @@ -38,4 +38,4 @@ inline_code: | }) ; - SetupWPyStruct(cls_SwerveModuleState); + SetupWPyStruct(cls_SwerveModuleState); diff --git a/wpimath/src/main/python/semiwrap/spline/CubicHermiteSpline.yml b/wpimath/src/main/python/semiwrap/spline/CubicHermiteSpline.yml index 8947e658a1..f32ee9e859 100644 --- a/wpimath/src/main/python/semiwrap/spline/CubicHermiteSpline.yml +++ b/wpimath/src/main/python/semiwrap/spline/CubicHermiteSpline.yml @@ -1,5 +1,5 @@ classes: - frc::CubicHermiteSpline: + wpi::math::CubicHermiteSpline: force_no_trampoline: true methods: CubicHermiteSpline: diff --git a/wpimath/src/main/python/semiwrap/spline/QuinticHermiteSpline.yml b/wpimath/src/main/python/semiwrap/spline/QuinticHermiteSpline.yml index 054929423f..b7750fc608 100644 --- a/wpimath/src/main/python/semiwrap/spline/QuinticHermiteSpline.yml +++ b/wpimath/src/main/python/semiwrap/spline/QuinticHermiteSpline.yml @@ -1,5 +1,5 @@ classes: - frc::QuinticHermiteSpline: + wpi::math::QuinticHermiteSpline: force_no_trampoline: true methods: QuinticHermiteSpline: diff --git a/wpimath/src/main/python/semiwrap/spline/Spline.yml b/wpimath/src/main/python/semiwrap/spline/Spline.yml index 8804b137a7..4417d7550a 100644 --- a/wpimath/src/main/python/semiwrap/spline/Spline.yml +++ b/wpimath/src/main/python/semiwrap/spline/Spline.yml @@ -2,11 +2,11 @@ extra_includes: - pybind11/stl.h classes: - frc::Spline: + wpi::math::Spline: is_polymorphic: true force_type_casters: - - units::curvature_t - - wpi::array + - wpi::units::curvature_t + - wpi::util::array template_params: - int Degree methods: @@ -26,12 +26,12 @@ classes: cls_ControlVector .def( py::init< - wpi::array, - wpi::array>(), + wpi::util::array, + wpi::util::array>(), py::arg("x"), py::arg("y") ); - frc::Spline::ControlVector: + wpi::math::Spline::ControlVector: force_no_default_constructor: true attributes: x: @@ -39,11 +39,11 @@ classes: templates: Spline3: - qualname: frc::Spline + qualname: wpi::math::Spline params: - 3 Spline5: - qualname: frc::Spline + qualname: wpi::math::Spline params: - 5 diff --git a/wpimath/src/main/python/semiwrap/spline/SplineHelper.yml b/wpimath/src/main/python/semiwrap/spline/SplineHelper.yml index 8ec6394658..f6f25b214d 100644 --- a/wpimath/src/main/python/semiwrap/spline/SplineHelper.yml +++ b/wpimath/src/main/python/semiwrap/spline/SplineHelper.yml @@ -1,5 +1,5 @@ classes: - frc::SplineHelper: + wpi::math::SplineHelper: methods: CubicControlVectorsFromWaypoints: QuinticSplinesFromWaypoints: diff --git a/wpimath/src/main/python/semiwrap/spline/SplineParameterizer.yml b/wpimath/src/main/python/semiwrap/spline/SplineParameterizer.yml index a4971fa5b3..5a1e4d9164 100644 --- a/wpimath/src/main/python/semiwrap/spline/SplineParameterizer.yml +++ b/wpimath/src/main/python/semiwrap/spline/SplineParameterizer.yml @@ -1,13 +1,13 @@ classes: - frc::SplineParameterizer: + wpi::math::SplineParameterizer: force_no_default_constructor: true force_type_casters: - - units::curvature_t + - wpi::units::curvature_t methods: Parameterize: template_impls: - ['3'] - ['5'] - frc::SplineParameterizer::MalformedSplineException: + wpi::math::SplineParameterizer::MalformedSplineException: ignore: true diff --git a/wpimath/src/main/python/wpimath/_impl/src/PyTrajectoryConstraint.h b/wpimath/src/main/python/wpimath/_impl/src/PyTrajectoryConstraint.h index e4930f3bf8..e80ff79298 100644 --- a/wpimath/src/main/python/wpimath/_impl/src/PyTrajectoryConstraint.h +++ b/wpimath/src/main/python/wpimath/_impl/src/PyTrajectoryConstraint.h @@ -3,35 +3,35 @@ #include "wpi/math/trajectory/constraint/TrajectoryConstraint.hpp" #include -namespace frc { +namespace wpi::math { struct PyTrajectoryConstraint : public TrajectoryConstraint { PyTrajectoryConstraint() {} - units::meters_per_second_t - MaxVelocity(const Pose2d &pose, units::curvature_t curvature, - units::meters_per_second_t velocity) const override { + wpi::units::meters_per_second_t + MaxVelocity(const Pose2d &pose, wpi::units::curvature_t curvature, + wpi::units::meters_per_second_t velocity) const override { return m_constraint->MaxVelocity(pose, curvature, velocity); } - MinMax MinMaxAcceleration(const Pose2d &pose, units::curvature_t curvature, - units::meters_per_second_t speed) const override { + MinMax MinMaxAcceleration(const Pose2d &pose, wpi::units::curvature_t curvature, + wpi::units::meters_per_second_t speed) const override { return m_constraint->MinMaxAcceleration(pose, curvature, speed); } std::shared_ptr m_constraint; }; -}; // namespace frc +}; // namespace wpi::math namespace pybind11 { namespace detail { -template <> struct type_caster { - using value_conv = make_caster>; +template <> struct type_caster { + using value_conv = make_caster>; - PYBIND11_TYPE_CASTER(frc::PyTrajectoryConstraint, _("wpimath._controls._controls.constraint.TrajectoryConstraint")); + PYBIND11_TYPE_CASTER(wpi::math::PyTrajectoryConstraint, _("wpimath._controls._controls.constraint.TrajectoryConstraint")); bool load(handle src, bool convert) { value_conv conv; @@ -40,11 +40,11 @@ template <> struct type_caster { } value.m_constraint = - cast_op>(std::move(conv)); + cast_op>(std::move(conv)); return true; } - static handle cast(const frc::PyTrajectoryConstraint &src, + static handle cast(const wpi::math::PyTrajectoryConstraint &src, return_value_policy policy, handle parent) { return value_conv::cast(src.m_constraint, policy, parent); } diff --git a/wpimath/src/main/python/wpimath/_impl/src/type_casters/_units_base_type_caster.h b/wpimath/src/main/python/wpimath/_impl/src/type_casters/_units_base_type_caster.h index d539405512..10d5f88c33 100644 --- a/wpimath/src/main/python/wpimath/_impl/src/type_casters/_units_base_type_caster.h +++ b/wpimath/src/main/python/wpimath/_impl/src/type_casters/_units_base_type_caster.h @@ -11,24 +11,24 @@ namespace detail { When going from C++ to Python (eg, return values), the units that a user gets as a float are in whatever the unit was for C++. - units::foot_t getFeet(); // converted to float, value is feet + wpi::units::foot_t getFeet(); // converted to float, value is feet When going from Python to C++, the units a user uses are once again whatever the C++ function specifies: - void setFeet(units::foot_t ft); // must pass a float, it's in feet - void setMeters(units::meter_t m); // must pass a float, it's in meters + void setFeet(wpi::units::foot_t ft); // must pass a float, it's in feet + void setMeters(wpi::units::meter_t m); // must pass a float, it's in meters Unfortunately, with this type caster and robotpy-build there are mismatch issues with implicit conversions when default values are used that don't match the actual value: - foo(units::second_t tm = 10_ms); // if not careful, pybind11 will + foo(wpi::units::second_t tm = 10_ms); // if not careful, pybind11 will // store as 10 seconds */ template class S> -struct type_caster> { - using value_type = units::unit_t; +struct type_caster> { + using value_type = wpi::units::unit_t; // TODO: there should be a way to include the type with this PYBIND11_TYPE_CASTER(value_type, handle_type_name::name); diff --git a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_acceleration_type_caster.h b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_acceleration_type_caster.h index f75f93a2ac..032c09f055 100644 --- a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_acceleration_type_caster.h +++ b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_acceleration_type_caster.h @@ -4,27 +4,27 @@ namespace pybind11 { namespace detail { -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.meters_per_second_squared"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.meters_per_second_squared"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.feet_per_second_squared"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.feet_per_second_squared"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.standard_gravity"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.standard_gravity"); }; diff --git a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_angle_type_caster.h b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_angle_type_caster.h index 14dfa0c690..c4323817c7 100644 --- a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_angle_type_caster.h +++ b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_angle_type_caster.h @@ -4,91 +4,91 @@ namespace pybind11 { namespace detail { -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.radians"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.radians"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanoradians"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanoradians"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microradians"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microradians"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.milliradians"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.milliradians"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kiloradians"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kiloradians"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.degrees"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.degrees"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.arcminutes"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.arcminutes"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.arcseconds"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.arcseconds"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.milliarcseconds"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.milliarcseconds"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.turns"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.turns"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.gradians"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.gradians"); }; diff --git a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_angular_acceleration_type_caster.h b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_angular_acceleration_type_caster.h index c633786416..01dc182c89 100644 --- a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_angular_acceleration_type_caster.h +++ b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_angular_acceleration_type_caster.h @@ -4,27 +4,27 @@ namespace pybind11 { namespace detail { -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.radians_per_second_squared"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.radians_per_second_squared"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.degrees_per_second_squared"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.degrees_per_second_squared"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.turns_per_second_squared"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.turns_per_second_squared"); }; diff --git a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_angular_velocity_type_caster.h b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_angular_velocity_type_caster.h index 3c3f857351..ca974fec09 100644 --- a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_angular_velocity_type_caster.h +++ b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_angular_velocity_type_caster.h @@ -4,43 +4,43 @@ namespace pybind11 { namespace detail { -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.radians_per_second"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.radians_per_second"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.degrees_per_second"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.degrees_per_second"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.turns_per_second"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.turns_per_second"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.revolutions_per_minute"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.revolutions_per_minute"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.milliarcseconds_per_year"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.milliarcseconds_per_year"); }; diff --git a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_area_type_caster.h b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_area_type_caster.h index ed0fc9c69d..ff733500a7 100644 --- a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_area_type_caster.h +++ b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_area_type_caster.h @@ -4,59 +4,59 @@ namespace pybind11 { namespace detail { -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.square_meters"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.square_meters"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.square_feet"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.square_feet"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.square_inches"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.square_inches"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.square_miles"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.square_miles"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.square_kilometers"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.square_kilometers"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.hectares"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.hectares"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.acres"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.acres"); }; diff --git a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_capacitance_type_caster.h b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_capacitance_type_caster.h index 46d1063b01..7ab11464a6 100644 --- a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_capacitance_type_caster.h +++ b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_capacitance_type_caster.h @@ -4,43 +4,43 @@ namespace pybind11 { namespace detail { -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.farads"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.farads"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanofarads"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanofarads"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microfarads"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microfarads"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.millifarads"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.millifarads"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilofarads"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilofarads"); }; diff --git a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_charge_type_caster.h b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_charge_type_caster.h index f3e3a7ab4e..e1d260befb 100644 --- a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_charge_type_caster.h +++ b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_charge_type_caster.h @@ -4,83 +4,83 @@ namespace pybind11 { namespace detail { -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.coulombs"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.coulombs"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanocoulombs"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanocoulombs"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microcoulombs"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microcoulombs"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.millicoulombs"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.millicoulombs"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilocoulombs"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilocoulombs"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.ampere_hours"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.ampere_hours"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanoampere_hours"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanoampere_hours"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microampere_hours"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microampere_hours"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.milliampere_hours"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.milliampere_hours"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kiloampere_hours"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kiloampere_hours"); }; diff --git a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_compound_type_caster.h b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_compound_type_caster.h index 41c9cb13d3..e837852a96 100644 --- a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_compound_type_caster.h +++ b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_compound_type_caster.h @@ -11,82 +11,82 @@ namespace pybind11 { namespace detail { template <> -struct handle_type_name>>> { +struct handle_type_name>>> { static constexpr auto name = _("wpimath.units.radians_per_meter"); }; template <> -struct handle_type_name>>> { +struct handle_type_name>>> { static constexpr auto name = _("wpimath.units.radians_per_second_per_volt"); }; template <> -struct handle_type_name>> { +struct handle_type_name>> { static constexpr auto name = _("wpimath.units.units_per_second"); }; template <> struct handle_type_name< - units::unit_t>>> { + wpi::units::unit_t>>> { static constexpr auto name = _("wpimath.units.units_per_second_squared"); }; -using volt_seconds = units::compound_unit; -using volt_seconds_squared = units::compound_unit; +using volt_seconds = wpi::units::compound_unit; +using volt_seconds_squared = wpi::units::compound_unit; -template <> struct handle_type_name> { +template <> struct handle_type_name> { static constexpr auto name = _("wpimath.units.volt_seconds"); }; -template <> struct handle_type_name> { +template <> struct handle_type_name> { static constexpr auto name = _("wpimath.units.volt_seconds_squared"); }; template <> -struct handle_type_name>>> { +struct handle_type_name>>> { static constexpr auto name = _("wpimath.units.volt_seconds_per_meter"); }; template <> -struct handle_type_name>>> { +struct handle_type_name>>> { static constexpr auto name = _("wpimath.units.volt_seconds_squared_per_meter"); }; template <> -struct handle_type_name>>> { +struct handle_type_name>>> { static constexpr auto name = _("wpimath.units.volt_seconds_per_feet"); }; template <> -struct handle_type_name>>> { +struct handle_type_name>>> { static constexpr auto name = _("wpimath.units.volt_seconds_squared_per_feet"); }; template <> -struct handle_type_name>>> { +struct handle_type_name>>> { static constexpr auto name = _("wpimath.units.volt_seconds_per_radian"); }; template <> -struct handle_type_name>>> { +struct handle_type_name>>> { static constexpr auto name = _("wpimath.units.volt_seconds_squared_per_radian"); }; -using unit_seconds = units::compound_unit; -using unit_seconds_squared = units::compound_unit; +using unit_seconds = wpi::units::compound_unit; +using unit_seconds_squared = wpi::units::compound_unit; template <> -struct handle_type_name>>> { +struct handle_type_name>>> { static constexpr auto name = _("wpimath.units.unit_seconds_squared_per_unit"); }; template <> -struct handle_type_name>>> { +struct handle_type_name>>> { static constexpr auto name = _("wpimath.units.meters_per_second_squared_per_volt"); }; diff --git a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_concentration_type_caster.h b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_concentration_type_caster.h index 160f3a2202..7a4d8d5fd9 100644 --- a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_concentration_type_caster.h +++ b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_concentration_type_caster.h @@ -4,35 +4,35 @@ namespace pybind11 { namespace detail { -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.parts_per_million"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.parts_per_million"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.parts_per_billion"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.parts_per_billion"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.parts_per_trillion"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.parts_per_trillion"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.percent"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.percent"); }; diff --git a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_conductance_type_caster.h b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_conductance_type_caster.h index 0b7f48bbf3..bf3200b099 100644 --- a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_conductance_type_caster.h +++ b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_conductance_type_caster.h @@ -4,43 +4,43 @@ namespace pybind11 { namespace detail { -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.siemens"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.siemens"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanosiemens"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanosiemens"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microsiemens"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microsiemens"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.millisiemens"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.millisiemens"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilosiemens"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilosiemens"); }; diff --git a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_current_type_caster.h b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_current_type_caster.h index 56952e11f6..fd5939564b 100644 --- a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_current_type_caster.h +++ b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_current_type_caster.h @@ -4,43 +4,43 @@ namespace pybind11 { namespace detail { -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.amperes"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.amperes"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanoamperes"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanoamperes"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microamperes"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microamperes"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.milliamperes"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.milliamperes"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kiloamperes"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kiloamperes"); }; diff --git a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_data_transfer_rate_type_caster.h b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_data_transfer_rate_type_caster.h index 2aebbbc968..717702982d 100644 --- a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_data_transfer_rate_type_caster.h +++ b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_data_transfer_rate_type_caster.h @@ -4,19 +4,19 @@ namespace pybind11 { namespace detail { -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.exabytes_per_second"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.exabytes_per_second"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.exabits_per_second"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.exabits_per_second"); }; diff --git a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_data_type_caster.h b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_data_type_caster.h index e89cfd2442..759fa1cafc 100644 --- a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_data_type_caster.h +++ b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_data_type_caster.h @@ -4,19 +4,19 @@ namespace pybind11 { namespace detail { -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.exabytes"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.exabytes"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.exabits"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.exabits"); }; diff --git a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_density_type_caster.h b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_density_type_caster.h index 1fd3272838..7b4d2bf3fb 100644 --- a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_density_type_caster.h +++ b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_density_type_caster.h @@ -4,83 +4,83 @@ namespace pybind11 { namespace detail { -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilograms_per_cubic_meter"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilograms_per_cubic_meter"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.grams_per_milliliter"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.grams_per_milliliter"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilograms_per_liter"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilograms_per_liter"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.ounces_per_cubic_foot"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.ounces_per_cubic_foot"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.ounces_per_cubic_inch"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.ounces_per_cubic_inch"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.ounces_per_gallon"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.ounces_per_gallon"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.pounds_per_cubic_foot"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.pounds_per_cubic_foot"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.pounds_per_cubic_inch"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.pounds_per_cubic_inch"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.pounds_per_gallon"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.pounds_per_gallon"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.slugs_per_cubic_foot"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.slugs_per_cubic_foot"); }; diff --git a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_energy_type_caster.h b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_energy_type_caster.h index 0d7e785c34..b671ab4b2e 100644 --- a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_energy_type_caster.h +++ b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_energy_type_caster.h @@ -4,139 +4,139 @@ namespace pybind11 { namespace detail { -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.joules"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.joules"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanojoules"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanojoules"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microjoules"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microjoules"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.millijoules"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.millijoules"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilojoules"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilojoules"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.calories"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.calories"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanocalories"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanocalories"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microcalories"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microcalories"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.millicalories"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.millicalories"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilocalories"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilocalories"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilowatt_hours"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilowatt_hours"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.watt_hours"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.watt_hours"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.british_thermal_units"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.british_thermal_units"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.british_thermal_units_iso"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.british_thermal_units_iso"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.british_thermal_units_59"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.british_thermal_units_59"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.therms"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.therms"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.foot_pounds"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.foot_pounds"); }; diff --git a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_force_type_caster.h b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_force_type_caster.h index 1d6c1e5f3e..94274e63e3 100644 --- a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_force_type_caster.h +++ b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_force_type_caster.h @@ -4,75 +4,75 @@ namespace pybind11 { namespace detail { -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.newtons"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.newtons"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanonewtons"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanonewtons"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.micronewtons"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.micronewtons"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.millinewtons"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.millinewtons"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilonewtons"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilonewtons"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.pounds"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.pounds"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.dynes"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.dynes"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kiloponds"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kiloponds"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.poundals"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.poundals"); }; diff --git a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_frequency_type_caster.h b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_frequency_type_caster.h index 75c3caf554..f4a477487b 100644 --- a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_frequency_type_caster.h +++ b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_frequency_type_caster.h @@ -4,43 +4,43 @@ namespace pybind11 { namespace detail { -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.hertz"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.hertz"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanohertz"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanohertz"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microhertz"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microhertz"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.millihertz"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.millihertz"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilohertz"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilohertz"); }; diff --git a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_illuminance_type_caster.h b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_illuminance_type_caster.h index 8df5e1f48c..f087b0b30f 100644 --- a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_illuminance_type_caster.h +++ b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_illuminance_type_caster.h @@ -4,67 +4,67 @@ namespace pybind11 { namespace detail { -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.luxes"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.luxes"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanoluxes"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanoluxes"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microluxes"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microluxes"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.milliluxes"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.milliluxes"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kiloluxes"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kiloluxes"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.footcandles"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.footcandles"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.lumens_per_square_inch"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.lumens_per_square_inch"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.phots"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.phots"); }; diff --git a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_impedance_type_caster.h b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_impedance_type_caster.h index d4a89edb45..57b6c9f630 100644 --- a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_impedance_type_caster.h +++ b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_impedance_type_caster.h @@ -4,43 +4,43 @@ namespace pybind11 { namespace detail { -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.ohms"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.ohms"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanoohms"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanoohms"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microohms"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microohms"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.milliohms"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.milliohms"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kiloohms"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kiloohms"); }; diff --git a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_inductance_type_caster.h b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_inductance_type_caster.h index 8585c0dc1d..3820713b49 100644 --- a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_inductance_type_caster.h +++ b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_inductance_type_caster.h @@ -4,43 +4,43 @@ namespace pybind11 { namespace detail { -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.henries"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.henries"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanohenries"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanohenries"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microhenries"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microhenries"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.millihenries"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.millihenries"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilohenries"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilohenries"); }; diff --git a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_length_type_caster.h b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_length_type_caster.h index f85fd206dd..3eb4321ea5 100644 --- a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_length_type_caster.h +++ b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_length_type_caster.h @@ -4,187 +4,187 @@ namespace pybind11 { namespace detail { -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.meters"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.meters"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanometers"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanometers"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.micrometers"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.micrometers"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.millimeters"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.millimeters"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.centimeters"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.centimeters"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilometers"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilometers"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.feet"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.feet"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.mils"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.mils"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.inches"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.inches"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.miles"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.miles"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nauticalMiles"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nauticalMiles"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.astronicalUnits"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.astronicalUnits"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.lightyears"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.lightyears"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.parsecs"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.parsecs"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.angstroms"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.angstroms"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.cubits"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.cubits"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.fathoms"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.fathoms"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.chains"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.chains"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.furlongs"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.furlongs"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.hands"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.hands"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.leagues"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.leagues"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nauticalLeagues"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nauticalLeagues"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.yards"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.yards"); }; diff --git a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_luminous_flux_type_caster.h b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_luminous_flux_type_caster.h index 7a4c3cc79d..9e0af5d056 100644 --- a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_luminous_flux_type_caster.h +++ b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_luminous_flux_type_caster.h @@ -4,43 +4,43 @@ namespace pybind11 { namespace detail { -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.lumens"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.lumens"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanolumens"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanolumens"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microlumens"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microlumens"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.millilumens"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.millilumens"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilolumens"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilolumens"); }; diff --git a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_luminous_intensity_type_caster.h b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_luminous_intensity_type_caster.h index d6a9bc6e55..45061f63b6 100644 --- a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_luminous_intensity_type_caster.h +++ b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_luminous_intensity_type_caster.h @@ -4,43 +4,43 @@ namespace pybind11 { namespace detail { -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.candelas"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.candelas"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanocandelas"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanocandelas"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microcandelas"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microcandelas"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.millicandelas"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.millicandelas"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilocandelas"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilocandelas"); }; diff --git a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_magnetic_field_strength_type_caster.h b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_magnetic_field_strength_type_caster.h index bb30e25ccf..d9d09accd2 100644 --- a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_magnetic_field_strength_type_caster.h +++ b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_magnetic_field_strength_type_caster.h @@ -4,51 +4,51 @@ namespace pybind11 { namespace detail { -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.teslas"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.teslas"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanoteslas"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanoteslas"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microteslas"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microteslas"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.milliteslas"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.milliteslas"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kiloteslas"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kiloteslas"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.gauss"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.gauss"); }; diff --git a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_magnetic_flux_type_caster.h b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_magnetic_flux_type_caster.h index 942a473f72..4650ff64b3 100644 --- a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_magnetic_flux_type_caster.h +++ b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_magnetic_flux_type_caster.h @@ -4,51 +4,51 @@ namespace pybind11 { namespace detail { -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.webers"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.webers"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanowebers"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanowebers"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microwebers"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microwebers"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.milliwebers"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.milliwebers"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilowebers"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilowebers"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.maxwells"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.maxwells"); }; diff --git a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_mass_type_caster.h b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_mass_type_caster.h index 07edf38f17..e49d803489 100644 --- a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_mass_type_caster.h +++ b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_mass_type_caster.h @@ -4,107 +4,107 @@ namespace pybind11 { namespace detail { -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.grams"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.grams"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanograms"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanograms"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.micrograms"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.micrograms"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.milligrams"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.milligrams"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilograms"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilograms"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.metric_tons"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.metric_tons"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.pounds"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.pounds"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.long_tons"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.long_tons"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.short_tons"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.short_tons"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.stone"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.stone"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.ounces"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.ounces"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.carats"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.carats"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.slugs"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.slugs"); }; diff --git a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_misc_type_caster.h b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_misc_type_caster.h index da662ee9d8..e500aa4561 100644 --- a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_misc_type_caster.h +++ b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_misc_type_caster.h @@ -5,19 +5,19 @@ namespace pybind11 { namespace detail { -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("float"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("float"); }; -// template <> struct handle_type_name { +// template <> struct handle_type_name { // static constexpr auto name = _("float"); // }; -// template <> struct handle_type_name { +// template <> struct handle_type_name { // static constexpr auto name = _("float"); // }; diff --git a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_moment_of_inertia_type_caster.h b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_moment_of_inertia_type_caster.h index b9f3daa822..ba4ca20076 100644 --- a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_moment_of_inertia_type_caster.h +++ b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_moment_of_inertia_type_caster.h @@ -4,11 +4,11 @@ namespace pybind11 { namespace detail { -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilogram_square_meters"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilogram_square_meters"); }; diff --git a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_power_type_caster.h b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_power_type_caster.h index 16788f6910..e4f43087e3 100644 --- a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_power_type_caster.h +++ b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_power_type_caster.h @@ -4,51 +4,51 @@ namespace pybind11 { namespace detail { -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.watts"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.watts"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanowatts"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanowatts"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microwatts"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microwatts"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.milliwatts"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.milliwatts"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilowatts"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilowatts"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.horsepower"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.horsepower"); }; diff --git a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_pressure_type_caster.h b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_pressure_type_caster.h index 46f578f269..c6aacba348 100644 --- a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_pressure_type_caster.h +++ b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_pressure_type_caster.h @@ -4,83 +4,83 @@ namespace pybind11 { namespace detail { -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.pascals"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.pascals"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanopascals"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanopascals"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.micropascals"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.micropascals"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.millipascals"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.millipascals"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilopascals"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilopascals"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.bars"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.bars"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.mbars"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.mbars"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.atmospheres"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.atmospheres"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.pounds_per_square_inch"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.pounds_per_square_inch"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.torrs"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.torrs"); }; diff --git a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_radiation_type_caster.h b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_radiation_type_caster.h index 67d50c3148..b48cef48d2 100644 --- a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_radiation_type_caster.h +++ b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_radiation_type_caster.h @@ -4,147 +4,147 @@ namespace pybind11 { namespace detail { -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.becquerels"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.becquerels"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanobecquerels"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanobecquerels"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microbecquerels"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microbecquerels"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.millibecquerels"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.millibecquerels"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilobecquerels"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilobecquerels"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.grays"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.grays"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanograys"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanograys"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.micrograys"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.micrograys"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.milligrays"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.milligrays"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilograys"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilograys"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.sieverts"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.sieverts"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanosieverts"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanosieverts"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microsieverts"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microsieverts"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.millisieverts"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.millisieverts"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilosieverts"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilosieverts"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.curies"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.curies"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.rutherfords"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.rutherfords"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.rads"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.rads"); }; diff --git a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_solid_angle_type_caster.h b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_solid_angle_type_caster.h index 1ef6a3f491..490a1d3a0a 100644 --- a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_solid_angle_type_caster.h +++ b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_solid_angle_type_caster.h @@ -4,59 +4,59 @@ namespace pybind11 { namespace detail { -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.steradians"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.steradians"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanosteradians"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanosteradians"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microsteradians"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microsteradians"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.millisteradians"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.millisteradians"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilosteradians"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilosteradians"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.degrees_squared"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.degrees_squared"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.spats"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.spats"); }; diff --git a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_substance_type_caster.h b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_substance_type_caster.h index 11b04a039a..202f8f0fbd 100644 --- a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_substance_type_caster.h +++ b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_substance_type_caster.h @@ -4,11 +4,11 @@ namespace pybind11 { namespace detail { -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.moles"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.moles"); }; diff --git a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_temperature_type_caster.h b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_temperature_type_caster.h index 32003c0f30..091e2ebcc8 100644 --- a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_temperature_type_caster.h +++ b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_temperature_type_caster.h @@ -4,43 +4,43 @@ namespace pybind11 { namespace detail { -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kelvin"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kelvin"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.celsius"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.celsius"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.fahrenheit"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.fahrenheit"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.reaumur"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.reaumur"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.rankine"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.rankine"); }; diff --git a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_time_type_caster.h b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_time_type_caster.h index 0caeca2c1e..f0bb0ad13c 100644 --- a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_time_type_caster.h +++ b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_time_type_caster.h @@ -4,99 +4,99 @@ namespace pybind11 { namespace detail { -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.seconds"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.seconds"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanoseconds"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanoseconds"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microseconds"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microseconds"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.milliseconds"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.milliseconds"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kiloseconds"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kiloseconds"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.minutes"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.minutes"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.hours"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.hours"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.days"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.days"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.weeks"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.weeks"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.years"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.years"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.julian_years"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.julian_years"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.gregorian_years"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.gregorian_years"); }; diff --git a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_torque_type_caster.h b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_torque_type_caster.h index a68aa3f523..f0cc6e6bea 100644 --- a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_torque_type_caster.h +++ b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_torque_type_caster.h @@ -4,43 +4,43 @@ namespace pybind11 { namespace detail { -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.newton_meters"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.newton_meters"); }; -// template <> struct handle_type_name { +// template <> struct handle_type_name { // static constexpr auto name = _("wpimath.units.foot_pounds"); // }; -// template <> struct handle_type_name { +// template <> struct handle_type_name { // static constexpr auto name = _("wpimath.units.foot_pounds"); // }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.foot_poundals"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.foot_poundals"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.inch_pounds"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.inch_pounds"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.meter_kilograms"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.meter_kilograms"); }; diff --git a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_velocity_type_caster.h b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_velocity_type_caster.h index 115803f2aa..d6e3319736 100644 --- a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_velocity_type_caster.h +++ b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_velocity_type_caster.h @@ -4,43 +4,43 @@ namespace pybind11 { namespace detail { -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.meters_per_second"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.meters_per_second"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.feet_per_second"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.feet_per_second"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.miles_per_hour"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.miles_per_hour"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilometers_per_hour"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilometers_per_hour"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.knots"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.knots"); }; diff --git a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_voltage_type_caster.h b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_voltage_type_caster.h index 16f3ac2e95..8c99318965 100644 --- a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_voltage_type_caster.h +++ b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_voltage_type_caster.h @@ -4,59 +4,59 @@ namespace pybind11 { namespace detail { -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.volts"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.volts"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanovolts"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanovolts"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microvolts"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microvolts"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.millivolts"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.millivolts"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilovolts"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kilovolts"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.statvolts"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.statvolts"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.abvolts"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.abvolts"); }; diff --git a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_volume_type_caster.h b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_volume_type_caster.h index d6b9218837..c2253cbbaa 100644 --- a/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_volume_type_caster.h +++ b/wpimath/src/main/python/wpimath/_impl/src/type_casters/units_volume_type_caster.h @@ -4,267 +4,267 @@ namespace pybind11 { namespace detail { -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.cubic_meters"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.cubic_meters"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.cubic_millimeters"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.cubic_millimeters"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.cubic_kilometers"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.cubic_kilometers"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.liters"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.liters"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanoliters"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.nanoliters"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microliters"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.microliters"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.milliliters"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.milliliters"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kiloliters"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.kiloliters"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.cubic_inches"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.cubic_inches"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.cubic_feet"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.cubic_feet"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.cubic_yards"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.cubic_yards"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.cubic_miles"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.cubic_miles"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.gallons"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.gallons"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.quarts"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.quarts"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.pints"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.pints"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.cups"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.cups"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.fluid_ounces"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.fluid_ounces"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.barrels"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.barrels"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.bushels"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.bushels"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.cords"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.cords"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.cubic_fathoms"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.cubic_fathoms"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.tablespoons"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.tablespoons"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.teaspoons"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.teaspoons"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.pinches"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.pinches"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.dashes"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.dashes"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.drops"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.drops"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.fifths"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.fifths"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.drams"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.drams"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.gills"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.gills"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.pecks"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.pecks"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.sacks"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.sacks"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.shots"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.shots"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.strikes"); }; -template <> struct handle_type_name { +template <> struct handle_type_name { static constexpr auto name = _("wpimath.units.strikes"); }; diff --git a/wpimath/src/main/python/wpimath/geometry/include/rpy/geometryToString.h b/wpimath/src/main/python/wpimath/geometry/include/rpy/geometryToString.h index 2c3a9e776e..7ef82e799b 100644 --- a/wpimath/src/main/python/wpimath/geometry/include/rpy/geometryToString.h +++ b/wpimath/src/main/python/wpimath/geometry/include/rpy/geometryToString.h @@ -11,11 +11,11 @@ namespace rpy { -inline std::string toString(const frc::Rotation2d &self) { +inline std::string toString(const wpi::math::Rotation2d &self) { return "Rotation2d(" + std::to_string(self.Radians()()) + ")"; } -inline std::string toString(const frc::Rotation3d &self) { +inline std::string toString(const wpi::math::Rotation3d &self) { return "Rotation3d(" "x=" + std::to_string(self.X()()) + @@ -27,7 +27,7 @@ inline std::string toString(const frc::Rotation3d &self) { std::to_string(self.Z()()) + ")"; } -inline std::string toString(const frc::Translation2d &self) { +inline std::string toString(const wpi::math::Translation2d &self) { return "Translation2d(" "x=" + std::to_string(self.X()()) + @@ -36,7 +36,7 @@ inline std::string toString(const frc::Translation2d &self) { std::to_string(self.Y()()) + ")"; } -inline std::string toString(const frc::Translation3d &self) { +inline std::string toString(const wpi::math::Translation3d &self) { return "Translation3d(" "x=" + std::to_string(self.X()()) + @@ -48,7 +48,7 @@ inline std::string toString(const frc::Translation3d &self) { std::to_string(self.Z()()) + ")"; } -inline std::string toString(const frc::Quaternion &self) { +inline std::string toString(const wpi::math::Quaternion &self) { return "Quaternion(" "w=" + std::to_string(self.W()) + @@ -63,33 +63,33 @@ inline std::string toString(const frc::Quaternion &self) { std::to_string(self.Z()) + ")"; } -inline std::string toString(const frc::Transform2d &self) { +inline std::string toString(const wpi::math::Transform2d &self) { return "Transform2d(" + rpy::toString(self.Translation()) + ", " + rpy::toString(self.Rotation()) + ")"; } -inline std::string toString(const frc::Transform3d &self) { +inline std::string toString(const wpi::math::Transform3d &self) { return "Transform3d(" + rpy::toString(self.Translation()) + ", " + rpy::toString(self.Rotation()) + ")"; } -inline std::string toString(const frc::Pose2d &self) { +inline std::string toString(const wpi::math::Pose2d &self) { return "Pose2d(" + rpy::toString(self.Translation()) + ", " + rpy::toString(self.Rotation()) + ")"; } -inline std::string toString(const frc::Pose3d &self) { +inline std::string toString(const wpi::math::Pose3d &self) { return "Pose3d(" + rpy::toString(self.Translation()) + ", " + rpy::toString(self.Rotation()) + ")"; } -inline std::string toString(const frc::Rectangle2d &self) { +inline std::string toString(const wpi::math::Rectangle2d &self) { return "Rectangle2d(center=" + rpy::toString(self.Center()) + ", xWidth=" + std::to_string(self.XWidth()()) + ", yWidth=" + std::to_string(self.YWidth()()) + ")"; } -inline std::string toString(const frc::Ellipse2d &self) { +inline std::string toString(const wpi::math::Ellipse2d &self) { return "Ellipse2d(center=" + rpy::toString(self.Center()) + ", xSemiAxis=" + std::to_string(self.XSemiAxis()()) + ", ySemiAxis=" + std::to_string(self.YSemiAxis()()) + ")"; diff --git a/wpimath/src/test/native/cpp/ComputerVisionUtilTest.cpp b/wpimath/src/test/native/cpp/ComputerVisionUtilTest.cpp index 18c790e6a6..7dd6c8d83e 100644 --- a/wpimath/src/test/native/cpp/ComputerVisionUtilTest.cpp +++ b/wpimath/src/test/native/cpp/ComputerVisionUtilTest.cpp @@ -7,13 +7,13 @@ #include "wpi/math/util/ComputerVisionUtil.hpp" TEST(ComputerVisionUtilTest, ObjectToRobotPose) { - frc::Pose3d robot{1_m, 2_m, 0_m, frc::Rotation3d{0_deg, 0_deg, 30_deg}}; - frc::Transform3d cameraToObject{frc::Translation3d{1_m, 1_m, 1_m}, - frc::Rotation3d{0_deg, -20_deg, 45_deg}}; - frc::Transform3d robotToCamera{frc::Translation3d{1_m, 0_m, 2_m}, - frc::Rotation3d{0_deg, 0_deg, 25_deg}}; - frc::Pose3d object = robot + robotToCamera + cameraToObject; + wpi::math::Pose3d robot{1_m, 2_m, 0_m, wpi::math::Rotation3d{0_deg, 0_deg, 30_deg}}; + wpi::math::Transform3d cameraToObject{wpi::math::Translation3d{1_m, 1_m, 1_m}, + wpi::math::Rotation3d{0_deg, -20_deg, 45_deg}}; + wpi::math::Transform3d robotToCamera{wpi::math::Translation3d{1_m, 0_m, 2_m}, + wpi::math::Rotation3d{0_deg, 0_deg, 25_deg}}; + wpi::math::Pose3d object = robot + robotToCamera + cameraToObject; EXPECT_EQ(robot, - frc::ObjectToRobotPose(object, cameraToObject, robotToCamera)); + wpi::math::ObjectToRobotPose(object, cameraToObject, robotToCamera)); } diff --git a/wpimath/src/test/native/cpp/DARETest.cpp b/wpimath/src/test/native/cpp/DARETest.cpp index b5b72e00f6..12c26cfeca 100644 --- a/wpimath/src/test/native/cpp/DARETest.cpp +++ b/wpimath/src/test/native/cpp/DARETest.cpp @@ -15,52 +15,52 @@ #include "wpi/util/print.hpp" // 2x1 -extern template wpi::expected, frc::DAREError> -frc::DARE<2, 1>(const Eigen::Matrix& A, +extern template wpi::util::expected, wpi::math::DAREError> +wpi::math::DARE<2, 1>(const Eigen::Matrix& A, const Eigen::Matrix& B, const Eigen::Matrix& Q, const Eigen::Matrix& R, bool checkPreconditions); -extern template wpi::expected, frc::DAREError> -frc::DARE<2, 1>(const Eigen::Matrix& A, +extern template wpi::util::expected, wpi::math::DAREError> +wpi::math::DARE<2, 1>(const Eigen::Matrix& A, const Eigen::Matrix& B, const Eigen::Matrix& Q, const Eigen::Matrix& R, const Eigen::Matrix& N, bool checkPreconditions); // 4x1 -extern template wpi::expected, frc::DAREError> -frc::DARE<4, 1>(const Eigen::Matrix& A, +extern template wpi::util::expected, wpi::math::DAREError> +wpi::math::DARE<4, 1>(const Eigen::Matrix& A, const Eigen::Matrix& B, const Eigen::Matrix& Q, const Eigen::Matrix& R, bool checkPreconditions); -extern template wpi::expected, frc::DAREError> -frc::DARE<4, 1>(const Eigen::Matrix& A, +extern template wpi::util::expected, wpi::math::DAREError> +wpi::math::DARE<4, 1>(const Eigen::Matrix& A, const Eigen::Matrix& B, const Eigen::Matrix& Q, const Eigen::Matrix& R, const Eigen::Matrix& N, bool checkPreconditions); // 2x2 -extern template wpi::expected, frc::DAREError> -frc::DARE<2, 2>(const Eigen::Matrix& A, +extern template wpi::util::expected, wpi::math::DAREError> +wpi::math::DARE<2, 2>(const Eigen::Matrix& A, const Eigen::Matrix& B, const Eigen::Matrix& Q, const Eigen::Matrix& R, bool checkPreconditions); -extern template wpi::expected, frc::DAREError> -frc::DARE<2, 2>(const Eigen::Matrix& A, +extern template wpi::util::expected, wpi::math::DAREError> +wpi::math::DARE<2, 2>(const Eigen::Matrix& A, const Eigen::Matrix& B, const Eigen::Matrix& Q, const Eigen::Matrix& R, const Eigen::Matrix& N, bool checkPreconditions); // 2x3 -extern template wpi::expected, frc::DAREError> -frc::DARE<2, 3>(const Eigen::Matrix& A, +extern template wpi::util::expected, wpi::math::DAREError> +wpi::math::DARE<2, 3>(const Eigen::Matrix& A, const Eigen::Matrix& B, const Eigen::Matrix& Q, const Eigen::Matrix& R, bool checkPreconditions); -extern template wpi::expected, frc::DAREError> -frc::DARE<2, 3>(const Eigen::Matrix& A, +extern template wpi::util::expected, wpi::math::DAREError> +wpi::math::DARE<2, 3>(const Eigen::Matrix& A, const Eigen::Matrix& B, const Eigen::Matrix& Q, const Eigen::Matrix& R, @@ -76,9 +76,9 @@ void ExpectMatrixEqual(const Eigen::MatrixXd& lhs, const Eigen::MatrixXd& rhs, } if (::testing::Test::HasFailure()) { - wpi::print("lhs =\n{}\n", lhs); - wpi::print("rhs =\n{}\n", rhs); - wpi::print("delta =\n{}\n", Eigen::MatrixXd{lhs - rhs}); + wpi::util::print("lhs =\n{}\n", lhs); + wpi::util::print("rhs =\n{}\n", rhs); + wpi::util::print("delta =\n{}\n", Eigen::MatrixXd{lhs - rhs}); } } @@ -131,13 +131,13 @@ TEST(DARETest, NonInvertibleA_ABQR) { // Example 2 of "On the Numerical Solution of the Discrete-Time Algebraic // Riccati Equation" - frc::Matrixd<4, 4> A{ + wpi::math::Matrixd<4, 4> A{ {0.5, 1, 0, 0}, {0, 0, 1, 0}, {0, 0, 0, 1}, {0, 0, 0, 0}}; - frc::Matrixd<4, 1> B{{0}, {0}, {0}, {1}}; - frc::Matrixd<4, 4> Q{{1, 0, 0, 0}, {0, 0, 0, 0}, {0, 0, 0, 0}, {0, 0, 0, 0}}; - frc::Matrixd<1, 1> R{0.25}; + wpi::math::Matrixd<4, 1> B{{0}, {0}, {0}, {1}}; + wpi::math::Matrixd<4, 4> Q{{1, 0, 0, 0}, {0, 0, 0, 0}, {0, 0, 0, 0}, {0, 0, 0, 0}}; + wpi::math::Matrixd<1, 1> R{0.25}; - auto ret = frc::DARE<4, 1>(A, B, Q, R); + auto ret = wpi::math::DARE<4, 1>(A, B, Q, R); EXPECT_TRUE(ret); auto X = ret.value(); @@ -150,19 +150,19 @@ TEST(DARETest, NonInvertibleA_ABQRN) { // Example 2 of "On the Numerical Solution of the Discrete-Time Algebraic // Riccati Equation" - frc::Matrixd<4, 4> A{ + wpi::math::Matrixd<4, 4> A{ {0.5, 1, 0, 0}, {0, 0, 1, 0}, {0, 0, 0, 1}, {0, 0, 0, 0}}; - frc::Matrixd<4, 1> B{{0}, {0}, {0}, {1}}; - frc::Matrixd<4, 4> Q{{1, 0, 0, 0}, {0, 0, 0, 0}, {0, 0, 0, 0}, {0, 0, 0, 0}}; - frc::Matrixd<1, 1> R{0.25}; + wpi::math::Matrixd<4, 1> B{{0}, {0}, {0}, {1}}; + wpi::math::Matrixd<4, 4> Q{{1, 0, 0, 0}, {0, 0, 0, 0}, {0, 0, 0, 0}, {0, 0, 0, 0}}; + wpi::math::Matrixd<1, 1> R{0.25}; - frc::Matrixd<4, 4> Aref{ + wpi::math::Matrixd<4, 4> Aref{ {0.25, 1, 0, 0}, {0, 0, 1, 0}, {0, 0, 0, 1}, {0, 0, 0, 0}}; Q = (A - Aref).transpose() * Q * (A - Aref); R = B.transpose() * Q * B + R; - frc::Matrixd<4, 1> N = (A - Aref).transpose() * Q * B; + wpi::math::Matrixd<4, 1> N = (A - Aref).transpose() * Q * B; - auto ret = frc::DARE<4, 1>(A, B, Q, R, N); + auto ret = wpi::math::DARE<4, 1>(A, B, Q, R, N); EXPECT_TRUE(ret); auto X = ret.value(); @@ -172,12 +172,12 @@ TEST(DARETest, NonInvertibleA_ABQRN) { } TEST(DARETest, InvertibleA_ABQR) { - frc::Matrixd<2, 2> A{{1, 1}, {0, 1}}; - frc::Matrixd<2, 1> B{{0}, {1}}; - frc::Matrixd<2, 2> Q{{1, 0}, {0, 0}}; - frc::Matrixd<1, 1> R{{0.3}}; + wpi::math::Matrixd<2, 2> A{{1, 1}, {0, 1}}; + wpi::math::Matrixd<2, 1> B{{0}, {1}}; + wpi::math::Matrixd<2, 2> Q{{1, 0}, {0, 0}}; + wpi::math::Matrixd<1, 1> R{{0.3}}; - auto ret = frc::DARE<2, 1>(A, B, Q, R); + auto ret = wpi::math::DARE<2, 1>(A, B, Q, R); EXPECT_TRUE(ret); auto X = ret.value(); @@ -187,17 +187,17 @@ TEST(DARETest, InvertibleA_ABQR) { } TEST(DARETest, InvertibleA_ABQRN) { - frc::Matrixd<2, 2> A{{1, 1}, {0, 1}}; - frc::Matrixd<2, 1> B{{0}, {1}}; - frc::Matrixd<2, 2> Q{{1, 0}, {0, 0}}; - frc::Matrixd<1, 1> R{0.3}; + wpi::math::Matrixd<2, 2> A{{1, 1}, {0, 1}}; + wpi::math::Matrixd<2, 1> B{{0}, {1}}; + wpi::math::Matrixd<2, 2> Q{{1, 0}, {0, 0}}; + wpi::math::Matrixd<1, 1> R{0.3}; - frc::Matrixd<2, 2> Aref{{0.5, 1}, {0, 1}}; + wpi::math::Matrixd<2, 2> Aref{{0.5, 1}, {0, 1}}; Q = (A - Aref).transpose() * Q * (A - Aref); R = B.transpose() * Q * B + R; - frc::Matrixd<2, 1> N = (A - Aref).transpose() * Q * B; + wpi::math::Matrixd<2, 1> N = (A - Aref).transpose() * Q * B; - auto ret = frc::DARE<2, 1>(A, B, Q, R, N); + auto ret = wpi::math::DARE<2, 1>(A, B, Q, R, N); EXPECT_TRUE(ret); auto X = ret.value(); @@ -209,12 +209,12 @@ TEST(DARETest, InvertibleA_ABQRN) { TEST(DARETest, FirstGeneralizedEigenvalueOfSTIsStable_ABQR) { // The first generalized eigenvalue of (S, T) is stable - frc::Matrixd<2, 2> A{{0, 1}, {0, 0}}; - frc::Matrixd<2, 1> B{{0}, {1}}; - frc::Matrixd<2, 2> Q{{1, 0}, {0, 1}}; - frc::Matrixd<1, 1> R{1}; + wpi::math::Matrixd<2, 2> A{{0, 1}, {0, 0}}; + wpi::math::Matrixd<2, 1> B{{0}, {1}}; + wpi::math::Matrixd<2, 2> Q{{1, 0}, {0, 1}}; + wpi::math::Matrixd<1, 1> R{1}; - auto ret = frc::DARE<2, 1>(A, B, Q, R); + auto ret = wpi::math::DARE<2, 1>(A, B, Q, R); EXPECT_TRUE(ret); auto X = ret.value(); @@ -226,17 +226,17 @@ TEST(DARETest, FirstGeneralizedEigenvalueOfSTIsStable_ABQR) { TEST(DARETest, FirstGeneralizedEigenvalueOfSTIsStable_ABQRN) { // The first generalized eigenvalue of (S, T) is stable - frc::Matrixd<2, 2> A{{0, 1}, {0, 0}}; - frc::Matrixd<2, 1> B{{0}, {1}}; - frc::Matrixd<2, 2> Q{{1, 0}, {0, 1}}; - frc::Matrixd<1, 1> R{1}; + wpi::math::Matrixd<2, 2> A{{0, 1}, {0, 0}}; + wpi::math::Matrixd<2, 1> B{{0}, {1}}; + wpi::math::Matrixd<2, 2> Q{{1, 0}, {0, 1}}; + wpi::math::Matrixd<1, 1> R{1}; - frc::Matrixd<2, 2> Aref{{0, 0.5}, {0, 0}}; + wpi::math::Matrixd<2, 2> Aref{{0, 0.5}, {0, 0}}; Q = (A - Aref).transpose() * Q * (A - Aref); R = B.transpose() * Q * B + R; - frc::Matrixd<2, 1> N = (A - Aref).transpose() * Q * B; + wpi::math::Matrixd<2, 1> N = (A - Aref).transpose() * Q * B; - auto ret = frc::DARE<2, 1>(A, B, Q, R, N); + auto ret = wpi::math::DARE<2, 1>(A, B, Q, R, N); EXPECT_TRUE(ret); auto X = ret.value(); @@ -251,7 +251,7 @@ TEST(DARETest, IdentitySystem_ABQR) { const Eigen::Matrix2d Q{Eigen::Matrix2d::Identity()}; const Eigen::Matrix2d R{Eigen::Matrix2d::Identity()}; - auto ret = frc::DARE<2, 2>(A, B, Q, R); + auto ret = wpi::math::DARE<2, 2>(A, B, Q, R); EXPECT_TRUE(ret); auto X = ret.value(); @@ -267,7 +267,7 @@ TEST(DARETest, IdentitySystem_ABQRN) { const Eigen::Matrix2d R{Eigen::Matrix2d::Identity()}; const Eigen::Matrix2d N{Eigen::Matrix2d::Identity()}; - auto ret = frc::DARE<2, 2>(A, B, Q, R, N); + auto ret = wpi::math::DARE<2, 2>(A, B, Q, R, N); EXPECT_TRUE(ret); auto X = ret.value(); @@ -278,11 +278,11 @@ TEST(DARETest, IdentitySystem_ABQRN) { TEST(DARETest, MoreInputsThanStates_ABQR) { const Eigen::Matrix2d A{Eigen::Matrix2d::Identity()}; - const frc::Matrixd<2, 3> B{{1.0, 0.0, 0.0}, {0.0, 0.5, 0.3}}; + const wpi::math::Matrixd<2, 3> B{{1.0, 0.0, 0.0}, {0.0, 0.5, 0.3}}; const Eigen::Matrix2d Q{Eigen::Matrix2d::Identity()}; const Eigen::Matrix3d R{Eigen::Matrix3d::Identity()}; - auto ret = frc::DARE<2, 3>(A, B, Q, R); + auto ret = wpi::math::DARE<2, 3>(A, B, Q, R); EXPECT_TRUE(ret); auto X = ret.value(); @@ -293,12 +293,12 @@ TEST(DARETest, MoreInputsThanStates_ABQR) { TEST(DARETest, MoreInputsThanStates_ABQRN) { const Eigen::Matrix2d A{Eigen::Matrix2d::Identity()}; - const frc::Matrixd<2, 3> B{{1.0, 0.0, 0.0}, {0.0, 0.5, 0.3}}; + const wpi::math::Matrixd<2, 3> B{{1.0, 0.0, 0.0}, {0.0, 0.5, 0.3}}; const Eigen::Matrix2d Q{Eigen::Matrix2d::Identity()}; const Eigen::Matrix3d R{Eigen::Matrix3d::Identity()}; - const frc::Matrixd<2, 3> N{{1.0, 0.0, 0.0}, {0.0, 1.0, 0.0}}; + const wpi::math::Matrixd<2, 3> N{{1.0, 0.0, 0.0}, {0.0, 1.0, 0.0}}; - auto ret = frc::DARE<2, 3>(A, B, Q, R, N); + auto ret = wpi::math::DARE<2, 3>(A, B, Q, R, N); EXPECT_TRUE(ret); auto X = ret.value(); @@ -313,9 +313,9 @@ TEST(DARETest, QNotSymmetric_ABQR) { const Eigen::Matrix2d Q{{1.0, 1.0}, {0.0, 1.0}}; const Eigen::Matrix2d R{Eigen::Matrix2d::Identity()}; - auto ret = frc::DARE<2, 2>(A, B, Q, R); + auto ret = wpi::math::DARE<2, 2>(A, B, Q, R); EXPECT_FALSE(ret); - EXPECT_EQ(ret.error(), frc::DAREError::QNotSymmetric); + EXPECT_EQ(ret.error(), wpi::math::DAREError::QNotSymmetric); } TEST(DARETest, QNotPositiveSemidefinite_ABQR) { @@ -324,9 +324,9 @@ TEST(DARETest, QNotPositiveSemidefinite_ABQR) { const Eigen::Matrix2d Q{-Eigen::Matrix2d::Identity()}; const Eigen::Matrix2d R{Eigen::Matrix2d::Identity()}; - auto ret = frc::DARE<2, 2>(A, B, Q, R); + auto ret = wpi::math::DARE<2, 2>(A, B, Q, R); EXPECT_FALSE(ret); - EXPECT_EQ(ret.error(), frc::DAREError::QNotPositiveSemidefinite); + EXPECT_EQ(ret.error(), wpi::math::DAREError::QNotPositiveSemidefinite); } TEST(DARETest, QNotSymmetric_ABQRN) { @@ -336,9 +336,9 @@ TEST(DARETest, QNotSymmetric_ABQRN) { const Eigen::Matrix2d R{Eigen::Matrix2d::Identity()}; const Eigen::Matrix2d N{2.0 * Eigen::Matrix2d::Identity()}; - auto ret = frc::DARE<2, 2>(A, B, Q, R, N); + auto ret = wpi::math::DARE<2, 2>(A, B, Q, R, N); EXPECT_FALSE(ret); - EXPECT_EQ(ret.error(), frc::DAREError::QNotSymmetric); + EXPECT_EQ(ret.error(), wpi::math::DAREError::QNotSymmetric); } TEST(DARETest, QNotPositiveSemidefinite_ABQRN) { @@ -348,9 +348,9 @@ TEST(DARETest, QNotPositiveSemidefinite_ABQRN) { const Eigen::Matrix2d R{Eigen::Matrix2d::Identity()}; const Eigen::Matrix2d N{2.0 * Eigen::Matrix2d::Identity()}; - auto ret = frc::DARE<2, 2>(A, B, Q, R, N); + auto ret = wpi::math::DARE<2, 2>(A, B, Q, R, N); EXPECT_FALSE(ret); - EXPECT_EQ(ret.error(), frc::DAREError::QNotPositiveSemidefinite); + EXPECT_EQ(ret.error(), wpi::math::DAREError::QNotPositiveSemidefinite); } TEST(DARETest, RNotSymmetric_ABQR) { @@ -359,9 +359,9 @@ TEST(DARETest, RNotSymmetric_ABQR) { const Eigen::Matrix2d Q{Eigen::Matrix2d::Identity()}; const Eigen::Matrix2d R{{1.0, 1.0}, {0.0, 1.0}}; - auto ret = frc::DARE<2, 2>(A, B, Q, R); + auto ret = wpi::math::DARE<2, 2>(A, B, Q, R); EXPECT_FALSE(ret); - EXPECT_EQ(ret.error(), frc::DAREError::RNotSymmetric); + EXPECT_EQ(ret.error(), wpi::math::DAREError::RNotSymmetric); } TEST(DARETest, RNotPositiveDefinite_ABQR) { @@ -370,14 +370,14 @@ TEST(DARETest, RNotPositiveDefinite_ABQR) { const Eigen::Matrix2d Q{Eigen::Matrix2d::Identity()}; const Eigen::Matrix2d R1{Eigen::Matrix2d::Zero()}; - auto ret1 = frc::DARE<2, 2>(A, B, Q, R1); + auto ret1 = wpi::math::DARE<2, 2>(A, B, Q, R1); EXPECT_FALSE(ret1); - EXPECT_EQ(ret1.error(), frc::DAREError::RNotPositiveDefinite); + EXPECT_EQ(ret1.error(), wpi::math::DAREError::RNotPositiveDefinite); const Eigen::Matrix2d R2{-Eigen::Matrix2d::Identity()}; - auto ret2 = frc::DARE<2, 2>(A, B, Q, R2); + auto ret2 = wpi::math::DARE<2, 2>(A, B, Q, R2); EXPECT_FALSE(ret2); - EXPECT_EQ(ret2.error(), frc::DAREError::RNotPositiveDefinite); + EXPECT_EQ(ret2.error(), wpi::math::DAREError::RNotPositiveDefinite); } TEST(DARETest, RNotSymmetric_ABQRN) { @@ -387,9 +387,9 @@ TEST(DARETest, RNotSymmetric_ABQRN) { const Eigen::Matrix2d N{Eigen::Matrix2d::Identity()}; const Eigen::Matrix2d R{{1.0, 1.0}, {0.0, 1.0}}; - auto ret = frc::DARE<2, 2>(A, B, Q, R, N); + auto ret = wpi::math::DARE<2, 2>(A, B, Q, R, N); EXPECT_FALSE(ret); - EXPECT_EQ(ret.error(), frc::DAREError::RNotSymmetric); + EXPECT_EQ(ret.error(), wpi::math::DAREError::RNotSymmetric); } TEST(DARETest, RNotPositiveDefinite_ABQRN) { @@ -399,14 +399,14 @@ TEST(DARETest, RNotPositiveDefinite_ABQRN) { const Eigen::Matrix2d N{Eigen::Matrix2d::Identity()}; const Eigen::Matrix2d R1{Eigen::Matrix2d::Zero()}; - auto ret1 = frc::DARE<2, 2>(A, B, Q, R1, N); + auto ret1 = wpi::math::DARE<2, 2>(A, B, Q, R1, N); EXPECT_FALSE(ret1); - EXPECT_EQ(ret1.error(), frc::DAREError::RNotPositiveDefinite); + EXPECT_EQ(ret1.error(), wpi::math::DAREError::RNotPositiveDefinite); const Eigen::Matrix2d R2{-Eigen::Matrix2d::Identity()}; - auto ret2 = frc::DARE<2, 2>(A, B, Q, R2, N); + auto ret2 = wpi::math::DARE<2, 2>(A, B, Q, R2, N); EXPECT_FALSE(ret2); - EXPECT_EQ(ret2.error(), frc::DAREError::RNotPositiveDefinite); + EXPECT_EQ(ret2.error(), wpi::math::DAREError::RNotPositiveDefinite); } TEST(DARETest, ABNotStabilizable_ABQR) { @@ -415,9 +415,9 @@ TEST(DARETest, ABNotStabilizable_ABQR) { const Eigen::Matrix2d Q{Eigen::Matrix2d::Identity()}; const Eigen::Matrix2d R{Eigen::Matrix2d::Identity()}; - auto ret = frc::DARE<2, 2>(A, B, Q, R); + auto ret = wpi::math::DARE<2, 2>(A, B, Q, R); EXPECT_FALSE(ret); - EXPECT_EQ(ret.error(), frc::DAREError::ABNotStabilizable); + EXPECT_EQ(ret.error(), wpi::math::DAREError::ABNotStabilizable); } TEST(DARETest, ABNotStabilizable_ABQRN) { @@ -427,9 +427,9 @@ TEST(DARETest, ABNotStabilizable_ABQRN) { const Eigen::Matrix2d R{Eigen::Matrix2d::Identity()}; const Eigen::Matrix2d N{Eigen::Matrix2d::Identity()}; - auto ret = frc::DARE<2, 2>(A, B, Q, R, N); + auto ret = wpi::math::DARE<2, 2>(A, B, Q, R, N); EXPECT_FALSE(ret); - EXPECT_EQ(ret.error(), frc::DAREError::ABNotStabilizable); + EXPECT_EQ(ret.error(), wpi::math::DAREError::ABNotStabilizable); } TEST(DARETest, ACNotDetectable_ABQR) { @@ -438,9 +438,9 @@ TEST(DARETest, ACNotDetectable_ABQR) { const Eigen::Matrix2d Q{Eigen::Matrix2d::Zero()}; const Eigen::Matrix2d R{Eigen::Matrix2d::Identity()}; - auto ret = frc::DARE<2, 2>(A, B, Q, R); + auto ret = wpi::math::DARE<2, 2>(A, B, Q, R); EXPECT_FALSE(ret); - EXPECT_EQ(ret.error(), frc::DAREError::ACNotDetectable); + EXPECT_EQ(ret.error(), wpi::math::DAREError::ACNotDetectable); } TEST(DARETest, ACNotDetectable_ABQRN) { @@ -450,9 +450,9 @@ TEST(DARETest, ACNotDetectable_ABQRN) { const Eigen::Matrix2d R{Eigen::Matrix2d::Identity()}; const Eigen::Matrix2d N{Eigen::Matrix2d::Zero()}; - auto ret = frc::DARE<2, 2>(A, B, Q, R, N); + auto ret = wpi::math::DARE<2, 2>(A, B, Q, R, N); EXPECT_FALSE(ret); - EXPECT_EQ(ret.error(), frc::DAREError::ACNotDetectable); + EXPECT_EQ(ret.error(), wpi::math::DAREError::ACNotDetectable); } TEST(DARETest, QDecomposition) { @@ -465,12 +465,12 @@ TEST(DARETest, QDecomposition) { // (A, C₁) should be detectable pair const Eigen::Matrix2d C_1{{0.0, 0.0}, {1.0, 0.0}}; const Eigen::Matrix2d Q_1 = C_1.transpose() * C_1; - auto ret1 = frc::DARE<2, 2>(A, B, Q_1, R); + auto ret1 = wpi::math::DARE<2, 2>(A, B, Q_1, R); EXPECT_TRUE(ret1); // (A, C₂) shouldn't be detectable pair const Eigen::Matrix2d C_2 = C_1.transpose(); const Eigen::Matrix2d Q_2 = C_2.transpose() * C_2; - auto ret2 = frc::DARE<2, 2>(A, B, Q_2, R); + auto ret2 = wpi::math::DARE<2, 2>(A, B, Q_2, R); EXPECT_FALSE(ret2); } diff --git a/wpimath/src/test/native/cpp/DARETest_Inst_2x1.cpp b/wpimath/src/test/native/cpp/DARETest_Inst_2x1.cpp index f73f25aa39..2219077ff6 100644 --- a/wpimath/src/test/native/cpp/DARETest_Inst_2x1.cpp +++ b/wpimath/src/test/native/cpp/DARETest_Inst_2x1.cpp @@ -4,13 +4,13 @@ #include "wpi/math/linalg/DARE.hpp" -template wpi::expected, frc::DAREError> -frc::DARE<2, 1>(const Eigen::Matrix& A, +template wpi::util::expected, wpi::math::DAREError> +wpi::math::DARE<2, 1>(const Eigen::Matrix& A, const Eigen::Matrix& B, const Eigen::Matrix& Q, const Eigen::Matrix& R, bool checkPreconditions); -template wpi::expected, frc::DAREError> -frc::DARE<2, 1>(const Eigen::Matrix& A, +template wpi::util::expected, wpi::math::DAREError> +wpi::math::DARE<2, 1>(const Eigen::Matrix& A, const Eigen::Matrix& B, const Eigen::Matrix& Q, const Eigen::Matrix& R, diff --git a/wpimath/src/test/native/cpp/DARETest_Inst_2x2.cpp b/wpimath/src/test/native/cpp/DARETest_Inst_2x2.cpp index 097f3be2cc..d881aec6ec 100644 --- a/wpimath/src/test/native/cpp/DARETest_Inst_2x2.cpp +++ b/wpimath/src/test/native/cpp/DARETest_Inst_2x2.cpp @@ -4,13 +4,13 @@ #include "wpi/math/linalg/DARE.hpp" -template wpi::expected, frc::DAREError> -frc::DARE<2, 2>(const Eigen::Matrix& A, +template wpi::util::expected, wpi::math::DAREError> +wpi::math::DARE<2, 2>(const Eigen::Matrix& A, const Eigen::Matrix& B, const Eigen::Matrix& Q, const Eigen::Matrix& R, bool checkPreconditions); -template wpi::expected, frc::DAREError> -frc::DARE<2, 2>(const Eigen::Matrix& A, +template wpi::util::expected, wpi::math::DAREError> +wpi::math::DARE<2, 2>(const Eigen::Matrix& A, const Eigen::Matrix& B, const Eigen::Matrix& Q, const Eigen::Matrix& R, diff --git a/wpimath/src/test/native/cpp/DARETest_Inst_2x3.cpp b/wpimath/src/test/native/cpp/DARETest_Inst_2x3.cpp index c2ea60250a..0a23f782b2 100644 --- a/wpimath/src/test/native/cpp/DARETest_Inst_2x3.cpp +++ b/wpimath/src/test/native/cpp/DARETest_Inst_2x3.cpp @@ -4,13 +4,13 @@ #include "wpi/math/linalg/DARE.hpp" -template wpi::expected, frc::DAREError> -frc::DARE<2, 3>(const Eigen::Matrix& A, +template wpi::util::expected, wpi::math::DAREError> +wpi::math::DARE<2, 3>(const Eigen::Matrix& A, const Eigen::Matrix& B, const Eigen::Matrix& Q, const Eigen::Matrix& R, bool checkPreconditions); -template wpi::expected, frc::DAREError> -frc::DARE<2, 3>(const Eigen::Matrix& A, +template wpi::util::expected, wpi::math::DAREError> +wpi::math::DARE<2, 3>(const Eigen::Matrix& A, const Eigen::Matrix& B, const Eigen::Matrix& Q, const Eigen::Matrix& R, diff --git a/wpimath/src/test/native/cpp/DARETest_Inst_4x1.cpp b/wpimath/src/test/native/cpp/DARETest_Inst_4x1.cpp index 5fa1ab1e7d..54e0d1ebf6 100644 --- a/wpimath/src/test/native/cpp/DARETest_Inst_4x1.cpp +++ b/wpimath/src/test/native/cpp/DARETest_Inst_4x1.cpp @@ -5,13 +5,13 @@ #include "wpi/math/linalg/DARE.hpp" #include "wpi/util/expected" -template wpi::expected, frc::DAREError> -frc::DARE<4, 1>(const Eigen::Matrix& A, +template wpi::util::expected, wpi::math::DAREError> +wpi::math::DARE<4, 1>(const Eigen::Matrix& A, const Eigen::Matrix& B, const Eigen::Matrix& Q, const Eigen::Matrix& R, bool checkPreconditions); -template wpi::expected, frc::DAREError> -frc::DARE<4, 1>(const Eigen::Matrix& A, +template wpi::util::expected, wpi::math::DAREError> +wpi::math::DARE<4, 1>(const Eigen::Matrix& A, const Eigen::Matrix& B, const Eigen::Matrix& Q, const Eigen::Matrix& R, diff --git a/wpimath/src/test/native/cpp/EigenTest.cpp b/wpimath/src/test/native/cpp/EigenTest.cpp index 15644545e0..998c1d076b 100644 --- a/wpimath/src/test/native/cpp/EigenTest.cpp +++ b/wpimath/src/test/native/cpp/EigenTest.cpp @@ -8,22 +8,22 @@ #include "wpi/math/linalg/EigenCore.hpp" TEST(EigenTest, Multiplication) { - frc::Matrixd<2, 2> m1{{2, 1}, {0, 1}}; - frc::Matrixd<2, 2> m2{{3, 0}, {0, 2.5}}; + wpi::math::Matrixd<2, 2> m1{{2, 1}, {0, 1}}; + wpi::math::Matrixd<2, 2> m2{{3, 0}, {0, 2.5}}; const auto result = m1 * m2; - frc::Matrixd<2, 2> expectedResult{{6.0, 2.5}, {0.0, 2.5}}; + wpi::math::Matrixd<2, 2> expectedResult{{6.0, 2.5}, {0.0, 2.5}}; EXPECT_TRUE(expectedResult.isApprox(result)); - frc::Matrixd<2, 3> m3{{1.0, 3.0, 0.5}, {2.0, 4.3, 1.2}}; - frc::Matrixd<3, 4> m4{ + wpi::math::Matrixd<2, 3> m3{{1.0, 3.0, 0.5}, {2.0, 4.3, 1.2}}; + wpi::math::Matrixd<3, 4> m4{ {3.0, 1.5, 2.0, 4.5}, {2.3, 1.0, 1.6, 3.1}, {5.2, 2.1, 2.0, 1.0}}; const auto result2 = m3 * m4; - frc::Matrixd<2, 4> expectedResult2{{12.5, 5.55, 7.8, 14.3}, + wpi::math::Matrixd<2, 4> expectedResult2{{12.5, 5.55, 7.8, 14.3}, {22.13, 9.82, 13.28, 23.53}}; EXPECT_TRUE(expectedResult2.isApprox(result2)); diff --git a/wpimath/src/test/native/cpp/MathUtilTest.cpp b/wpimath/src/test/native/cpp/MathUtilTest.cpp index f87dc991e6..d3fe98dc9f 100644 --- a/wpimath/src/test/native/cpp/MathUtilTest.cpp +++ b/wpimath/src/test/native/cpp/MathUtilTest.cpp @@ -21,256 +21,256 @@ TEST(MathUtilTest, ApplyDeadbandUnityScale) { // < 0 - EXPECT_DOUBLE_EQ(-1.0, frc::ApplyDeadband(-1.0, 0.02)); + EXPECT_DOUBLE_EQ(-1.0, wpi::math::ApplyDeadband(-1.0, 0.02)); EXPECT_DOUBLE_EQ((-0.03 + 0.02) / (1.0 - 0.02), - frc::ApplyDeadband(-0.03, 0.02)); - EXPECT_DOUBLE_EQ(0.0, frc::ApplyDeadband(-0.02, 0.02)); - EXPECT_DOUBLE_EQ(0.0, frc::ApplyDeadband(-0.01, 0.02)); + wpi::math::ApplyDeadband(-0.03, 0.02)); + EXPECT_DOUBLE_EQ(0.0, wpi::math::ApplyDeadband(-0.02, 0.02)); + EXPECT_DOUBLE_EQ(0.0, wpi::math::ApplyDeadband(-0.01, 0.02)); // == 0 - EXPECT_DOUBLE_EQ(0.0, frc::ApplyDeadband(0.0, 0.02)); + EXPECT_DOUBLE_EQ(0.0, wpi::math::ApplyDeadband(0.0, 0.02)); // > 0 - EXPECT_DOUBLE_EQ(0.0, frc::ApplyDeadband(0.01, 0.02)); - EXPECT_DOUBLE_EQ(0.0, frc::ApplyDeadband(0.02, 0.02)); + EXPECT_DOUBLE_EQ(0.0, wpi::math::ApplyDeadband(0.01, 0.02)); + EXPECT_DOUBLE_EQ(0.0, wpi::math::ApplyDeadband(0.02, 0.02)); EXPECT_DOUBLE_EQ((0.03 - 0.02) / (1.0 - 0.02), - frc::ApplyDeadband(0.03, 0.02)); - EXPECT_DOUBLE_EQ(1.0, frc::ApplyDeadband(1.0, 0.02)); + wpi::math::ApplyDeadband(0.03, 0.02)); + EXPECT_DOUBLE_EQ(1.0, wpi::math::ApplyDeadband(1.0, 0.02)); } TEST(MathUtilTest, ApplyDeadbandArbitraryScale) { // < 0 - EXPECT_DOUBLE_EQ(-2.5, frc::ApplyDeadband(-2.5, 0.02, 2.5)); - EXPECT_DOUBLE_EQ(0.0, frc::ApplyDeadband(-0.02, 0.02, 2.5)); - EXPECT_DOUBLE_EQ(0.0, frc::ApplyDeadband(-0.01, 0.02, 2.5)); + EXPECT_DOUBLE_EQ(-2.5, wpi::math::ApplyDeadband(-2.5, 0.02, 2.5)); + EXPECT_DOUBLE_EQ(0.0, wpi::math::ApplyDeadband(-0.02, 0.02, 2.5)); + EXPECT_DOUBLE_EQ(0.0, wpi::math::ApplyDeadband(-0.01, 0.02, 2.5)); // == 0 - EXPECT_DOUBLE_EQ(0.0, frc::ApplyDeadband(0.0, 0.02, 2.5)); + EXPECT_DOUBLE_EQ(0.0, wpi::math::ApplyDeadband(0.0, 0.02, 2.5)); // > 0 - EXPECT_DOUBLE_EQ(0.0, frc::ApplyDeadband(0.01, 0.02, 2.5)); - EXPECT_DOUBLE_EQ(0.0, frc::ApplyDeadband(0.02, 0.02, 2.5)); - EXPECT_DOUBLE_EQ(2.5, frc::ApplyDeadband(2.5, 0.02, 2.5)); + EXPECT_DOUBLE_EQ(0.0, wpi::math::ApplyDeadband(0.01, 0.02, 2.5)); + EXPECT_DOUBLE_EQ(0.0, wpi::math::ApplyDeadband(0.02, 0.02, 2.5)); + EXPECT_DOUBLE_EQ(2.5, wpi::math::ApplyDeadband(2.5, 0.02, 2.5)); } TEST(MathUtilTest, ApplyDeadbandUnits) { // < 0 EXPECT_UNITS_EQ(-20_rad, - frc::ApplyDeadband(-20_rad, 1_rad, 20_rad)); + wpi::math::ApplyDeadband(-20_rad, 1_rad, 20_rad)); } TEST(MathUtilTest, ApplyDeadbandLargeMaxMagnitude) { EXPECT_DOUBLE_EQ( 80.0, - frc::ApplyDeadband(100.0, 20.0, std::numeric_limits::infinity())); + wpi::math::ApplyDeadband(100.0, 20.0, std::numeric_limits::infinity())); } TEST(MathUtilTest, ApplyDeadband2dUnityScale) { EXPECT_EQ((Eigen::Vector2d{{0.0}, {1.0}}), - frc::ApplyDeadband(Eigen::Vector2d{{0.0}, {1.0}}, 0.02)); + wpi::math::ApplyDeadband(Eigen::Vector2d{{0.0}, {1.0}}, 0.02)); EXPECT_EQ((Eigen::Vector2d{{0.0}, {-1.0}}), - frc::ApplyDeadband(Eigen::Vector2d{{0.0}, {-1.0}}, 0.02)); + wpi::math::ApplyDeadband(Eigen::Vector2d{{0.0}, {-1.0}}, 0.02)); EXPECT_EQ((Eigen::Vector2d{{-1.0}, {0.0}}), - frc::ApplyDeadband(Eigen::Vector2d{{-1.0}, {0.0}}, 0.02)); + wpi::math::ApplyDeadband(Eigen::Vector2d{{-1.0}, {0.0}}, 0.02)); // == 0 EXPECT_EQ((Eigen::Vector2d{{0.0}, {0.0}}), - frc::ApplyDeadband(Eigen::Vector2d{{0.0}, {0.0}}, 0.02)); + wpi::math::ApplyDeadband(Eigen::Vector2d{{0.0}, {0.0}}, 0.02)); // > 0 EXPECT_EQ((Eigen::Vector2d{{0.0}, {0.0}}), - frc::ApplyDeadband(Eigen::Vector2d{{0.01}, {0.0}}, 0.02)); + wpi::math::ApplyDeadband(Eigen::Vector2d{{0.01}, {0.0}}, 0.02)); EXPECT_EQ((Eigen::Vector2d{{0.0}, {0.0}}), - frc::ApplyDeadband(Eigen::Vector2d{{0.02}, {0.0}}, 0.02)); + wpi::math::ApplyDeadband(Eigen::Vector2d{{0.02}, {0.0}}, 0.02)); EXPECT_EQ((Eigen::Vector2d{{(0.03 - 0.02) / (1.0 - 0.02)}, {0.0}}), - frc::ApplyDeadband(Eigen::Vector2d{{0.03}, {0.0}}, 0.02)); + wpi::math::ApplyDeadband(Eigen::Vector2d{{0.03}, {0.0}}, 0.02)); EXPECT_EQ((Eigen::Vector2d{{1.0}, {0.0}}), - frc::ApplyDeadband(Eigen::Vector2d{{1.0}, {0.0}}, 0.02)); + wpi::math::ApplyDeadband(Eigen::Vector2d{{1.0}, {0.0}}, 0.02)); } TEST(MathUtilTest, ApplyDeadband2dArbitraryScale) { EXPECT_EQ((Eigen::Vector2d{{0.0}, {2.5}}), - frc::ApplyDeadband(Eigen::Vector2d{{0.0}, {2.5}}, 0.02, 2.5)); + wpi::math::ApplyDeadband(Eigen::Vector2d{{0.0}, {2.5}}, 0.02, 2.5)); EXPECT_EQ((Eigen::Vector2d{{0.0}, {-2.5}}), - frc::ApplyDeadband(Eigen::Vector2d{{0.0}, {-2.5}}, 0.02, 2.5)); + wpi::math::ApplyDeadband(Eigen::Vector2d{{0.0}, {-2.5}}, 0.02, 2.5)); EXPECT_EQ((Eigen::Vector2d{{-2.5}, {0.0}}), - frc::ApplyDeadband(Eigen::Vector2d{{-2.5}, {0.0}}, 0.02, 2.5)); + wpi::math::ApplyDeadband(Eigen::Vector2d{{-2.5}, {0.0}}, 0.02, 2.5)); // == 0 EXPECT_EQ((Eigen::Vector2d{{0.0}, {0.0}}), - frc::ApplyDeadband(Eigen::Vector2d{{0.0}, {0.0}}, 0.02, 2.5)); + wpi::math::ApplyDeadband(Eigen::Vector2d{{0.0}, {0.0}}, 0.02, 2.5)); // > 0 EXPECT_EQ((Eigen::Vector2d{{0.0}, {0.0}}), - frc::ApplyDeadband(Eigen::Vector2d{{0.01}, {0.0}}, 0.02, 2.5)); + wpi::math::ApplyDeadband(Eigen::Vector2d{{0.01}, {0.0}}, 0.02, 2.5)); EXPECT_EQ((Eigen::Vector2d{{0.0}, {0.0}}), - frc::ApplyDeadband(Eigen::Vector2d{{0.02}, {0.0}}, 0.02, 2.5)); + wpi::math::ApplyDeadband(Eigen::Vector2d{{0.02}, {0.0}}, 0.02, 2.5)); EXPECT_EQ((Eigen::Vector2d{{2.5}, {0.0}}), - frc::ApplyDeadband(Eigen::Vector2d{{2.5}, {0.0}}, 0.02, 2.5)); + wpi::math::ApplyDeadband(Eigen::Vector2d{{2.5}, {0.0}}, 0.02, 2.5)); } TEST(MathUtilTest, ApplyDeadband2dLargeMaxMagnitude) { EXPECT_EQ((Eigen::Vector2d{{80.0}, {0.0}}), - (frc::ApplyDeadband(Eigen::Vector2d{{100.0}, {0.0}}, 20.0, + (wpi::math::ApplyDeadband(Eigen::Vector2d{{100.0}, {0.0}}, 20.0, std::numeric_limits::infinity()))); } TEST(MathUtilTest, ApplyDeadband2dUnits) { - EXPECT_EQ((Eigen::Vector{0_mps, 2.5_mps}), - frc::ApplyDeadband( - Eigen::Vector{0_mps, 2.5_mps}, + EXPECT_EQ((Eigen::Vector{0_mps, 2.5_mps}), + wpi::math::ApplyDeadband( + Eigen::Vector{0_mps, 2.5_mps}, 0.02_mps, 2.5_mps)); - EXPECT_EQ((Eigen::Vector{1_mps, 0_mps}), - frc::ApplyDeadband( - Eigen::Vector{1_mps, 0_mps}, + EXPECT_EQ((Eigen::Vector{1_mps, 0_mps}), + wpi::math::ApplyDeadband( + Eigen::Vector{1_mps, 0_mps}, 0.02_mps)); - EXPECT_EQ((Eigen::Vector{0_mps, 0_mps}), - frc::ApplyDeadband( - Eigen::Vector{0_mps, 0_mps}, + EXPECT_EQ((Eigen::Vector{0_mps, 0_mps}), + wpi::math::ApplyDeadband( + Eigen::Vector{0_mps, 0_mps}, 0.02_mps, 2.5_mps)); } TEST(MathUtilTest, CopyDirectionPow) { - EXPECT_DOUBLE_EQ(0.5, frc::CopyDirectionPow(0.5, 1.0)); - EXPECT_DOUBLE_EQ(-0.5, frc::CopyDirectionPow(-0.5, 1.0)); + EXPECT_DOUBLE_EQ(0.5, wpi::math::CopyDirectionPow(0.5, 1.0)); + EXPECT_DOUBLE_EQ(-0.5, wpi::math::CopyDirectionPow(-0.5, 1.0)); - EXPECT_DOUBLE_EQ(0.5 * 0.5, frc::CopyDirectionPow(0.5, 2.0)); - EXPECT_DOUBLE_EQ(-(0.5 * 0.5), frc::CopyDirectionPow(-0.5, 2.0)); + EXPECT_DOUBLE_EQ(0.5 * 0.5, wpi::math::CopyDirectionPow(0.5, 2.0)); + EXPECT_DOUBLE_EQ(-(0.5 * 0.5), wpi::math::CopyDirectionPow(-0.5, 2.0)); - EXPECT_DOUBLE_EQ(std::sqrt(0.5), frc::CopyDirectionPow(0.5, 0.5)); - EXPECT_DOUBLE_EQ(-std::sqrt(0.5), frc::CopyDirectionPow(-0.5, 0.5)); + EXPECT_DOUBLE_EQ(std::sqrt(0.5), wpi::math::CopyDirectionPow(0.5, 0.5)); + EXPECT_DOUBLE_EQ(-std::sqrt(0.5), wpi::math::CopyDirectionPow(-0.5, 0.5)); - EXPECT_DOUBLE_EQ(0.0, frc::CopyDirectionPow(0.0, 2.0)); - EXPECT_DOUBLE_EQ(1.0, frc::CopyDirectionPow(1.0, 2.0)); - EXPECT_DOUBLE_EQ(-1.0, frc::CopyDirectionPow(-1.0, 2.0)); + EXPECT_DOUBLE_EQ(0.0, wpi::math::CopyDirectionPow(0.0, 2.0)); + EXPECT_DOUBLE_EQ(1.0, wpi::math::CopyDirectionPow(1.0, 2.0)); + EXPECT_DOUBLE_EQ(-1.0, wpi::math::CopyDirectionPow(-1.0, 2.0)); - EXPECT_DOUBLE_EQ(std::pow(0.8, 0.3), frc::CopyDirectionPow(0.8, 0.3)); - EXPECT_DOUBLE_EQ(-std::pow(0.8, 0.3), frc::CopyDirectionPow(-0.8, 0.3)); + EXPECT_DOUBLE_EQ(std::pow(0.8, 0.3), wpi::math::CopyDirectionPow(0.8, 0.3)); + EXPECT_DOUBLE_EQ(-std::pow(0.8, 0.3), wpi::math::CopyDirectionPow(-0.8, 0.3)); } TEST(MathUtilTest, CopyDirectionPowWithMaxMagnitude) { - EXPECT_DOUBLE_EQ(5.0, frc::CopyDirectionPow(5.0, 1.0, 10.0)); - EXPECT_DOUBLE_EQ(-5.0, frc::CopyDirectionPow(-5.0, 1.0, 10.0)); + EXPECT_DOUBLE_EQ(5.0, wpi::math::CopyDirectionPow(5.0, 1.0, 10.0)); + EXPECT_DOUBLE_EQ(-5.0, wpi::math::CopyDirectionPow(-5.0, 1.0, 10.0)); - EXPECT_DOUBLE_EQ(0.5 * 0.5 * 10, frc::CopyDirectionPow(5.0, 2.0, 10.0)); - EXPECT_DOUBLE_EQ(-0.5 * 0.5 * 10, frc::CopyDirectionPow(-5.0, 2.0, 10.0)); + EXPECT_DOUBLE_EQ(0.5 * 0.5 * 10, wpi::math::CopyDirectionPow(5.0, 2.0, 10.0)); + EXPECT_DOUBLE_EQ(-0.5 * 0.5 * 10, wpi::math::CopyDirectionPow(-5.0, 2.0, 10.0)); - EXPECT_DOUBLE_EQ(std::sqrt(0.5) * 10, frc::CopyDirectionPow(5.0, 0.5, 10.0)); + EXPECT_DOUBLE_EQ(std::sqrt(0.5) * 10, wpi::math::CopyDirectionPow(5.0, 0.5, 10.0)); EXPECT_DOUBLE_EQ(-std::sqrt(0.5) * 10, - frc::CopyDirectionPow(-5.0, 0.5, 10.0)); + wpi::math::CopyDirectionPow(-5.0, 0.5, 10.0)); - EXPECT_DOUBLE_EQ(0.0, frc::CopyDirectionPow(0.0, 2.0, 5.0)); - EXPECT_DOUBLE_EQ(5.0, frc::CopyDirectionPow(5.0, 2.0, 5.0)); - EXPECT_DOUBLE_EQ(-5.0, frc::CopyDirectionPow(-5.0, 2.0, 5.0)); + EXPECT_DOUBLE_EQ(0.0, wpi::math::CopyDirectionPow(0.0, 2.0, 5.0)); + EXPECT_DOUBLE_EQ(5.0, wpi::math::CopyDirectionPow(5.0, 2.0, 5.0)); + EXPECT_DOUBLE_EQ(-5.0, wpi::math::CopyDirectionPow(-5.0, 2.0, 5.0)); EXPECT_DOUBLE_EQ(std::pow(0.8, 0.3) * 100, - frc::CopyDirectionPow(80.0, 0.3, 100.0)); + wpi::math::CopyDirectionPow(80.0, 0.3, 100.0)); EXPECT_DOUBLE_EQ(-std::pow(0.8, 0.3) * 100, - frc::CopyDirectionPow(-80.0, 0.3, 100.0)); + wpi::math::CopyDirectionPow(-80.0, 0.3, 100.0)); } TEST(MathUtilTest, CopyDirectionPowWithUnits) { EXPECT_UNITS_EQ( - 0_mps, frc::CopyDirectionPow(0_mps, 2.0)); + 0_mps, wpi::math::CopyDirectionPow(0_mps, 2.0)); EXPECT_UNITS_EQ( - 1_mps, frc::CopyDirectionPow(1_mps, 2.0)); + 1_mps, wpi::math::CopyDirectionPow(1_mps, 2.0)); EXPECT_UNITS_EQ( - -1_mps, frc::CopyDirectionPow(-1_mps, 2.0)); + -1_mps, wpi::math::CopyDirectionPow(-1_mps, 2.0)); EXPECT_UNITS_EQ( - units::meters_per_second_t{0.5 * 0.5 * 10}, - frc::CopyDirectionPow(5_mps, 2.0, 10_mps)); + wpi::units::meters_per_second_t{0.5 * 0.5 * 10}, + wpi::math::CopyDirectionPow(5_mps, 2.0, 10_mps)); EXPECT_UNITS_EQ( - units::meters_per_second_t{-0.5 * 0.5 * 10}, - frc::CopyDirectionPow(-5_mps, 2.0, 10_mps)); + wpi::units::meters_per_second_t{-0.5 * 0.5 * 10}, + wpi::math::CopyDirectionPow(-5_mps, 2.0, 10_mps)); } TEST(MathUtilTest, CopyDirectionPow2d) { EXPECT_EQ((Eigen::Vector2d{{0.5}, {0.0}}), - frc::CopyDirectionPow(Eigen::Vector2d{{0.5}, {0.0}}, 1.0)); + wpi::math::CopyDirectionPow(Eigen::Vector2d{{0.5}, {0.0}}, 1.0)); EXPECT_EQ((Eigen::Vector2d{{-0.5}, {0.0}}), - frc::CopyDirectionPow(Eigen::Vector2d{{-0.5}, {0.0}}, 1.0)); + wpi::math::CopyDirectionPow(Eigen::Vector2d{{-0.5}, {0.0}}, 1.0)); EXPECT_EQ((Eigen::Vector2d{{0.25}, {0.0}}), - frc::CopyDirectionPow(Eigen::Vector2d{{0.5}, {0.0}}, 2.0)); + wpi::math::CopyDirectionPow(Eigen::Vector2d{{0.5}, {0.0}}, 2.0)); EXPECT_EQ((Eigen::Vector2d{{-0.25}, {0.0}}), - frc::CopyDirectionPow(Eigen::Vector2d{{-0.5}, {0.0}}, 2.0)); + wpi::math::CopyDirectionPow(Eigen::Vector2d{{-0.5}, {0.0}}, 2.0)); EXPECT_EQ((Eigen::Vector2d{{std::sqrt(0.5)}, {0.0}}), - frc::CopyDirectionPow(Eigen::Vector2d{{0.5}, {0.0}}, 0.5)); + wpi::math::CopyDirectionPow(Eigen::Vector2d{{0.5}, {0.0}}, 0.5)); EXPECT_EQ((Eigen::Vector2d{{-std::sqrt(0.5)}, {0.0}}), - frc::CopyDirectionPow(Eigen::Vector2d{{-0.5}, {0.0}}, 0.5)); + wpi::math::CopyDirectionPow(Eigen::Vector2d{{-0.5}, {0.0}}, 0.5)); EXPECT_EQ((Eigen::Vector2d{{0.0}, {0.0}}), - frc::CopyDirectionPow(Eigen::Vector2d{{0.0}, {0.0}}, 2.0)); + wpi::math::CopyDirectionPow(Eigen::Vector2d{{0.0}, {0.0}}, 2.0)); EXPECT_EQ((Eigen::Vector2d{{1.0}, {0.0}}), - frc::CopyDirectionPow(Eigen::Vector2d{{1.0}, {0.0}}, 2.0)); + wpi::math::CopyDirectionPow(Eigen::Vector2d{{1.0}, {0.0}}, 2.0)); EXPECT_EQ((Eigen::Vector2d{{-1.0}, {0.0}}), - frc::CopyDirectionPow(Eigen::Vector2d{{-1.0}, {0.0}}, 2.0)); + wpi::math::CopyDirectionPow(Eigen::Vector2d{{-1.0}, {0.0}}, 2.0)); EXPECT_EQ((Eigen::Vector2d{{0.0}, {1.0}}), - frc::CopyDirectionPow(Eigen::Vector2d{{0.0}, {1.0}}, 2.0)); + wpi::math::CopyDirectionPow(Eigen::Vector2d{{0.0}, {1.0}}, 2.0)); EXPECT_EQ((Eigen::Vector2d{{0.0}, {-1.0}}), - frc::CopyDirectionPow(Eigen::Vector2d{{0.0}, {-1.0}}, 2.0)); + wpi::math::CopyDirectionPow(Eigen::Vector2d{{0.0}, {-1.0}}, 2.0)); EXPECT_EQ((Eigen::Vector2d{{0.0}, {std::pow(0.8, 0.3)}}), - frc::CopyDirectionPow(Eigen::Vector2d{{0.0}, {0.8}}, 0.3)); + wpi::math::CopyDirectionPow(Eigen::Vector2d{{0.0}, {0.8}}, 0.3)); EXPECT_EQ((Eigen::Vector2d{{0.0}, {-std::pow(0.8, 0.3)}}), - frc::CopyDirectionPow(Eigen::Vector2d{{0.0}, {-0.8}}, 0.3)); + wpi::math::CopyDirectionPow(Eigen::Vector2d{{0.0}, {-0.8}}, 0.3)); } TEST(MathUtilTest, CopyDirectionPow2dMaxDistance) { EXPECT_EQ((Eigen::Vector2d{{5.0}, {0.0}}), - frc::CopyDirectionPow(Eigen::Vector2d{{5.0}, {0.0}}, 1.0, 10.0)); + wpi::math::CopyDirectionPow(Eigen::Vector2d{{5.0}, {0.0}}, 1.0, 10.0)); EXPECT_EQ((Eigen::Vector2d{{-5.0}, {0.0}}), - frc::CopyDirectionPow(Eigen::Vector2d{{-5.0}, {0.0}}, 1.0, 10.0)); + wpi::math::CopyDirectionPow(Eigen::Vector2d{{-5.0}, {0.0}}, 1.0, 10.0)); EXPECT_EQ((Eigen::Vector2d{{2.5}, {0.0}}), - frc::CopyDirectionPow(Eigen::Vector2d{{5.0}, {0.0}}, 2.0, 10.0)); + wpi::math::CopyDirectionPow(Eigen::Vector2d{{5.0}, {0.0}}, 2.0, 10.0)); EXPECT_EQ((Eigen::Vector2d{{-2.5}, {0.0}}), - frc::CopyDirectionPow(Eigen::Vector2d{{-5.0}, {0.0}}, 2.0, 10.0)); + wpi::math::CopyDirectionPow(Eigen::Vector2d{{-5.0}, {0.0}}, 2.0, 10.0)); EXPECT_EQ((Eigen::Vector2d{{std::sqrt(0.5) * 10.0}, {0.0}}), - frc::CopyDirectionPow(Eigen::Vector2d{{5.0}, {0.0}}, 0.5, 10.0)); + wpi::math::CopyDirectionPow(Eigen::Vector2d{{5.0}, {0.0}}, 0.5, 10.0)); EXPECT_EQ((Eigen::Vector2d{{-std::sqrt(0.5) * 10.0}, {0.0}}), - frc::CopyDirectionPow(Eigen::Vector2d{{-5.0}, {0.0}}, 0.5, 10.0)); + wpi::math::CopyDirectionPow(Eigen::Vector2d{{-5.0}, {0.0}}, 0.5, 10.0)); EXPECT_EQ((Eigen::Vector2d{{0.0}, {0.0}}), - frc::CopyDirectionPow(Eigen::Vector2d{{0.0}, {0.0}}, 2.0, 5.0)); + wpi::math::CopyDirectionPow(Eigen::Vector2d{{0.0}, {0.0}}, 2.0, 5.0)); EXPECT_EQ((Eigen::Vector2d{{5.0}, {0.0}}), - frc::CopyDirectionPow(Eigen::Vector2d{{5.0}, {0.0}}, 2.0, 5.0)); + wpi::math::CopyDirectionPow(Eigen::Vector2d{{5.0}, {0.0}}, 2.0, 5.0)); EXPECT_EQ((Eigen::Vector2d{{-5.0}, {0.0}}), - frc::CopyDirectionPow(Eigen::Vector2d{{-5.0}, {0.0}}, 2.0, 5.0)); + wpi::math::CopyDirectionPow(Eigen::Vector2d{{-5.0}, {0.0}}, 2.0, 5.0)); EXPECT_EQ((Eigen::Vector2d{{0.0}, {std::pow(0.8, 0.3) * 100.0}}), - frc::CopyDirectionPow(Eigen::Vector2d{{0.0}, {80.0}}, 0.3, 100.0)); + wpi::math::CopyDirectionPow(Eigen::Vector2d{{0.0}, {80.0}}, 0.3, 100.0)); EXPECT_EQ((Eigen::Vector2d{{0.0}, {-std::pow(0.8, 0.3) * 100.0}}), - frc::CopyDirectionPow(Eigen::Vector2d{{0.0}, {-80.0}}, 0.3, 100.0)); + wpi::math::CopyDirectionPow(Eigen::Vector2d{{0.0}, {-80.0}}, 0.3, 100.0)); } TEST(MathUtilTest, CopyDirectionPow2dUnits) { EXPECT_EQ( - (Eigen::Vector{1_mps, 0_mps}), - frc::CopyDirectionPow( - Eigen::Vector{1_mps, 0_mps}, 2.0)); + (Eigen::Vector{1_mps, 0_mps}), + wpi::math::CopyDirectionPow( + Eigen::Vector{1_mps, 0_mps}, 2.0)); EXPECT_EQ( - (Eigen::Vector{-1_mps, 0_mps}), - frc::CopyDirectionPow( - Eigen::Vector{-1_mps, 0_mps}, 2.0)); + (Eigen::Vector{-1_mps, 0_mps}), + wpi::math::CopyDirectionPow( + Eigen::Vector{-1_mps, 0_mps}, 2.0)); - EXPECT_EQ((Eigen::Vector{0_mps, 0_mps}), - frc::CopyDirectionPow( - Eigen::Vector{0_mps, 0_mps}, 2.0, + EXPECT_EQ((Eigen::Vector{0_mps, 0_mps}), + wpi::math::CopyDirectionPow( + Eigen::Vector{0_mps, 0_mps}, 2.0, 5_mps)); - EXPECT_EQ((Eigen::Vector{5_mps, 0_mps}), - frc::CopyDirectionPow( - Eigen::Vector{5_mps, 0_mps}, 2.0, + EXPECT_EQ((Eigen::Vector{5_mps, 0_mps}), + wpi::math::CopyDirectionPow( + Eigen::Vector{5_mps, 0_mps}, 2.0, 5_mps)); - EXPECT_EQ((Eigen::Vector{-5_mps, 0_mps}), - frc::CopyDirectionPow( - Eigen::Vector{-5_mps, 0_mps}, + EXPECT_EQ((Eigen::Vector{-5_mps, 0_mps}), + wpi::math::CopyDirectionPow( + Eigen::Vector{-5_mps, 0_mps}, 2.0, 5_mps)); } @@ -279,156 +279,156 @@ TEST(MathUtilTest, InputModulus) { // result of an angle reference minus the measurement. // Test symmetric range - EXPECT_DOUBLE_EQ(-20.0, frc::InputModulus(170.0 - (-170.0), -180.0, 180.0)); + EXPECT_DOUBLE_EQ(-20.0, wpi::math::InputModulus(170.0 - (-170.0), -180.0, 180.0)); EXPECT_DOUBLE_EQ(-20.0, - frc::InputModulus(170.0 + 360.0 - (-170.0), -180.0, 180.0)); + wpi::math::InputModulus(170.0 + 360.0 - (-170.0), -180.0, 180.0)); EXPECT_DOUBLE_EQ(-20.0, - frc::InputModulus(170.0 - (-170.0 + 360.0), -180.0, 180.0)); - EXPECT_DOUBLE_EQ(20.0, frc::InputModulus(-170.0 - 170.0, -180.0, 180.0)); + wpi::math::InputModulus(170.0 - (-170.0 + 360.0), -180.0, 180.0)); + EXPECT_DOUBLE_EQ(20.0, wpi::math::InputModulus(-170.0 - 170.0, -180.0, 180.0)); EXPECT_DOUBLE_EQ(20.0, - frc::InputModulus(-170.0 + 360.0 - 170.0, -180.0, 180.0)); + wpi::math::InputModulus(-170.0 + 360.0 - 170.0, -180.0, 180.0)); EXPECT_DOUBLE_EQ(20.0, - frc::InputModulus(-170.0 - (170.0 + 360.0), -180.0, 180.0)); + wpi::math::InputModulus(-170.0 - (170.0 + 360.0), -180.0, 180.0)); // Test range starting at zero - EXPECT_DOUBLE_EQ(340.0, frc::InputModulus(170.0 - 190.0, 0.0, 360.0)); - EXPECT_DOUBLE_EQ(340.0, frc::InputModulus(170.0 + 360.0 - 190.0, 0.0, 360.0)); + EXPECT_DOUBLE_EQ(340.0, wpi::math::InputModulus(170.0 - 190.0, 0.0, 360.0)); + EXPECT_DOUBLE_EQ(340.0, wpi::math::InputModulus(170.0 + 360.0 - 190.0, 0.0, 360.0)); EXPECT_DOUBLE_EQ(340.0, - frc::InputModulus(170.0 - (190.0 + 360.0), 0.0, 360.0)); + wpi::math::InputModulus(170.0 - (190.0 + 360.0), 0.0, 360.0)); // Test asymmetric range that doesn't start at zero - EXPECT_DOUBLE_EQ(-20.0, frc::InputModulus(170.0 - (-170.0), -170.0, 190.0)); + EXPECT_DOUBLE_EQ(-20.0, wpi::math::InputModulus(170.0 - (-170.0), -170.0, 190.0)); // Test range with both positive endpoints - EXPECT_DOUBLE_EQ(2.0, frc::InputModulus(0.0, 1.0, 3.0)); - EXPECT_DOUBLE_EQ(3.0, frc::InputModulus(1.0, 1.0, 3.0)); - EXPECT_DOUBLE_EQ(2.0, frc::InputModulus(2.0, 1.0, 3.0)); - EXPECT_DOUBLE_EQ(3.0, frc::InputModulus(3.0, 1.0, 3.0)); - EXPECT_DOUBLE_EQ(2.0, frc::InputModulus(4.0, 1.0, 3.0)); + EXPECT_DOUBLE_EQ(2.0, wpi::math::InputModulus(0.0, 1.0, 3.0)); + EXPECT_DOUBLE_EQ(3.0, wpi::math::InputModulus(1.0, 1.0, 3.0)); + EXPECT_DOUBLE_EQ(2.0, wpi::math::InputModulus(2.0, 1.0, 3.0)); + EXPECT_DOUBLE_EQ(3.0, wpi::math::InputModulus(3.0, 1.0, 3.0)); + EXPECT_DOUBLE_EQ(2.0, wpi::math::InputModulus(4.0, 1.0, 3.0)); // Test all supported types EXPECT_DOUBLE_EQ(-20.0, - frc::InputModulus(170.0 - (-170.0), -170.0, 190.0)); - EXPECT_EQ(-20, frc::InputModulus(170 - (-170), -170, 190)); - EXPECT_EQ(-20_deg, frc::InputModulus(170_deg - (-170_deg), + wpi::math::InputModulus(170.0 - (-170.0), -170.0, 190.0)); + EXPECT_EQ(-20, wpi::math::InputModulus(170 - (-170), -170, 190)); + EXPECT_EQ(-20_deg, wpi::math::InputModulus(170_deg - (-170_deg), -170_deg, 190_deg)); } TEST(MathUtilTest, AngleModulus) { EXPECT_UNITS_NEAR( - frc::AngleModulus(units::radian_t{-2000 * std::numbers::pi / 180}), - units::radian_t{160 * std::numbers::pi / 180}, 1e-10); + wpi::math::AngleModulus(wpi::units::radian_t{-2000 * std::numbers::pi / 180}), + wpi::units::radian_t{160 * std::numbers::pi / 180}, 1e-10); EXPECT_UNITS_NEAR( - frc::AngleModulus(units::radian_t{358 * std::numbers::pi / 180}), - units::radian_t{-2 * std::numbers::pi / 180}, 1e-10); - EXPECT_UNITS_NEAR(frc::AngleModulus(units::radian_t{2.0 * std::numbers::pi}), + wpi::math::AngleModulus(wpi::units::radian_t{358 * std::numbers::pi / 180}), + wpi::units::radian_t{-2 * std::numbers::pi / 180}, 1e-10); + EXPECT_UNITS_NEAR(wpi::math::AngleModulus(wpi::units::radian_t{2.0 * std::numbers::pi}), 0_rad, 1e-10); - EXPECT_UNITS_EQ(frc::AngleModulus(units::radian_t{5 * std::numbers::pi}), - units::radian_t{std::numbers::pi}); - EXPECT_UNITS_EQ(frc::AngleModulus(units::radian_t{-5 * std::numbers::pi}), - units::radian_t{std::numbers::pi}); - EXPECT_UNITS_EQ(frc::AngleModulus(units::radian_t{std::numbers::pi / 2}), - units::radian_t{std::numbers::pi / 2}); - EXPECT_UNITS_EQ(frc::AngleModulus(units::radian_t{-std::numbers::pi / 2}), - units::radian_t{-std::numbers::pi / 2}); + EXPECT_UNITS_EQ(wpi::math::AngleModulus(wpi::units::radian_t{5 * std::numbers::pi}), + wpi::units::radian_t{std::numbers::pi}); + EXPECT_UNITS_EQ(wpi::math::AngleModulus(wpi::units::radian_t{-5 * std::numbers::pi}), + wpi::units::radian_t{std::numbers::pi}); + EXPECT_UNITS_EQ(wpi::math::AngleModulus(wpi::units::radian_t{std::numbers::pi / 2}), + wpi::units::radian_t{std::numbers::pi / 2}); + EXPECT_UNITS_EQ(wpi::math::AngleModulus(wpi::units::radian_t{-std::numbers::pi / 2}), + wpi::units::radian_t{-std::numbers::pi / 2}); } TEST(MathUtilTest, IsNear) { // The answer is always 42 // Positive integer checks - EXPECT_TRUE(frc::IsNear(42, 42, 1)); - EXPECT_TRUE(frc::IsNear(42, 41, 2)); - EXPECT_TRUE(frc::IsNear(42, 43, 2)); - EXPECT_FALSE(frc::IsNear(42, 44, 1)); + EXPECT_TRUE(wpi::math::IsNear(42, 42, 1)); + EXPECT_TRUE(wpi::math::IsNear(42, 41, 2)); + EXPECT_TRUE(wpi::math::IsNear(42, 43, 2)); + EXPECT_FALSE(wpi::math::IsNear(42, 44, 1)); // Negative integer checks - EXPECT_TRUE(frc::IsNear(-42, -42, 1)); - EXPECT_TRUE(frc::IsNear(-42, -41, 2)); - EXPECT_TRUE(frc::IsNear(-42, -43, 2)); - EXPECT_FALSE(frc::IsNear(-42, -44, 1)); + EXPECT_TRUE(wpi::math::IsNear(-42, -42, 1)); + EXPECT_TRUE(wpi::math::IsNear(-42, -41, 2)); + EXPECT_TRUE(wpi::math::IsNear(-42, -43, 2)); + EXPECT_FALSE(wpi::math::IsNear(-42, -44, 1)); // Mixed sign integer checks - EXPECT_FALSE(frc::IsNear(-42, 42, 1)); - EXPECT_FALSE(frc::IsNear(-42, 41, 2)); - EXPECT_FALSE(frc::IsNear(-42, 43, 2)); - EXPECT_FALSE(frc::IsNear(42, -42, 1)); - EXPECT_FALSE(frc::IsNear(42, -41, 2)); - EXPECT_FALSE(frc::IsNear(42, -43, 2)); + EXPECT_FALSE(wpi::math::IsNear(-42, 42, 1)); + EXPECT_FALSE(wpi::math::IsNear(-42, 41, 2)); + EXPECT_FALSE(wpi::math::IsNear(-42, 43, 2)); + EXPECT_FALSE(wpi::math::IsNear(42, -42, 1)); + EXPECT_FALSE(wpi::math::IsNear(42, -41, 2)); + EXPECT_FALSE(wpi::math::IsNear(42, -43, 2)); // Floating point checks - EXPECT_TRUE(frc::IsNear(42, 41.5, 1)); - EXPECT_TRUE(frc::IsNear(42, 42.5, 1)); - EXPECT_TRUE(frc::IsNear(42, 41.5, 0.75)); - EXPECT_TRUE(frc::IsNear(42, 42.5, 0.75)); + EXPECT_TRUE(wpi::math::IsNear(42, 41.5, 1)); + EXPECT_TRUE(wpi::math::IsNear(42, 42.5, 1)); + EXPECT_TRUE(wpi::math::IsNear(42, 41.5, 0.75)); + EXPECT_TRUE(wpi::math::IsNear(42, 42.5, 0.75)); // Wraparound checks - EXPECT_TRUE(frc::IsNear(0_deg, 356_deg, 5_deg, 0_deg, 360_deg)); - EXPECT_TRUE(frc::IsNear(0, -356, 5, 0, 360)); - EXPECT_TRUE(frc::IsNear(0, 4, 5, 0, 360)); - EXPECT_TRUE(frc::IsNear(0, -4, 5, 0, 360)); - EXPECT_TRUE(frc::IsNear(400, 41, 5, 0, 360)); - EXPECT_TRUE(frc::IsNear(400, -319, 5, 0, 360)); - EXPECT_TRUE(frc::IsNear(400, 401, 5, 0, 360)); - EXPECT_FALSE(frc::IsNear(0, 356, 2.5, 0, 360)); - EXPECT_FALSE(frc::IsNear(0, -356, 2.5, 0, 360)); - EXPECT_FALSE(frc::IsNear(0, 4, 2.5, 0, 360)); - EXPECT_FALSE(frc::IsNear(0, -4, 2.5, 0, 360)); - EXPECT_FALSE(frc::IsNear(400, 35, 5, 0, 360)); - EXPECT_FALSE(frc::IsNear(400, -315, 5, 0, 360)); - EXPECT_FALSE(frc::IsNear(400, 395, 5, 0, 360)); - EXPECT_FALSE(frc::IsNear(0_deg, -4_deg, 2.5_deg, 0_deg, 360_deg)); + EXPECT_TRUE(wpi::math::IsNear(0_deg, 356_deg, 5_deg, 0_deg, 360_deg)); + EXPECT_TRUE(wpi::math::IsNear(0, -356, 5, 0, 360)); + EXPECT_TRUE(wpi::math::IsNear(0, 4, 5, 0, 360)); + EXPECT_TRUE(wpi::math::IsNear(0, -4, 5, 0, 360)); + EXPECT_TRUE(wpi::math::IsNear(400, 41, 5, 0, 360)); + EXPECT_TRUE(wpi::math::IsNear(400, -319, 5, 0, 360)); + EXPECT_TRUE(wpi::math::IsNear(400, 401, 5, 0, 360)); + EXPECT_FALSE(wpi::math::IsNear(0, 356, 2.5, 0, 360)); + EXPECT_FALSE(wpi::math::IsNear(0, -356, 2.5, 0, 360)); + EXPECT_FALSE(wpi::math::IsNear(0, 4, 2.5, 0, 360)); + EXPECT_FALSE(wpi::math::IsNear(0, -4, 2.5, 0, 360)); + EXPECT_FALSE(wpi::math::IsNear(400, 35, 5, 0, 360)); + EXPECT_FALSE(wpi::math::IsNear(400, -315, 5, 0, 360)); + EXPECT_FALSE(wpi::math::IsNear(400, 395, 5, 0, 360)); + EXPECT_FALSE(wpi::math::IsNear(0_deg, -4_deg, 2.5_deg, 0_deg, 360_deg)); } TEST(MathUtilTest, Translation2dSlewRateLimitUnchanged) { - const frc::Translation2d translation1{0_m, 0_m}; - const frc::Translation2d translation2{2_m, 2_m}; + const wpi::math::Translation2d translation1{0_m, 0_m}; + const wpi::math::Translation2d translation2{2_m, 2_m}; - const frc::Translation2d result1 = - frc::SlewRateLimit(translation1, translation2, 1_s, 50_mps); + const wpi::math::Translation2d result1 = + wpi::math::SlewRateLimit(translation1, translation2, 1_s, 50_mps); - const frc::Translation2d expected1{2_m, 2_m}; + const wpi::math::Translation2d expected1{2_m, 2_m}; EXPECT_EQ(result1, expected1); } TEST(MathUtilTest, Translation2dSlewRateLimitChanged) { - const frc::Translation2d translation3{1_m, 1_m}; - const frc::Translation2d translation4{3_m, 3_m}; + const wpi::math::Translation2d translation3{1_m, 1_m}; + const wpi::math::Translation2d translation4{3_m, 3_m}; - const frc::Translation2d result2 = - frc::SlewRateLimit(translation3, translation4, 0.25_s, 2_mps); + const wpi::math::Translation2d result2 = + wpi::math::SlewRateLimit(translation3, translation4, 0.25_s, 2_mps); - const frc::Translation2d expected2{ - units::meter_t{1.0 + 0.5 * (std::numbers::sqrt2 / 2)}, - units::meter_t{1.0 + 0.5 * (std::numbers::sqrt2 / 2)}}; + const wpi::math::Translation2d expected2{ + wpi::units::meter_t{1.0 + 0.5 * (std::numbers::sqrt2 / 2)}, + wpi::units::meter_t{1.0 + 0.5 * (std::numbers::sqrt2 / 2)}}; EXPECT_EQ(result2, expected2); } TEST(MathUtilTest, Translation3dSlewRateLimitUnchanged) { - const frc::Translation3d translation1{0_m, 0_m, 0_m}; - const frc::Translation3d translation2{2_m, 2_m, 2_m}; + const wpi::math::Translation3d translation1{0_m, 0_m, 0_m}; + const wpi::math::Translation3d translation2{2_m, 2_m, 2_m}; - const frc::Translation3d result1 = - frc::SlewRateLimit(translation1, translation2, 1_s, 50.0_mps); + const wpi::math::Translation3d result1 = + wpi::math::SlewRateLimit(translation1, translation2, 1_s, 50.0_mps); - const frc::Translation3d expected1{2_m, 2_m, 2_m}; + const wpi::math::Translation3d expected1{2_m, 2_m, 2_m}; EXPECT_EQ(result1, expected1); } TEST(MathUtilTest, Translation3dSlewRateLimitChanged) { - const frc::Translation3d translation3{1_m, 1_m, 1_m}; - const frc::Translation3d translation4{3_m, 3_m, 3_m}; + const wpi::math::Translation3d translation3{1_m, 1_m, 1_m}; + const wpi::math::Translation3d translation4{3_m, 3_m, 3_m}; - const frc::Translation3d result2 = - frc::SlewRateLimit(translation3, translation4, 0.25_s, 2.0_mps); + const wpi::math::Translation3d result2 = + wpi::math::SlewRateLimit(translation3, translation4, 0.25_s, 2.0_mps); - const frc::Translation3d expected2{ - units::meter_t{1.0 + 0.5 * std::numbers::inv_sqrt3}, - units::meter_t{1.0 + 0.5 * std::numbers::inv_sqrt3}, - units::meter_t{1.0 + 0.5 * std::numbers::inv_sqrt3}}; + const wpi::math::Translation3d expected2{ + wpi::units::meter_t{1.0 + 0.5 * std::numbers::inv_sqrt3}, + wpi::units::meter_t{1.0 + 0.5 * std::numbers::inv_sqrt3}, + wpi::units::meter_t{1.0 + 0.5 * std::numbers::inv_sqrt3}}; EXPECT_EQ(result2, expected2); } diff --git a/wpimath/src/test/native/cpp/ProtoTestBase.hpp b/wpimath/src/test/native/cpp/ProtoTestBase.hpp index e1bc16ed78..27caf376c1 100644 --- a/wpimath/src/test/native/cpp/ProtoTestBase.hpp +++ b/wpimath/src/test/native/cpp/ProtoTestBase.hpp @@ -15,8 +15,8 @@ class ProtoTest : public testing::Test {}; TYPED_TEST_SUITE_P(ProtoTest); TYPED_TEST_P(ProtoTest, RoundTrip) { - wpi::ProtobufMessage message; - wpi::SmallVector buf; + wpi::util::ProtobufMessage message; + wpi::util::SmallVector buf; ASSERT_TRUE(message.Pack(buf, TypeParam::kTestData)); auto unpacked_data = message.Unpack(buf); diff --git a/wpimath/src/test/native/cpp/StateSpaceTest.cpp b/wpimath/src/test/native/cpp/StateSpaceTest.cpp index 3cf8a3b258..7c06c865a2 100644 --- a/wpimath/src/test/native/cpp/StateSpaceTest.cpp +++ b/wpimath/src/test/native/cpp/StateSpaceTest.cpp @@ -17,7 +17,7 @@ #include "wpi/math/system/plant/LinearSystemId.hpp" #include "wpi/units/time.hpp" -namespace frc { +namespace wpi::math { constexpr double kPositionStddev = 0.0001; constexpr auto kDt = 0.00505_s; @@ -36,7 +36,7 @@ class StateSpaceTest : public testing::Test { // Gear ratio constexpr double G = 40.0 / 40.0; - return frc::LinearSystemId::ElevatorSystem(motors, m, r, G).Slice(0); + return wpi::math::LinearSystemId::ElevatorSystem(motors, m, r, G).Slice(0); }(); LinearQuadraticRegulator<2, 1> controller{plant, {0.02, 0.4}, {12.0}, kDt}; KalmanFilter<2, 1, 1> observer{plant, {0.05, 1.0}, {0.0001}, kDt}; @@ -67,4 +67,4 @@ TEST_F(StateSpaceTest, CorrectPredictLoop) { EXPECT_NEAR(loop.Xhat(1), 0.0, 0.5); } -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/test/native/cpp/StateSpaceUtilTest.cpp b/wpimath/src/test/native/cpp/StateSpaceUtilTest.cpp index 4fcccefefa..2ad89c20d9 100644 --- a/wpimath/src/test/native/cpp/StateSpaceUtilTest.cpp +++ b/wpimath/src/test/native/cpp/StateSpaceUtilTest.cpp @@ -8,7 +8,7 @@ #include "wpi/math/util/StateSpaceUtil.hpp" TEST(StateSpaceUtilTest, CostParameterPack) { - constexpr frc::Matrixd<3, 3> mat = frc::MakeCostMatrix(1.0, 2.0, 3.0); + constexpr wpi::math::Matrixd<3, 3> mat = wpi::math::MakeCostMatrix(1.0, 2.0, 3.0); EXPECT_NEAR(mat(0, 0), 1.0, 1e-3); EXPECT_NEAR(mat(0, 1), 0.0, 1e-3); EXPECT_NEAR(mat(0, 2), 0.0, 1e-3); @@ -21,7 +21,7 @@ TEST(StateSpaceUtilTest, CostParameterPack) { } TEST(StateSpaceUtilTest, CostArray) { - constexpr frc::Matrixd<3, 3> mat = frc::MakeCostMatrix<3>({1.0, 2.0, 3.0}); + constexpr wpi::math::Matrixd<3, 3> mat = wpi::math::MakeCostMatrix<3>({1.0, 2.0, 3.0}); EXPECT_NEAR(mat(0, 0), 1.0, 1e-3); EXPECT_NEAR(mat(0, 1), 0.0, 1e-3); EXPECT_NEAR(mat(0, 2), 0.0, 1e-3); @@ -34,7 +34,7 @@ TEST(StateSpaceUtilTest, CostArray) { } TEST(StateSpaceUtilTest, CostDynamic) { - Eigen::MatrixXd mat = frc::MakeCostMatrix(std::vector{1.0, 2.0, 3.0}); + Eigen::MatrixXd mat = wpi::math::MakeCostMatrix(std::vector{1.0, 2.0, 3.0}); EXPECT_NEAR(mat(0, 0), 1.0, 1e-3); EXPECT_NEAR(mat(0, 1), 0.0, 1e-3); EXPECT_NEAR(mat(0, 2), 0.0, 1e-3); @@ -47,7 +47,7 @@ TEST(StateSpaceUtilTest, CostDynamic) { } TEST(StateSpaceUtilTest, CovParameterPack) { - constexpr frc::Matrixd<3, 3> mat = frc::MakeCovMatrix(1.0, 2.0, 3.0); + constexpr wpi::math::Matrixd<3, 3> mat = wpi::math::MakeCovMatrix(1.0, 2.0, 3.0); EXPECT_NEAR(mat(0, 0), 1.0, 1e-3); EXPECT_NEAR(mat(0, 1), 0.0, 1e-3); EXPECT_NEAR(mat(0, 2), 0.0, 1e-3); @@ -60,7 +60,7 @@ TEST(StateSpaceUtilTest, CovParameterPack) { } TEST(StateSpaceUtilTest, CovArray) { - constexpr frc::Matrixd<3, 3> mat = frc::MakeCovMatrix<3>({1.0, 2.0, 3.0}); + constexpr wpi::math::Matrixd<3, 3> mat = wpi::math::MakeCovMatrix<3>({1.0, 2.0, 3.0}); EXPECT_NEAR(mat(0, 0), 1.0, 1e-3); EXPECT_NEAR(mat(0, 1), 0.0, 1e-3); EXPECT_NEAR(mat(0, 2), 0.0, 1e-3); @@ -73,7 +73,7 @@ TEST(StateSpaceUtilTest, CovArray) { } TEST(StateSpaceUtilTest, CovDynamic) { - Eigen::MatrixXd mat = frc::MakeCovMatrix(std::vector{1.0, 2.0, 3.0}); + Eigen::MatrixXd mat = wpi::math::MakeCovMatrix(std::vector{1.0, 2.0, 3.0}); EXPECT_NEAR(mat(0, 0), 1.0, 1e-3); EXPECT_NEAR(mat(0, 1), 0.0, 1e-3); EXPECT_NEAR(mat(0, 2), 0.0, 1e-3); @@ -87,63 +87,63 @@ TEST(StateSpaceUtilTest, CovDynamic) { TEST(StateSpaceUtilTest, WhiteNoiseVectorParameterPack) { [[maybe_unused]] - frc::Vectord<2> vec = frc::MakeWhiteNoiseVector(2.0, 3.0); + wpi::math::Vectord<2> vec = wpi::math::MakeWhiteNoiseVector(2.0, 3.0); } TEST(StateSpaceUtilTest, WhiteNoiseVectorArray) { [[maybe_unused]] - frc::Vectord<2> vec = frc::MakeWhiteNoiseVector<2>({2.0, 3.0}); + wpi::math::Vectord<2> vec = wpi::math::MakeWhiteNoiseVector<2>({2.0, 3.0}); } TEST(StateSpaceUtilTest, WhiteNoiseVectorDynamic) { [[maybe_unused]] - Eigen::VectorXd vec = frc::MakeWhiteNoiseVector(std::vector{2.0, 3.0}); + Eigen::VectorXd vec = wpi::math::MakeWhiteNoiseVector(std::vector{2.0, 3.0}); } TEST(StateSpaceUtilTest, IsStabilizable) { - frc::Matrixd<2, 1> B{0, 1}; + wpi::math::Matrixd<2, 1> B{0, 1}; // First eigenvalue is uncontrollable and unstable. // Second eigenvalue is controllable and stable. EXPECT_FALSE( - (frc::IsStabilizable<2, 1>(frc::Matrixd<2, 2>{{1.2, 0}, {0, 0.5}}, B))); + (wpi::math::IsStabilizable<2, 1>(wpi::math::Matrixd<2, 2>{{1.2, 0}, {0, 0.5}}, B))); // First eigenvalue is uncontrollable and marginally stable. // Second eigenvalue is controllable and stable. EXPECT_FALSE( - (frc::IsStabilizable<2, 1>(frc::Matrixd<2, 2>{{1, 0}, {0, 0.5}}, B))); + (wpi::math::IsStabilizable<2, 1>(wpi::math::Matrixd<2, 2>{{1, 0}, {0, 0.5}}, B))); // First eigenvalue is uncontrollable and stable. // Second eigenvalue is controllable and stable. EXPECT_TRUE( - (frc::IsStabilizable<2, 1>(frc::Matrixd<2, 2>{{0.2, 0}, {0, 0.5}}, B))); + (wpi::math::IsStabilizable<2, 1>(wpi::math::Matrixd<2, 2>{{0.2, 0}, {0, 0.5}}, B))); // First eigenvalue is uncontrollable and stable. // Second eigenvalue is controllable and unstable. EXPECT_TRUE( - (frc::IsStabilizable<2, 1>(frc::Matrixd<2, 2>{{0.2, 0}, {0, 1.2}}, B))); + (wpi::math::IsStabilizable<2, 1>(wpi::math::Matrixd<2, 2>{{0.2, 0}, {0, 1.2}}, B))); } TEST(StateSpaceUtilTest, IsDetectable) { - frc::Matrixd<1, 2> C{0, 1}; + wpi::math::Matrixd<1, 2> C{0, 1}; // First eigenvalue is unobservable and unstable. // Second eigenvalue is observable and stable. EXPECT_FALSE( - (frc::IsDetectable<2, 1>(frc::Matrixd<2, 2>{{1.2, 0}, {0, 0.5}}, C))); + (wpi::math::IsDetectable<2, 1>(wpi::math::Matrixd<2, 2>{{1.2, 0}, {0, 0.5}}, C))); // First eigenvalue is unobservable and marginally stable. // Second eigenvalue is observable and stable. EXPECT_FALSE( - (frc::IsDetectable<2, 1>(frc::Matrixd<2, 2>{{1, 0}, {0, 0.5}}, C))); + (wpi::math::IsDetectable<2, 1>(wpi::math::Matrixd<2, 2>{{1, 0}, {0, 0.5}}, C))); // First eigenvalue is unobservable and stable. // Second eigenvalue is observable and stable. EXPECT_TRUE( - (frc::IsDetectable<2, 1>(frc::Matrixd<2, 2>{{0.2, 0}, {0, 0.5}}, C))); + (wpi::math::IsDetectable<2, 1>(wpi::math::Matrixd<2, 2>{{0.2, 0}, {0, 0.5}}, C))); // First eigenvalue is unobservable and stable. // Second eigenvalue is observable and unstable. EXPECT_TRUE( - (frc::IsDetectable<2, 1>(frc::Matrixd<2, 2>{{0.2, 0}, {0, 1.2}}, C))); + (wpi::math::IsDetectable<2, 1>(wpi::math::Matrixd<2, 2>{{0.2, 0}, {0, 1.2}}, C))); } diff --git a/wpimath/src/test/native/cpp/StructTestBase.hpp b/wpimath/src/test/native/cpp/StructTestBase.hpp index 014db74760..450c01392b 100644 --- a/wpimath/src/test/native/cpp/StructTestBase.hpp +++ b/wpimath/src/test/native/cpp/StructTestBase.hpp @@ -16,45 +16,45 @@ TYPED_TEST_SUITE_P(StructTest); // For these tests: // TypeParam defines Type, kTestData, and CheckEq // Type is the data type -// StructType is the instantiation of wpi::Struct<> +// StructType is the instantiation of wpi::util::Struct<> TYPED_TEST_P(StructTest, RoundTrip) { using Type = typename TypeParam::Type; - using StructType = wpi::Struct; + using StructType = wpi::util::Struct; uint8_t buffer[StructType::GetSize()]; std::memset(buffer, 0, StructType::GetSize()); - wpi::PackStruct(buffer, TypeParam::kTestData); + wpi::util::PackStruct(buffer, TypeParam::kTestData); - Type unpacked_data = wpi::UnpackStruct(buffer); + Type unpacked_data = wpi::util::UnpackStruct(buffer); TypeParam::CheckEq(TypeParam::kTestData, unpacked_data); } TYPED_TEST_P(StructTest, DoublePack) { using Type = typename TypeParam::Type; - using StructType = wpi::Struct; + using StructType = wpi::util::Struct; uint8_t buffer[StructType::GetSize()]; std::memset(buffer, 0, StructType::GetSize()); - wpi::PackStruct(buffer, TypeParam::kTestData); - wpi::PackStruct(buffer, TypeParam::kTestData); + wpi::util::PackStruct(buffer, TypeParam::kTestData); + wpi::util::PackStruct(buffer, TypeParam::kTestData); - Type unpacked_data = wpi::UnpackStruct(buffer); + Type unpacked_data = wpi::util::UnpackStruct(buffer); TypeParam::CheckEq(TypeParam::kTestData, unpacked_data); } TYPED_TEST_P(StructTest, DoubleUnpack) { using Type = typename TypeParam::Type; - using StructType = wpi::Struct; + using StructType = wpi::util::Struct; uint8_t buffer[StructType::GetSize()]; std::memset(buffer, 0, StructType::GetSize()); - wpi::PackStruct(buffer, TypeParam::kTestData); + wpi::util::PackStruct(buffer, TypeParam::kTestData); { - Type unpacked_data = wpi::UnpackStruct(buffer); + Type unpacked_data = wpi::util::UnpackStruct(buffer); TypeParam::CheckEq(TypeParam::kTestData, unpacked_data); } { - Type unpacked_data = wpi::UnpackStruct(buffer); + Type unpacked_data = wpi::util::UnpackStruct(buffer); TypeParam::CheckEq(TypeParam::kTestData, unpacked_data); } } diff --git a/wpimath/src/test/native/cpp/UnitsTest.cpp b/wpimath/src/test/native/cpp/UnitsTest.cpp index f61623287d..2440a9c8a3 100644 --- a/wpimath/src/test/native/cpp/UnitsTest.cpp +++ b/wpimath/src/test/native/cpp/UnitsTest.cpp @@ -51,46 +51,46 @@ #include "wpi/units/voltage.hpp" #include "wpi/units/volume.hpp" -using namespace units::acceleration; -using namespace units::angle; -using namespace units::angular_acceleration; -using namespace units::angular_jerk; -using namespace units::angular_velocity; -using namespace units::area; -using namespace units::capacitance; -using namespace units::charge; -using namespace units::concentration; -using namespace units::conductance; -using namespace units::data; -using namespace units::data_transfer_rate; -using namespace units::density; -using namespace units::dimensionless; -using namespace units::energy; -using namespace units::frequency; -using namespace units::illuminance; -using namespace units::impedance; -using namespace units::inductance; -using namespace units::length; -using namespace units::luminous_flux; -using namespace units::luminous_intensity; -using namespace units::magnetic_field_strength; -using namespace units::magnetic_flux; -using namespace units::mass; -using namespace units::math; -using namespace units::power; -using namespace units::pressure; -using namespace units::radiation; -using namespace units::solid_angle; -using namespace units::temperature; -using namespace units::time; -using namespace units::torque; -using namespace units::velocity; -using namespace units::voltage; -using namespace units::volume; +using namespace wpi::units::acceleration; +using namespace wpi::units::angle; +using namespace wpi::units::angular_acceleration; +using namespace wpi::units::angular_jerk; +using namespace wpi::units::angular_velocity; +using namespace wpi::units::area; +using namespace wpi::units::capacitance; +using namespace wpi::units::charge; +using namespace wpi::units::concentration; +using namespace wpi::units::conductance; +using namespace wpi::units::data; +using namespace wpi::units::data_transfer_rate; +using namespace wpi::units::density; +using namespace wpi::units::dimensionless; +using namespace wpi::units::energy; +using namespace wpi::units::frequency; +using namespace wpi::units::illuminance; +using namespace wpi::units::impedance; +using namespace wpi::units::inductance; +using namespace wpi::units::length; +using namespace wpi::units::luminous_flux; +using namespace wpi::units::luminous_intensity; +using namespace wpi::units::magnetic_field_strength; +using namespace wpi::units::magnetic_flux; +using namespace wpi::units::mass; +using namespace wpi::units::math; +using namespace wpi::units::power; +using namespace wpi::units::pressure; +using namespace wpi::units::radiation; +using namespace wpi::units::solid_angle; +using namespace wpi::units::temperature; +using namespace wpi::units::time; +using namespace wpi::units::torque; +using namespace wpi::units::velocity; +using namespace wpi::units::voltage; +using namespace wpi::units::volume; using namespace units; #if !defined(_MSC_VER) || _MSC_VER > 1800 -using namespace units::literals; +using namespace wpi::units::literals; #endif namespace { @@ -452,7 +452,7 @@ TEST_F(TypeTraits, is_substance_unit) { TEST_F(TypeTraits, is_luminous_intensity_unit) { EXPECT_TRUE((traits::is_luminous_intensity_unit_v)); EXPECT_FALSE( - (traits::is_luminous_intensity_unit_v)); + (traits::is_luminous_intensity_unit_v)); EXPECT_FALSE((traits::is_luminous_intensity_unit_v)); EXPECT_TRUE((traits::is_luminous_intensity_unit_v)); @@ -534,19 +534,19 @@ TEST_F(TypeTraits, is_acceleration_unit) { } TEST_F(TypeTraits, is_force_unit) { - EXPECT_TRUE((traits::is_force_unit_v)); - EXPECT_TRUE((traits::is_force_unit_v)); + EXPECT_TRUE((traits::is_force_unit_v)); + EXPECT_TRUE((traits::is_force_unit_v)); EXPECT_FALSE((traits::is_force_unit_v)); EXPECT_FALSE((traits::is_force_unit_v)); - EXPECT_TRUE((traits::is_force_unit_v)); - EXPECT_TRUE((traits::is_force_unit_v)); - EXPECT_TRUE((traits::is_force_unit_v)); - EXPECT_TRUE((traits::is_force_unit_v)); + EXPECT_TRUE((traits::is_force_unit_v)); + EXPECT_TRUE((traits::is_force_unit_v)); + EXPECT_TRUE((traits::is_force_unit_v)); + EXPECT_TRUE((traits::is_force_unit_v)); EXPECT_FALSE((traits::is_force_unit_v)); - EXPECT_TRUE((traits::is_force_unit_v)); - EXPECT_FALSE((traits::is_force_unit_v)); + EXPECT_TRUE((traits::is_force_unit_v)); + EXPECT_FALSE((traits::is_force_unit_v)); } TEST_F(TypeTraits, is_pressure_unit) { @@ -677,7 +677,7 @@ TEST_F(TypeTraits, is_magnetic_flux_unit) { TEST_F(TypeTraits, is_magnetic_field_strength_unit) { EXPECT_TRUE((traits::is_magnetic_field_strength_unit_v< - units::magnetic_field_strength::tesla>)); + wpi::units::magnetic_field_strength::tesla>)); EXPECT_TRUE((traits::is_magnetic_field_strength_unit_v)); EXPECT_FALSE((traits::is_magnetic_field_strength_unit_v)); EXPECT_FALSE((traits::is_magnetic_field_strength_unit_v)); @@ -919,13 +919,13 @@ TEST_F(UnitManipulators, dimensionalAnalysis) { // REALLY handy if the unit types aren't know (i.e. they themselves are // template parameters), as you can get the resulting unit of the operation. - using velocity = units::detail::unit_divide; + using velocity = wpi::units::detail::unit_divide; bool shouldBeTrue = std::is_same_v; EXPECT_TRUE(shouldBeTrue); using acceleration1 = unit, category::acceleration_unit>; - using acceleration2 = units::detail::unit_divide< - meters, units::detail::unit_multiply>; + using acceleration2 = wpi::units::detail::unit_divide< + meters, wpi::units::detail::unit_multiply>; shouldBeTrue = std::is_same_v; EXPECT_TRUE(shouldBeTrue); } @@ -964,7 +964,7 @@ TEST_F(UnitContainer, has_value_member) { } TEST_F(UnitContainer, make_unit) { - auto dist = units::make_unit(5); + auto dist = wpi::units::make_unit(5); EXPECT_EQ(meter_t(5), dist); } @@ -1380,17 +1380,17 @@ TEST_F(UnitContainer, cout) { // undefined unit testing::internal::CaptureStdout(); - std::cout << units::math::cpow<4>(meter_t(2)); + std::cout << wpi::units::math::cpow<4>(meter_t(2)); output = testing::internal::GetCapturedStdout(); EXPECT_STREQ("16 m^4", output.c_str()); testing::internal::CaptureStdout(); - std::cout << units::math::cpow<3>(foot_t(2)); + std::cout << wpi::units::math::cpow<3>(foot_t(2)); output = testing::internal::GetCapturedStdout(); EXPECT_STREQ("8 cu_ft", output.c_str()); testing::internal::CaptureStdout(); - std::cout << std::setprecision(9) << units::math::cpow<4>(foot_t(2)); + std::cout << std::setprecision(9) << wpi::units::math::cpow<4>(foot_t(2)); output = testing::internal::GetCapturedStdout(); EXPECT_STREQ("0.138095597 m^4", output.c_str()); @@ -1427,59 +1427,59 @@ TEST_F(UnitContainer, cout) { #if __has_include() && !defined(UNIT_LIB_DISABLE_FMT) TEST_F(UnitContainer, fmtlib) { testing::internal::CaptureStdout(); - wpi::print("{}", degree_t(349.87)); + wpi::util::print("{}", degree_t(349.87)); std::string output = testing::internal::GetCapturedStdout(); EXPECT_STREQ("349.87 deg", output.c_str()); testing::internal::CaptureStdout(); - wpi::print("{}", meter_t(1.0)); + wpi::util::print("{}", meter_t(1.0)); output = testing::internal::GetCapturedStdout(); EXPECT_STREQ("1 m", output.c_str()); testing::internal::CaptureStdout(); - wpi::print("{}", dB_t(31.0)); + wpi::util::print("{}", dB_t(31.0)); output = testing::internal::GetCapturedStdout(); EXPECT_STREQ("31 dB", output.c_str()); testing::internal::CaptureStdout(); - wpi::print("{}", volt_t(21.79)); + wpi::util::print("{}", volt_t(21.79)); output = testing::internal::GetCapturedStdout(); EXPECT_STREQ("21.79 V", output.c_str()); testing::internal::CaptureStdout(); - wpi::print("{}", dBW_t(12.0)); + wpi::util::print("{}", dBW_t(12.0)); output = testing::internal::GetCapturedStdout(); EXPECT_STREQ("12 dBW", output.c_str()); testing::internal::CaptureStdout(); - wpi::print("{}", dBm_t(120.0)); + wpi::util::print("{}", dBm_t(120.0)); output = testing::internal::GetCapturedStdout(); EXPECT_STREQ("120 dBm", output.c_str()); testing::internal::CaptureStdout(); - wpi::print("{}", miles_per_hour_t(72.1)); + wpi::util::print("{}", miles_per_hour_t(72.1)); output = testing::internal::GetCapturedStdout(); EXPECT_STREQ("72.1 mph", output.c_str()); // undefined unit testing::internal::CaptureStdout(); - wpi::print("{}", units::math::cpow<4>(meter_t(2))); + wpi::util::print("{}", wpi::units::math::cpow<4>(meter_t(2))); output = testing::internal::GetCapturedStdout(); EXPECT_STREQ("16 m^4", output.c_str()); testing::internal::CaptureStdout(); - wpi::print("{}", units::math::cpow<3>(foot_t(2))); + wpi::util::print("{}", wpi::units::math::cpow<3>(foot_t(2))); output = testing::internal::GetCapturedStdout(); EXPECT_STREQ("8 cu_ft", output.c_str()); testing::internal::CaptureStdout(); - wpi::print("{:.9}", units::math::cpow<4>(foot_t(2))); + wpi::util::print("{:.9}", wpi::units::math::cpow<4>(foot_t(2))); output = testing::internal::GetCapturedStdout(); EXPECT_STREQ("0.138095597 m^4", output.c_str()); // constants testing::internal::CaptureStdout(); - wpi::print("{:.8}", constants::k_B); + wpi::util::print("{:.8}", constants::k_B); output = testing::internal::GetCapturedStdout(); #if defined(_MSC_VER) && (_MSC_VER <= 1800) EXPECT_STREQ("1.3806485e-023 m^2 kg s^-2 K^-1", output.c_str()); @@ -1488,7 +1488,7 @@ TEST_F(UnitContainer, fmtlib) { #endif testing::internal::CaptureStdout(); - wpi::print("{:.9}", constants::mu_B); + wpi::util::print("{:.9}", constants::mu_B); output = testing::internal::GetCapturedStdout(); #if defined(_MSC_VER) && (_MSC_VER <= 1800) EXPECT_STREQ("9.27400999e-024 m^2 A", output.c_str()); @@ -1497,7 +1497,7 @@ TEST_F(UnitContainer, fmtlib) { #endif testing::internal::CaptureStdout(); - wpi::print("{:.7}", constants::sigma); + wpi::util::print("{:.7}", constants::sigma); output = testing::internal::GetCapturedStdout(); #if defined(_MSC_VER) && (_MSC_VER <= 1800) EXPECT_STREQ("5.670367e-008 kg s^-3 K^-4", output.c_str()); @@ -1509,10 +1509,10 @@ TEST_F(UnitContainer, fmtlib) { TEST_F(UnitContainer, to_string) { foot_t a(3.5); - EXPECT_STREQ("3.5 ft", units::length::to_string(a).c_str()); + EXPECT_STREQ("3.5 ft", wpi::units::length::to_string(a).c_str()); meter_t b(8); - EXPECT_STREQ("8 m", units::length::to_string(b).c_str()); + EXPECT_STREQ("8 m", wpi::units::length::to_string(b).c_str()); } TEST_F(UnitContainer, DISABLED_to_string_locale) { @@ -1530,10 +1530,10 @@ TEST_F(UnitContainer, DISABLED_to_string_locale) { EXPECT_EQ(point_de, ','); kilometer_t de = 2_km; - EXPECT_STREQ("2 km", units::length::to_string(de).c_str()); + EXPECT_STREQ("2 km", wpi::units::length::to_string(de).c_str()); de = 2.5_km; - EXPECT_STREQ("2,5 km", units::length::to_string(de).c_str()); + EXPECT_STREQ("2,5 km", wpi::units::length::to_string(de).c_str()); // US locale #if defined(_MSC_VER) @@ -1547,20 +1547,20 @@ TEST_F(UnitContainer, DISABLED_to_string_locale) { EXPECT_EQ(point_us, '.'); mile_t us = 2_mi; - EXPECT_STREQ("2 mi", units::length::to_string(us).c_str()); + EXPECT_STREQ("2 mi", wpi::units::length::to_string(us).c_str()); us = 2.5_mi; - EXPECT_STREQ("2.5 mi", units::length::to_string(us).c_str()); + EXPECT_STREQ("2.5 mi", wpi::units::length::to_string(us).c_str()); } TEST_F(UnitContainer, nameAndAbbreviation) { foot_t a(3.5); - EXPECT_STREQ("ft", units::abbreviation(a)); + EXPECT_STREQ("ft", wpi::units::abbreviation(a)); EXPECT_STREQ("ft", a.abbreviation()); EXPECT_STREQ("foot", a.name()); meter_t b(8); - EXPECT_STREQ("m", units::abbreviation(b)); + EXPECT_STREQ("m", wpi::units::abbreviation(b)); EXPECT_STREQ("m", b.abbreviation()); EXPECT_STREQ("meter", b.name()); } @@ -2033,17 +2033,17 @@ TEST_F(UnitConversion, acceleration) { TEST_F(UnitConversion, force) { double test; - test = convert(1.0); + test = convert(1.0); EXPECT_NEAR(1.0, test, 5.0e-5); - test = convert(6.3); + test = convert(6.3); EXPECT_NEAR(1.4163, test, 5.0e-5); - test = convert(5.0); + test = convert(5.0); EXPECT_NEAR(500000.0, test, 5.0e-5); - test = convert(2.1); + test = convert(2.1); EXPECT_NEAR(15.1893, test, 5.0e-5); - test = convert(173.0); + test = convert(173.0); EXPECT_NEAR(17.6411, test, 5.0e-5); - test = convert(21.879); + test = convert(21.879); EXPECT_NEAR(0.308451933, test, 5.0e-10); } @@ -2635,16 +2635,16 @@ TEST_F(UnitConversion, data_transfer_rate) { TEST_F(UnitConversion, pi) { EXPECT_TRUE( - units::traits::is_dimensionless_unit_v); - EXPECT_TRUE(units::traits::is_dimensionless_unit_v); + wpi::units::traits::is_dimensionless_unit_v); + EXPECT_TRUE(wpi::units::traits::is_dimensionless_unit_v); // implicit conversion/arithmetic EXPECT_NEAR(3.14159, constants::pi, 5.0e-6); EXPECT_NEAR(6.28318531, (2 * constants::pi), 5.0e-9); EXPECT_NEAR(6.28318531, (constants::pi + constants::pi), 5.0e-9); EXPECT_NEAR(0.0, (constants::pi - constants::pi), 5.0e-9); - EXPECT_NEAR(31.00627668, units::math::cpow<3>(constants::pi), 5.0e-10); - EXPECT_NEAR(0.0322515344, (1.0 / units::math::cpow<3>(constants::pi)), + EXPECT_NEAR(31.00627668, wpi::units::math::cpow<3>(constants::pi), 5.0e-10); + EXPECT_NEAR(0.0322515344, (1.0 / wpi::units::math::cpow<3>(constants::pi)), 5.0e-11); EXPECT_TRUE(constants::detail::PI_VAL == constants::pi); EXPECT_TRUE(1.0 != constants::pi); @@ -2748,10 +2748,10 @@ TEST_F(UnitConversion, std_chrono) { } TEST_F(UnitConversion, squaredTemperature) { - using squared_celsius = units::compound_unit>; - using squared_celsius_t = units::unit_t; + using squared_celsius = wpi::units::compound_unit>; + using squared_celsius_t = wpi::units::unit_t; const squared_celsius_t right(100); - const celsius_t rootRight = units::math::sqrt(right); + const celsius_t rootRight = wpi::units::math::sqrt(right); EXPECT_EQ(celsius_t(10), rootRight); } @@ -3127,8 +3127,8 @@ TEST_F(Constexpr, arithmetic) { constexpr auto result5(meter_t(1) - meter_t(1)); constexpr auto result6(meter_t(1) * meter_t(1)); constexpr auto result7(meter_t(1) / meter_t(1)); - constexpr auto result8(units::math::cpow<2>(meter_t(2))); - constexpr auto result9 = units::math::cpow<3>(2_m); + constexpr auto result8(wpi::units::math::cpow<2>(meter_t(2))); + constexpr auto result9 = wpi::units::math::cpow<3>(2_m); constexpr auto result10 = 2_m * 2_m; EXPECT_TRUE(noexcept(result0)); @@ -3329,7 +3329,7 @@ TEST_F(CompileTimeArithmetic, unit_value_multiply) { EXPECT_TRUE(( traits::is_unit_value_t_category_v)); - using nRatio = unit_value_t; + using nRatio = unit_value_t; using productN = unit_value_multiply; EXPECT_FALSE( @@ -3517,11 +3517,11 @@ TEST_F(CaseStudies, pythagoreanTheorum) { TEST(Units, overloadResolution) { // Slight hack to get nested functions struct Scope { - static bool f(units::meter_t) { + static bool f(wpi::units::meter_t) { return true; }; - static bool f(units::second_t) { + static bool f(wpi::units::second_t) { return false; }; }; diff --git a/wpimath/src/test/native/cpp/controller/ArmFeedforwardTest.cpp b/wpimath/src/test/native/cpp/controller/ArmFeedforwardTest.cpp index b2f1d03d03..dd5873e787 100644 --- a/wpimath/src/test/native/cpp/controller/ArmFeedforwardTest.cpp +++ b/wpimath/src/test/native/cpp/controller/ArmFeedforwardTest.cpp @@ -35,22 +35,22 @@ using Kg_unit = decltype(1_V); * @param dt The simulation time. * @return The final state as a 2-vector of angle and angular velocity. */ -frc::Matrixd<2, 1> Simulate(Ks_unit Ks, Kv_unit Kv, Ka_unit Ka, Kg_unit Kg, - units::radian_t currentAngle, - units::radians_per_second_t currentVelocity, - units::volt_t input, units::second_t dt) { - frc::Matrixd<2, 2> A{{0.0, 1.0}, {0.0, -Kv.value() / Ka.value()}}; - frc::Matrixd<2, 1> B{{0.0}, {1.0 / Ka.value()}}; +wpi::math::Matrixd<2, 1> Simulate(Ks_unit Ks, Kv_unit Kv, Ka_unit Ka, Kg_unit Kg, + wpi::units::radian_t currentAngle, + wpi::units::radians_per_second_t currentVelocity, + wpi::units::volt_t input, wpi::units::second_t dt) { + wpi::math::Matrixd<2, 2> A{{0.0, 1.0}, {0.0, -Kv.value() / Ka.value()}}; + wpi::math::Matrixd<2, 1> B{{0.0}, {1.0 / Ka.value()}}; - return frc::RK4( - [&](const frc::Matrixd<2, 1>& x, - const frc::Matrixd<1, 1>& u) -> frc::Matrixd<2, 1> { - frc::Matrixd<2, 1> c{0.0, -Ks.value() / Ka.value() * wpi::sgn(x(1)) - + return wpi::math::RK4( + [&](const wpi::math::Matrixd<2, 1>& x, + const wpi::math::Matrixd<1, 1>& u) -> wpi::math::Matrixd<2, 1> { + wpi::math::Matrixd<2, 1> c{0.0, -Ks.value() / Ka.value() * wpi::util::sgn(x(1)) - Kg.value() / Ka.value() * std::cos(x(0))}; return A * x + B * u + c; }, - frc::Matrixd<2, 1>{currentAngle.value(), currentVelocity.value()}, - frc::Matrixd<1, 1>{input.value()}, dt); + wpi::math::Matrixd<2, 1>{currentAngle.value(), currentVelocity.value()}, + wpi::math::Matrixd<1, 1>{input.value()}, dt); } /** @@ -66,12 +66,12 @@ frc::Matrixd<2, 1> Simulate(Ks_unit Ks, Kv_unit Kv, Ka_unit Ka, Kg_unit Kg, * @param input The input voltage. * @param dt The simulation time. */ -void CalculateAndSimulate(const frc::ArmFeedforward& armFF, Ks_unit Ks, +void CalculateAndSimulate(const wpi::math::ArmFeedforward& armFF, Ks_unit Ks, Kv_unit Kv, Ka_unit Ka, Kg_unit Kg, - units::radian_t currentAngle, - units::radians_per_second_t currentVelocity, - units::radians_per_second_t nextVelocity, - units::second_t dt) { + wpi::units::radian_t currentAngle, + wpi::units::radians_per_second_t currentVelocity, + wpi::units::radians_per_second_t nextVelocity, + wpi::units::second_t dt) { auto input = armFF.Calculate(currentAngle, currentVelocity, nextVelocity); EXPECT_NEAR( nextVelocity.value(), @@ -86,7 +86,7 @@ TEST(ArmFeedforwardTest, Calculate) { constexpr auto Kv = 1.5_V / 1_rad_per_s; constexpr auto Ka = 2_V / 1_rad_per_s_sq; constexpr auto Kg = 1_V; - frc::ArmFeedforward armFF{Ks, Kg, Kv, Ka}; + wpi::math::ArmFeedforward armFF{Ks, Kg, Kv, Ka}; // Calculate(angle, angular velocity) EXPECT_NEAR( @@ -112,7 +112,7 @@ TEST(ArmFeedforwardTest, CalculateIllConditionedModel) { constexpr auto Kv = 2.7167_V / 1_rad_per_s; constexpr auto Ka = 1e-2_V / 1_rad_per_s_sq; constexpr auto Kg = 0.2708_V; - frc::ArmFeedforward armFF{Ks, Kg, Kv, Ka}; + wpi::math::ArmFeedforward armFF{Ks, Kg, Kv, Ka}; constexpr auto currentAngle = 1_rad; constexpr auto currentVelocity = 0.02_rad_per_s; @@ -123,7 +123,7 @@ TEST(ArmFeedforwardTest, CalculateIllConditionedModel) { EXPECT_DOUBLE_EQ( armFF.Calculate(currentAngle, currentVelocity, nextVelocity).value(), (Ks + Kv * currentVelocity + Ka * averageAccel + - Kg * units::math::cos(currentAngle)) + Kg * wpi::units::math::cos(currentAngle)) .value()); } @@ -132,7 +132,7 @@ TEST(ArmFeedforwardTest, CalculateIllConditionedGradient) { constexpr auto Kv = 2.7167_V / 1_rad_per_s; constexpr auto Ka = 0.50799_V / 1_rad_per_s_sq; constexpr auto Kg = 0.2708_V; - frc::ArmFeedforward armFF{Ks, Kg, Kv, Ka}; + wpi::math::ArmFeedforward armFF{Ks, Kg, Kv, Ka}; CalculateAndSimulate(armFF, Ks, Kv, Ka, Kg, 1_rad, 0.02_rad_per_s, 0_rad_per_s, 20_ms); @@ -143,7 +143,7 @@ TEST(ArmFeedforwardTest, AchievableVelocity) { constexpr auto Kv = 1.5_V / 1_rad_per_s; constexpr auto Ka = 2_V / 1_rad_per_s_sq; constexpr auto Kg = 1_V; - frc::ArmFeedforward armFF{Ks, Kg, Kv, Ka}; + wpi::math::ArmFeedforward armFF{Ks, Kg, Kv, Ka}; EXPECT_NEAR(armFF .MaxAchievableVelocity(12_V, std::numbers::pi / 3 * 1_rad, @@ -162,7 +162,7 @@ TEST(ArmFeedforwardTest, AchievableAcceleration) { constexpr auto Kv = 1.5_V / 1_rad_per_s; constexpr auto Ka = 2_V / 1_rad_per_s_sq; constexpr auto Kg = 1_V; - frc::ArmFeedforward armFF{Ks, Kg, Kv, Ka}; + wpi::math::ArmFeedforward armFF{Ks, Kg, Kv, Ka}; EXPECT_NEAR(armFF .MaxAchievableAcceleration(12_V, std::numbers::pi / 3 * 1_rad, @@ -191,7 +191,7 @@ TEST(ArmFeedforwardTest, NegativeGains) { constexpr auto Kv = 1.5_V / 1_rad_per_s; constexpr auto Ka = 2_V / 1_rad_per_s_sq; constexpr auto Kg = 1_V; - frc::ArmFeedforward armFF{Ks, Kg, -Kv, -Ka}; + wpi::math::ArmFeedforward armFF{Ks, Kg, -Kv, -Ka}; EXPECT_EQ(armFF.GetKv().value(), 0); EXPECT_EQ(armFF.GetKa().value(), 0); diff --git a/wpimath/src/test/native/cpp/controller/BangBangInputOutputTest.cpp b/wpimath/src/test/native/cpp/controller/BangBangInputOutputTest.cpp index 4d0069cfb9..43242088a5 100644 --- a/wpimath/src/test/native/cpp/controller/BangBangInputOutputTest.cpp +++ b/wpimath/src/test/native/cpp/controller/BangBangInputOutputTest.cpp @@ -7,13 +7,13 @@ #include "wpi/math/controller/BangBangController.hpp" TEST(BangBangInputOutputTest, ShouldOutput) { - frc::BangBangController controller; + wpi::math::BangBangController controller; EXPECT_DOUBLE_EQ(controller.Calculate(0, 1), 1); } TEST(BangBangInputOutputTest, ShouldNotOutput) { - frc::BangBangController controller; + wpi::math::BangBangController controller; EXPECT_DOUBLE_EQ(controller.Calculate(1, 0), 0); } diff --git a/wpimath/src/test/native/cpp/controller/BangBangToleranceTest.cpp b/wpimath/src/test/native/cpp/controller/BangBangToleranceTest.cpp index 9a2fbe60c7..f84b7ab080 100644 --- a/wpimath/src/test/native/cpp/controller/BangBangToleranceTest.cpp +++ b/wpimath/src/test/native/cpp/controller/BangBangToleranceTest.cpp @@ -7,7 +7,7 @@ #include "wpi/math/controller/BangBangController.hpp" TEST(BangBangToleranceTest, InTolerance) { - frc::BangBangController controller{0.1}; + wpi::math::BangBangController controller{0.1}; controller.SetSetpoint(1); controller.Calculate(1); @@ -15,7 +15,7 @@ TEST(BangBangToleranceTest, InTolerance) { } TEST(BangBangToleranceTest, OutOfTolerance) { - frc::BangBangController controller{0.1}; + wpi::math::BangBangController controller{0.1}; controller.SetSetpoint(1); controller.Calculate(0); diff --git a/wpimath/src/test/native/cpp/controller/ControlAffinePlantInversionFeedforwardTest.cpp b/wpimath/src/test/native/cpp/controller/ControlAffinePlantInversionFeedforwardTest.cpp index 0c2a4c181f..2e2a26577c 100644 --- a/wpimath/src/test/native/cpp/controller/ControlAffinePlantInversionFeedforwardTest.cpp +++ b/wpimath/src/test/native/cpp/controller/ControlAffinePlantInversionFeedforwardTest.cpp @@ -8,7 +8,7 @@ #include "wpi/math/linalg/EigenCore.hpp" #include "wpi/units/time.hpp" -namespace frc { +namespace wpi::math { Vectord<2> Dynamics(const Vectord<2>& x, const Vectord<1>& u) { return Matrixd<2, 2>{{1.0, 0.0}, {0.0, 1.0}} * x + @@ -20,7 +20,7 @@ Vectord<2> StateDynamics(const Vectord<2>& x) { } TEST(ControlAffinePlantInversionFeedforwardTest, Calculate) { - frc::ControlAffinePlantInversionFeedforward<2, 1> feedforward{&Dynamics, + wpi::math::ControlAffinePlantInversionFeedforward<2, 1> feedforward{&Dynamics, 20_ms}; Vectord<2> r{2, 2}; @@ -30,7 +30,7 @@ TEST(ControlAffinePlantInversionFeedforwardTest, Calculate) { } TEST(ControlAffinePlantInversionFeedforwardTest, CalculateState) { - frc::ControlAffinePlantInversionFeedforward<2, 1> feedforward{ + wpi::math::ControlAffinePlantInversionFeedforward<2, 1> feedforward{ &StateDynamics, Matrixd<2, 1>{{0.0}, {1.0}}, 20_ms}; Vectord<2> r{2, 2}; @@ -39,4 +39,4 @@ TEST(ControlAffinePlantInversionFeedforwardTest, CalculateState) { EXPECT_NEAR(48, feedforward.Calculate(r, nextR)(0, 0), 1e-6); } -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/test/native/cpp/controller/DifferentialDriveAccelerationLimiterTest.cpp b/wpimath/src/test/native/cpp/controller/DifferentialDriveAccelerationLimiterTest.cpp index 4fa9ba29e6..5ea7f9c631 100644 --- a/wpimath/src/test/native/cpp/controller/DifferentialDriveAccelerationLimiterTest.cpp +++ b/wpimath/src/test/native/cpp/controller/DifferentialDriveAccelerationLimiterTest.cpp @@ -8,11 +8,11 @@ #include "wpi/math/system/plant/LinearSystemId.hpp" #include "wpi/units/math.hpp" -namespace frc { +namespace wpi::math { TEST(DifferentialDriveAccelerationLimiterTest, LowLimits) { constexpr auto trackwidth = 0.9_m; - constexpr units::second_t dt = 5_ms; + constexpr wpi::units::second_t dt = 5_ms; constexpr auto maxA = 2_mps_sq; constexpr auto maxAlpha = 2_rad_per_s_sq; @@ -31,15 +31,15 @@ TEST(DifferentialDriveAccelerationLimiterTest, LowLimits) { { Vectord<2> accels = plant.A() * xAccelLimiter + plant.B() * Vectord<2>{12.0, 12.0}; - units::meters_per_second_squared_t a{(accels(0) + accels(1)) / 2.0}; - EXPECT_GT(units::math::abs(a), maxA); + wpi::units::meters_per_second_squared_t a{(accels(0) + accels(1)) / 2.0}; + EXPECT_GT(wpi::units::math::abs(a), maxA); } { Vectord<2> accels = plant.A() * xAccelLimiter + plant.B() * Vectord<2>{-12.0, 12.0}; - units::radians_per_second_squared_t alpha{(accels(1) - accels(0)) / + wpi::units::radians_per_second_squared_t alpha{(accels(1) - accels(0)) / trackwidth.value()}; - EXPECT_GT(units::math::abs(alpha), maxAlpha); + EXPECT_GT(wpi::units::math::abs(alpha), maxAlpha); } // Forward @@ -47,19 +47,19 @@ TEST(DifferentialDriveAccelerationLimiterTest, LowLimits) { for (auto t = 0_s; t < 3_s; t += dt) { x = plant.CalculateX(x, u, dt); auto [left, right] = - accelLimiter.Calculate(units::meters_per_second_t{xAccelLimiter(0)}, - units::meters_per_second_t{xAccelLimiter(1)}, - units::volt_t{u(0)}, units::volt_t{u(1)}); + accelLimiter.Calculate(wpi::units::meters_per_second_t{xAccelLimiter(0)}, + wpi::units::meters_per_second_t{xAccelLimiter(1)}, + wpi::units::volt_t{u(0)}, wpi::units::volt_t{u(1)}); xAccelLimiter = plant.CalculateX(xAccelLimiter, Vectord<2>{left, right}, dt); Vectord<2> accels = plant.A() * xAccelLimiter + plant.B() * Vectord<2>{left, right}; - units::meters_per_second_squared_t a{(accels(0) + accels(1)) / 2.0}; - units::radians_per_second_squared_t alpha{(accels(1) - accels(0)) / + wpi::units::meters_per_second_squared_t a{(accels(0) + accels(1)) / 2.0}; + wpi::units::radians_per_second_squared_t alpha{(accels(1) - accels(0)) / trackwidth.value()}; - EXPECT_LE(units::math::abs(a), maxA); - EXPECT_LE(units::math::abs(alpha), maxAlpha); + EXPECT_LE(wpi::units::math::abs(a), maxA); + EXPECT_LE(wpi::units::math::abs(alpha), maxAlpha); } // Backward @@ -67,19 +67,19 @@ TEST(DifferentialDriveAccelerationLimiterTest, LowLimits) { for (auto t = 0_s; t < 3_s; t += dt) { x = plant.CalculateX(x, u, dt); auto [left, right] = - accelLimiter.Calculate(units::meters_per_second_t{xAccelLimiter(0)}, - units::meters_per_second_t{xAccelLimiter(1)}, - units::volt_t{u(0)}, units::volt_t{u(1)}); + accelLimiter.Calculate(wpi::units::meters_per_second_t{xAccelLimiter(0)}, + wpi::units::meters_per_second_t{xAccelLimiter(1)}, + wpi::units::volt_t{u(0)}, wpi::units::volt_t{u(1)}); xAccelLimiter = plant.CalculateX(xAccelLimiter, Vectord<2>{left, right}, dt); Vectord<2> accels = plant.A() * xAccelLimiter + plant.B() * Vectord<2>{left, right}; - units::meters_per_second_squared_t a{(accels(0) + accels(1)) / 2.0}; - units::radians_per_second_squared_t alpha{(accels(1) - accels(0)) / + wpi::units::meters_per_second_squared_t a{(accels(0) + accels(1)) / 2.0}; + wpi::units::radians_per_second_squared_t alpha{(accels(1) - accels(0)) / trackwidth.value()}; - EXPECT_LE(units::math::abs(a), maxA); - EXPECT_LE(units::math::abs(alpha), maxAlpha); + EXPECT_LE(wpi::units::math::abs(a), maxA); + EXPECT_LE(wpi::units::math::abs(alpha), maxAlpha); } // Rotate CCW @@ -87,25 +87,25 @@ TEST(DifferentialDriveAccelerationLimiterTest, LowLimits) { for (auto t = 0_s; t < 3_s; t += dt) { x = plant.CalculateX(x, u, dt); auto [left, right] = - accelLimiter.Calculate(units::meters_per_second_t{xAccelLimiter(0)}, - units::meters_per_second_t{xAccelLimiter(1)}, - units::volt_t{u(0)}, units::volt_t{u(1)}); + accelLimiter.Calculate(wpi::units::meters_per_second_t{xAccelLimiter(0)}, + wpi::units::meters_per_second_t{xAccelLimiter(1)}, + wpi::units::volt_t{u(0)}, wpi::units::volt_t{u(1)}); xAccelLimiter = plant.CalculateX(xAccelLimiter, Vectord<2>{left, right}, dt); Vectord<2> accels = plant.A() * xAccelLimiter + plant.B() * Vectord<2>{left, right}; - units::meters_per_second_squared_t a{(accels(0) + accels(1)) / 2.0}; - units::radians_per_second_squared_t alpha{(accels(1) - accels(0)) / + wpi::units::meters_per_second_squared_t a{(accels(0) + accels(1)) / 2.0}; + wpi::units::radians_per_second_squared_t alpha{(accels(1) - accels(0)) / trackwidth.value()}; - EXPECT_LE(units::math::abs(a), maxA); - EXPECT_LE(units::math::abs(alpha), maxAlpha); + EXPECT_LE(wpi::units::math::abs(a), maxA); + EXPECT_LE(wpi::units::math::abs(alpha), maxAlpha); } } TEST(DifferentialDriveAccelerationLimiterTest, HighLimits) { constexpr auto trackwidth = 0.9_m; - constexpr units::second_t dt = 5_ms; + constexpr wpi::units::second_t dt = 5_ms; using Kv_t = decltype(1_V / 1_mps); using Ka_t = decltype(1_V / 1_mps_sq); @@ -126,9 +126,9 @@ TEST(DifferentialDriveAccelerationLimiterTest, HighLimits) { for (auto t = 0_s; t < 3_s; t += dt) { x = plant.CalculateX(x, u, dt); auto [left, right] = - accelLimiter.Calculate(units::meters_per_second_t{xAccelLimiter(0)}, - units::meters_per_second_t{xAccelLimiter(1)}, - units::volt_t{u(0)}, units::volt_t{u(1)}); + accelLimiter.Calculate(wpi::units::meters_per_second_t{xAccelLimiter(0)}, + wpi::units::meters_per_second_t{xAccelLimiter(1)}, + wpi::units::volt_t{u(0)}, wpi::units::volt_t{u(1)}); xAccelLimiter = plant.CalculateX(xAccelLimiter, Vectord<2>{left, right}, dt); @@ -143,9 +143,9 @@ TEST(DifferentialDriveAccelerationLimiterTest, HighLimits) { for (auto t = 0_s; t < 3_s; t += dt) { x = plant.CalculateX(x, u, dt); auto [left, right] = - accelLimiter.Calculate(units::meters_per_second_t{xAccelLimiter(0)}, - units::meters_per_second_t{xAccelLimiter(1)}, - units::volt_t{u(0)}, units::volt_t{u(1)}); + accelLimiter.Calculate(wpi::units::meters_per_second_t{xAccelLimiter(0)}, + wpi::units::meters_per_second_t{xAccelLimiter(1)}, + wpi::units::volt_t{u(0)}, wpi::units::volt_t{u(1)}); xAccelLimiter = plant.CalculateX(xAccelLimiter, Vectord<2>{left, right}, dt); @@ -160,9 +160,9 @@ TEST(DifferentialDriveAccelerationLimiterTest, HighLimits) { for (auto t = 0_s; t < 3_s; t += dt) { x = plant.CalculateX(x, u, dt); auto [left, right] = - accelLimiter.Calculate(units::meters_per_second_t{xAccelLimiter(0)}, - units::meters_per_second_t{xAccelLimiter(1)}, - units::volt_t{u(0)}, units::volt_t{u(1)}); + accelLimiter.Calculate(wpi::units::meters_per_second_t{xAccelLimiter(0)}, + wpi::units::meters_per_second_t{xAccelLimiter(1)}, + wpi::units::volt_t{u(0)}, wpi::units::volt_t{u(1)}); xAccelLimiter = plant.CalculateX(xAccelLimiter, Vectord<2>{left, right}, dt); @@ -173,7 +173,7 @@ TEST(DifferentialDriveAccelerationLimiterTest, HighLimits) { TEST(DifferentialDriveAccelerationLimiterTest, SeparateMinMaxLowLimits) { constexpr auto trackwidth = 0.9_m; - constexpr units::second_t dt = 5_ms; + constexpr wpi::units::second_t dt = 5_ms; constexpr auto minA = -1_mps_sq; constexpr auto maxA = 2_mps_sq; constexpr auto maxAlpha = 2_rad_per_s_sq; @@ -193,9 +193,9 @@ TEST(DifferentialDriveAccelerationLimiterTest, SeparateMinMaxLowLimits) { { Vectord<2> accels = plant.A() * xAccelLimiter + plant.B() * Vectord<2>{12.0, 12.0}; - units::meters_per_second_squared_t a{(accels(0) + accels(1)) / 2.0}; - EXPECT_GT(units::math::abs(a), maxA); - EXPECT_GT(units::math::abs(a), -minA); + wpi::units::meters_per_second_squared_t a{(accels(0) + accels(1)) / 2.0}; + EXPECT_GT(wpi::units::math::abs(a), maxA); + EXPECT_GT(wpi::units::math::abs(a), -minA); } // a should always be within [minA, maxA] @@ -204,15 +204,15 @@ TEST(DifferentialDriveAccelerationLimiterTest, SeparateMinMaxLowLimits) { for (auto t = 0_s; t < 3_s; t += dt) { x = plant.CalculateX(x, u, dt); auto [left, right] = - accelLimiter.Calculate(units::meters_per_second_t{xAccelLimiter(0)}, - units::meters_per_second_t{xAccelLimiter(1)}, - units::volt_t{u(0)}, units::volt_t{u(1)}); + accelLimiter.Calculate(wpi::units::meters_per_second_t{xAccelLimiter(0)}, + wpi::units::meters_per_second_t{xAccelLimiter(1)}, + wpi::units::volt_t{u(0)}, wpi::units::volt_t{u(1)}); xAccelLimiter = plant.CalculateX(xAccelLimiter, Vectord<2>{left, right}, dt); Vectord<2> accels = plant.A() * xAccelLimiter + plant.B() * Vectord<2>{left, right}; - units::meters_per_second_squared_t a{(accels(0) + accels(1)) / 2.0}; + wpi::units::meters_per_second_squared_t a{(accels(0) + accels(1)) / 2.0}; EXPECT_GE(a, minA); EXPECT_LE(a, maxA); } @@ -222,15 +222,15 @@ TEST(DifferentialDriveAccelerationLimiterTest, SeparateMinMaxLowLimits) { for (auto t = 0_s; t < 3_s; t += dt) { x = plant.CalculateX(x, u, dt); auto [left, right] = - accelLimiter.Calculate(units::meters_per_second_t{xAccelLimiter(0)}, - units::meters_per_second_t{xAccelLimiter(1)}, - units::volt_t{u(0)}, units::volt_t{u(1)}); + accelLimiter.Calculate(wpi::units::meters_per_second_t{xAccelLimiter(0)}, + wpi::units::meters_per_second_t{xAccelLimiter(1)}, + wpi::units::volt_t{u(0)}, wpi::units::volt_t{u(1)}); xAccelLimiter = plant.CalculateX(xAccelLimiter, Vectord<2>{left, right}, dt); Vectord<2> accels = plant.A() * xAccelLimiter + plant.B() * Vectord<2>{left, right}; - units::meters_per_second_squared_t a{(accels(0) + accels(1)) / 2.0}; + wpi::units::meters_per_second_squared_t a{(accels(0) + accels(1)) / 2.0}; EXPECT_GE(a, minA); EXPECT_LE(a, maxA); } @@ -254,4 +254,4 @@ TEST(DifferentialDriveAccelerationLimiterTest, MinAccelGreaterThanMaxAccel) { std::invalid_argument); } -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/test/native/cpp/controller/DifferentialDriveFeedforwardTest.cpp b/wpimath/src/test/native/cpp/controller/DifferentialDriveFeedforwardTest.cpp index 56bdc0b0b2..c08962358b 100644 --- a/wpimath/src/test/native/cpp/controller/DifferentialDriveFeedforwardTest.cpp +++ b/wpimath/src/test/native/cpp/controller/DifferentialDriveFeedforwardTest.cpp @@ -20,12 +20,12 @@ TEST(DifferentialDriveFeedforwardTest, CalculateWithTrackwidth) { constexpr auto kVAngular = 1_V / 1_rad_per_s; constexpr auto kAAngular = 1_V / 1_rad_per_s_sq; constexpr auto trackwidth = 1_m; - constexpr units::second_t dt = 20_ms; + constexpr wpi::units::second_t dt = 20_ms; - frc::DifferentialDriveFeedforward differentialDriveFeedforward{ + wpi::math::DifferentialDriveFeedforward differentialDriveFeedforward{ kVLinear, kALinear, kVAngular, kAAngular, trackwidth}; - frc::LinearSystem<2, 2, 2> plant = - frc::LinearSystemId::IdentifyDrivetrainSystem( + wpi::math::LinearSystem<2, 2, 2> plant = + wpi::math::LinearSystemId::IdentifyDrivetrainSystem( kVLinear, kALinear, kVAngular, kAAngular, trackwidth); for (auto currentLeftVelocity = -4_mps; currentLeftVelocity <= 4_mps; currentLeftVelocity += 2_mps) { @@ -54,12 +54,12 @@ TEST(DifferentialDriveFeedforwardTest, CalculateWithoutTrackwidth) { constexpr auto kALinear = 1_V / 1_mps_sq; constexpr auto kVAngular = 1_V / 1_mps; constexpr auto kAAngular = 1_V / 1_mps_sq; - constexpr units::second_t dt = 20_ms; + constexpr wpi::units::second_t dt = 20_ms; - frc::DifferentialDriveFeedforward differentialDriveFeedforward{ + wpi::math::DifferentialDriveFeedforward differentialDriveFeedforward{ kVLinear, kALinear, kVAngular, kAAngular}; - frc::LinearSystem<2, 2, 2> plant = - frc::LinearSystemId::IdentifyDrivetrainSystem(kVLinear, kALinear, + wpi::math::LinearSystem<2, 2, 2> plant = + wpi::math::LinearSystemId::IdentifyDrivetrainSystem(kVLinear, kALinear, kVAngular, kAAngular); for (auto currentLeftVelocity = -4_mps; currentLeftVelocity <= 4_mps; currentLeftVelocity += 2_mps) { diff --git a/wpimath/src/test/native/cpp/controller/ElevatorFeedforwardTest.cpp b/wpimath/src/test/native/cpp/controller/ElevatorFeedforwardTest.cpp index 5c3bfc395d..3ef46491aa 100644 --- a/wpimath/src/test/native/cpp/controller/ElevatorFeedforwardTest.cpp +++ b/wpimath/src/test/native/cpp/controller/ElevatorFeedforwardTest.cpp @@ -19,24 +19,24 @@ static constexpr auto Ka = 2_V * 1_s * 1_s / 1_m; static constexpr auto Kg = 1_V; TEST(ElevatorFeedforwardTest, Calculate) { - frc::ElevatorFeedforward elevatorFF{Ks, Kg, Kv, Ka}; + wpi::math::ElevatorFeedforward elevatorFF{Ks, Kg, Kv, Ka}; EXPECT_NEAR(elevatorFF.Calculate(0_m / 1_s).value(), Kg.value(), 0.002); EXPECT_NEAR(elevatorFF.Calculate(2_m / 1_s).value(), 4.5, 0.002); - frc::Matrixd<1, 1> A{-Kv.value() / Ka.value()}; - frc::Matrixd<1, 1> B{1.0 / Ka.value()}; - constexpr units::second_t dt = 20_ms; - frc::LinearPlantInversionFeedforward<1, 1> plantInversion{A, B, dt}; + wpi::math::Matrixd<1, 1> A{-Kv.value() / Ka.value()}; + wpi::math::Matrixd<1, 1> B{1.0 / Ka.value()}; + constexpr wpi::units::second_t dt = 20_ms; + wpi::math::LinearPlantInversionFeedforward<1, 1> plantInversion{A, B, dt}; - frc::Vectord<1> r{2.0}; - frc::Vectord<1> nextR{3.0}; + wpi::math::Vectord<1> r{2.0}; + wpi::math::Vectord<1> nextR{3.0}; EXPECT_NEAR(plantInversion.Calculate(r, nextR)(0) + Ks.value() + Kg.value(), elevatorFF.Calculate(2_mps, 3_mps).value(), 0.002); } TEST(ElevatorFeedforwardTest, AchievableVelocity) { - frc::ElevatorFeedforward elevatorFF{Ks, Kg, Kv, Ka}; + wpi::math::ElevatorFeedforward elevatorFF{Ks, Kg, Kv, Ka}; EXPECT_NEAR(elevatorFF.MaxAchievableVelocity(11_V, 1_m / 1_s / 1_s).value(), 5, 0.002); EXPECT_NEAR(elevatorFF.MinAchievableVelocity(11_V, 1_m / 1_s / 1_s).value(), @@ -44,7 +44,7 @@ TEST(ElevatorFeedforwardTest, AchievableVelocity) { } TEST(ElevatorFeedforwardTest, AchievableAcceleration) { - frc::ElevatorFeedforward elevatorFF{Ks, Kg, Kv, Ka}; + wpi::math::ElevatorFeedforward elevatorFF{Ks, Kg, Kv, Ka}; EXPECT_NEAR(elevatorFF.MaxAchievableAcceleration(12_V, 2_m / 1_s).value(), 3.75, 0.002); EXPECT_NEAR(elevatorFF.MaxAchievableAcceleration(12_V, -2_m / 1_s).value(), @@ -56,7 +56,7 @@ TEST(ElevatorFeedforwardTest, AchievableAcceleration) { } TEST(ElevatorFeedforwardTest, NegativeGains) { - frc::ElevatorFeedforward elevatorFF{Ks, Kg, -Kv, -Ka}; + wpi::math::ElevatorFeedforward elevatorFF{Ks, Kg, -Kv, -Ka}; EXPECT_EQ(elevatorFF.GetKv().value(), 0); EXPECT_EQ(elevatorFF.GetKa().value(), 0); } diff --git a/wpimath/src/test/native/cpp/controller/ImplicitModelFollowerTest.cpp b/wpimath/src/test/native/cpp/controller/ImplicitModelFollowerTest.cpp index 7f43e2a80d..97472a9494 100644 --- a/wpimath/src/test/native/cpp/controller/ImplicitModelFollowerTest.cpp +++ b/wpimath/src/test/native/cpp/controller/ImplicitModelFollowerTest.cpp @@ -7,10 +7,10 @@ #include "wpi/math/controller/ImplicitModelFollower.hpp" #include "wpi/math/system/plant/LinearSystemId.hpp" -namespace frc { +namespace wpi::math { TEST(ImplicitModelFollowerTest, SameModel) { - constexpr units::second_t dt = 5_ms; + constexpr wpi::units::second_t dt = 5_ms; using Kv_t = decltype(1_V / 1_mps); using Ka_t = decltype(1_V / 1_mps_sq); @@ -54,7 +54,7 @@ TEST(ImplicitModelFollowerTest, SameModel) { } TEST(ImplicitModelFollowerTest, SlowerRefModel) { - constexpr units::second_t dt = 5_ms; + constexpr wpi::units::second_t dt = 5_ms; using Kv_t = decltype(1_V / 1_mps); using Ka_t = decltype(1_V / 1_mps_sq); @@ -106,4 +106,4 @@ TEST(ImplicitModelFollowerTest, SlowerRefModel) { } } -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/test/native/cpp/controller/LTVDifferentialDriveControllerTest.cpp b/wpimath/src/test/native/cpp/controller/LTVDifferentialDriveControllerTest.cpp index 406ce3c3af..2f2fa11bd6 100644 --- a/wpimath/src/test/native/cpp/controller/LTVDifferentialDriveControllerTest.cpp +++ b/wpimath/src/test/native/cpp/controller/LTVDifferentialDriveControllerTest.cpp @@ -14,10 +14,10 @@ #include "wpi/units/math.hpp" #define EXPECT_NEAR_UNITS(val1, val2, eps) \ - EXPECT_LE(units::math::abs(val1 - val2), eps) + EXPECT_LE(wpi::units::math::abs(val1 - val2), eps) -static constexpr units::meter_t kTolerance{1 / 12.0}; -static constexpr units::radian_t kAngularTolerance{2.0 * std::numbers::pi / +static constexpr wpi::units::meter_t kTolerance{1 / 12.0}; +static constexpr wpi::units::radian_t kAngularTolerance{2.0 * std::numbers::pi / 180.0}; /** @@ -45,14 +45,14 @@ static constexpr auto kLinearV = 3.02_V / 1_mps; static constexpr auto kLinearA = 0.642_V / 1_mps_sq; static constexpr auto kAngularV = 1.382_V / 1_mps; static constexpr auto kAngularA = 0.08495_V / 1_mps_sq; -static auto plant = frc::LinearSystemId::IdentifyDrivetrainSystem( +static auto plant = wpi::math::LinearSystemId::IdentifyDrivetrainSystem( kLinearV, kLinearA, kAngularV, kAngularA); static constexpr auto kTrackwidth = 0.9_m; -frc::Vectord<5> Dynamics(const frc::Vectord<5>& x, const frc::Vectord<2>& u) { +wpi::math::Vectord<5> Dynamics(const wpi::math::Vectord<5>& x, const wpi::math::Vectord<2>& u) { double v = (x(State::kLeftVelocity) + x(State::kRightVelocity)) / 2.0; - frc::Vectord<5> xdot; + wpi::math::Vectord<5> xdot; xdot(0) = v * std::cos(x(State::kHeading)); xdot(1) = v * std::sin(x(State::kHeading)); xdot(2) = ((x(State::kRightVelocity) - x(State::kLeftVelocity)) / kTrackwidth) @@ -62,18 +62,18 @@ frc::Vectord<5> Dynamics(const frc::Vectord<5>& x, const frc::Vectord<2>& u) { } TEST(LTVDifferentialDriveControllerTest, ReachesReference) { - constexpr units::second_t kDt = 20_ms; + constexpr wpi::units::second_t kDt = 20_ms; - frc::LTVDifferentialDriveController controller{ + wpi::math::LTVDifferentialDriveController controller{ plant, kTrackwidth, {0.0625, 0.125, 2.5, 0.95, 0.95}, {12.0, 12.0}, kDt}; - frc::Pose2d robotPose{2.7_m, 23_m, 0_deg}; + wpi::math::Pose2d robotPose{2.7_m, 23_m, 0_deg}; - auto waypoints = std::vector{frc::Pose2d{2.75_m, 22.521_m, 0_rad}, - frc::Pose2d{24.73_m, 19.68_m, 5.846_rad}}; - auto trajectory = frc::TrajectoryGenerator::GenerateTrajectory( + auto waypoints = std::vector{wpi::math::Pose2d{2.75_m, 22.521_m, 0_rad}, + wpi::math::Pose2d{24.73_m, 19.68_m, 5.846_rad}}; + auto trajectory = wpi::math::TrajectoryGenerator::GenerateTrajectory( waypoints, {8.8_mps, 0.1_mps_sq}); - frc::Vectord<5> x = frc::Vectord<5>::Zero(); + wpi::math::Vectord<5> x = wpi::math::Vectord<5>::Zero(); x(State::kX) = robotPose.X().value(); x(State::kY) = robotPose.Y().value(); x(State::kHeading) = robotPose.Rotation().Radians().value(); @@ -82,21 +82,21 @@ TEST(LTVDifferentialDriveControllerTest, ReachesReference) { for (size_t i = 0; i < (totalTime / kDt).value(); ++i) { auto state = trajectory.Sample(kDt * i); robotPose = - frc::Pose2d{units::meter_t{x(State::kX)}, units::meter_t{x(State::kY)}, - units::radian_t{x(State::kHeading)}}; + wpi::math::Pose2d{wpi::units::meter_t{x(State::kX)}, wpi::units::meter_t{x(State::kY)}, + wpi::units::radian_t{x(State::kHeading)}}; auto [leftVoltage, rightVoltage] = controller.Calculate( - robotPose, units::meters_per_second_t{x(State::kLeftVelocity)}, - units::meters_per_second_t{x(State::kRightVelocity)}, state); + robotPose, wpi::units::meters_per_second_t{x(State::kLeftVelocity)}, + wpi::units::meters_per_second_t{x(State::kRightVelocity)}, state); - x = frc::RKDP(&Dynamics, x, - frc::Vectord<2>{leftVoltage.value(), rightVoltage.value()}, + x = wpi::math::RKDP(&Dynamics, x, + wpi::math::Vectord<2>{leftVoltage.value(), rightVoltage.value()}, kDt); } auto& endPose = trajectory.States().back().pose; EXPECT_NEAR_UNITS(endPose.X(), robotPose.X(), kTolerance); EXPECT_NEAR_UNITS(endPose.Y(), robotPose.Y(), kTolerance); - EXPECT_NEAR_UNITS(frc::AngleModulus(endPose.Rotation().Radians() - + EXPECT_NEAR_UNITS(wpi::math::AngleModulus(endPose.Rotation().Radians() - robotPose.Rotation().Radians()), 0_rad, kAngularTolerance); } diff --git a/wpimath/src/test/native/cpp/controller/LTVUnicycleControllerTest.cpp b/wpimath/src/test/native/cpp/controller/LTVUnicycleControllerTest.cpp index db2482137d..ae92929172 100644 --- a/wpimath/src/test/native/cpp/controller/LTVUnicycleControllerTest.cpp +++ b/wpimath/src/test/native/cpp/controller/LTVUnicycleControllerTest.cpp @@ -10,21 +10,21 @@ #include "wpi/units/math.hpp" #define EXPECT_NEAR_UNITS(val1, val2, eps) \ - EXPECT_LE(units::math::abs(val1 - val2), eps) + EXPECT_LE(wpi::units::math::abs(val1 - val2), eps) -static constexpr units::meter_t kTolerance{1 / 12.0}; -static constexpr units::radian_t kAngularTolerance{2.0 * std::numbers::pi / +static constexpr wpi::units::meter_t kTolerance{1 / 12.0}; +static constexpr wpi::units::radian_t kAngularTolerance{2.0 * std::numbers::pi / 180.0}; TEST(LTVUnicycleControllerTest, ReachesReference) { - constexpr units::second_t kDt = 20_ms; + constexpr wpi::units::second_t kDt = 20_ms; - frc::LTVUnicycleController controller{{0.0625, 0.125, 2.5}, {4.0, 4.0}, kDt}; - frc::Pose2d robotPose{2.7_m, 23_m, 0_deg}; + wpi::math::LTVUnicycleController controller{{0.0625, 0.125, 2.5}, {4.0, 4.0}, kDt}; + wpi::math::Pose2d robotPose{2.7_m, 23_m, 0_deg}; - auto waypoints = std::vector{frc::Pose2d{2.75_m, 22.521_m, 0_rad}, - frc::Pose2d{24.73_m, 19.68_m, 5.846_rad}}; - auto trajectory = frc::TrajectoryGenerator::GenerateTrajectory( + auto waypoints = std::vector{wpi::math::Pose2d{2.75_m, 22.521_m, 0_rad}, + wpi::math::Pose2d{24.73_m, 19.68_m, 5.846_rad}}; + auto trajectory = wpi::math::TrajectoryGenerator::GenerateTrajectory( waypoints, {8.8_mps, 0.1_mps_sq}); auto totalTime = trajectory.TotalTime(); @@ -33,13 +33,13 @@ TEST(LTVUnicycleControllerTest, ReachesReference) { auto [vx, vy, omega] = controller.Calculate(robotPose, state); static_cast(vy); - robotPose = robotPose + frc::Twist2d{vx * kDt, 0_m, omega * kDt}.Exp(); + robotPose = robotPose + wpi::math::Twist2d{vx * kDt, 0_m, omega * kDt}.Exp(); } auto& endPose = trajectory.States().back().pose; EXPECT_NEAR_UNITS(endPose.X(), robotPose.X(), kTolerance); EXPECT_NEAR_UNITS(endPose.Y(), robotPose.Y(), kTolerance); - EXPECT_NEAR_UNITS(frc::AngleModulus(endPose.Rotation().Radians() - + EXPECT_NEAR_UNITS(wpi::math::AngleModulus(endPose.Rotation().Radians() - robotPose.Rotation().Radians()), 0_rad, kAngularTolerance); } diff --git a/wpimath/src/test/native/cpp/controller/LinearPlantInversionFeedforwardTest.cpp b/wpimath/src/test/native/cpp/controller/LinearPlantInversionFeedforwardTest.cpp index eadce768de..e5f877e974 100644 --- a/wpimath/src/test/native/cpp/controller/LinearPlantInversionFeedforwardTest.cpp +++ b/wpimath/src/test/native/cpp/controller/LinearPlantInversionFeedforwardTest.cpp @@ -10,13 +10,13 @@ #include "wpi/math/linalg/EigenCore.hpp" #include "wpi/units/time.hpp" -namespace frc { +namespace wpi::math { TEST(LinearPlantInversionFeedforwardTest, Calculate) { Matrixd<2, 2> A{{1, 0}, {0, 1}}; Matrixd<2, 1> B{0, 1}; - frc::LinearPlantInversionFeedforward<2, 1> feedforward{A, B, 20_ms}; + wpi::math::LinearPlantInversionFeedforward<2, 1> feedforward{A, B, 20_ms}; Vectord<2> r{2, 2}; Vectord<2> nextR{3, 3}; @@ -24,4 +24,4 @@ TEST(LinearPlantInversionFeedforwardTest, Calculate) { EXPECT_NEAR(47.502599, feedforward.Calculate(r, nextR)(0, 0), 0.002); } -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/test/native/cpp/controller/LinearQuadraticRegulatorTest.cpp b/wpimath/src/test/native/cpp/controller/LinearQuadraticRegulatorTest.cpp index f4f8440229..aa9372faba 100644 --- a/wpimath/src/test/native/cpp/controller/LinearQuadraticRegulatorTest.cpp +++ b/wpimath/src/test/native/cpp/controller/LinearQuadraticRegulatorTest.cpp @@ -13,7 +13,7 @@ #include "wpi/math/system/plant/LinearSystemId.hpp" #include "wpi/units/time.hpp" -namespace frc { +namespace wpi::math { TEST(LinearQuadraticRegulatorTest, ElevatorGains) { LinearSystem<2, 1, 1> plant = [] { @@ -28,7 +28,7 @@ TEST(LinearQuadraticRegulatorTest, ElevatorGains) { // Gear ratio constexpr double G = 40.0 / 40.0; - return frc::LinearSystemId::ElevatorSystem(motors, m, r, G).Slice(0); + return wpi::math::LinearSystemId::ElevatorSystem(motors, m, r, G).Slice(0); }(); Matrixd<1, 2> K = LinearQuadraticRegulator<2, 1>{plant, {0.02, 0.4}, {12.0}, 5_ms}.K(); @@ -50,7 +50,7 @@ TEST(LinearQuadraticRegulatorTest, ArmGains) { // Gear ratio constexpr double G = 100.0; - return frc::LinearSystemId::SingleJointedArmSystem(motors, + return wpi::math::LinearSystemId::SingleJointedArmSystem(motors, 1.0 / 3.0 * m * r * r, G) .Slice(0); }(); @@ -76,7 +76,7 @@ TEST(LinearQuadraticRegulatorTest, FourMotorElevator) { // Gear ratio constexpr double G = 14.67; - return frc::LinearSystemId::ElevatorSystem(motors, m, r, G).Slice(0); + return wpi::math::LinearSystemId::ElevatorSystem(motors, m, r, G).Slice(0); }(); Matrixd<1, 2> K = LinearQuadraticRegulator<2, 1>{plant, {0.1, 0.2}, {12.0}, 20_ms}.K(); @@ -103,7 +103,7 @@ template Matrixd GetImplicitModelFollowingK( const Matrixd& A, const Matrixd& B, const Matrixd& Q, const Matrixd& R, - const Matrixd& Aref, units::second_t dt) { + const Matrixd& Aref, wpi::units::second_t dt) { // Discretize real dynamics Matrixd discA; Matrixd discB; @@ -178,7 +178,7 @@ TEST(LinearQuadraticRegulatorTest, LatencyCompensate) { // Gear ratio constexpr double G = 14.67; - return frc::LinearSystemId::ElevatorSystem(motors, m, r, G).Slice(0); + return wpi::math::LinearSystemId::ElevatorSystem(motors, m, r, G).Slice(0); }(); LinearQuadraticRegulator<2, 1> controller{plant, {0.1, 0.2}, {12.0}, 20_ms}; @@ -188,4 +188,4 @@ TEST(LinearQuadraticRegulatorTest, LatencyCompensate) { EXPECT_NEAR(0.07904881, controller.K(0, 1), 1e-3); } -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/test/native/cpp/controller/PIDInputOutputTest.cpp b/wpimath/src/test/native/cpp/controller/PIDInputOutputTest.cpp index c91bcc9a6c..aa0fb9a227 100644 --- a/wpimath/src/test/native/cpp/controller/PIDInputOutputTest.cpp +++ b/wpimath/src/test/native/cpp/controller/PIDInputOutputTest.cpp @@ -7,7 +7,7 @@ #include "wpi/math/controller/PIDController.hpp" TEST(PIDInputOutputTest, ContinuousInput) { - frc::PIDController controller{0.0, 0.0, 0.0}; + wpi::math::PIDController controller{0.0, 0.0, 0.0}; controller.SetP(1); controller.EnableContinuousInput(-180, 180); @@ -18,7 +18,7 @@ TEST(PIDInputOutputTest, ContinuousInput) { } TEST(PIDInputOutputTest, ProportionalGainOutput) { - frc::PIDController controller{0.0, 0.0, 0.0}; + wpi::math::PIDController controller{0.0, 0.0, 0.0}; controller.SetP(4); @@ -26,7 +26,7 @@ TEST(PIDInputOutputTest, ProportionalGainOutput) { } TEST(PIDInputOutputTest, IntegralGainOutput) { - frc::PIDController controller{0.0, 0.0, 0.0}; + wpi::math::PIDController controller{0.0, 0.0, 0.0}; controller.SetI(4); @@ -40,7 +40,7 @@ TEST(PIDInputOutputTest, IntegralGainOutput) { } TEST(PIDInputOutputTest, DerivativeGainOutput) { - frc::PIDController controller{0.0, 0.0, 0.0}; + wpi::math::PIDController controller{0.0, 0.0, 0.0}; controller.SetD(4); @@ -51,7 +51,7 @@ TEST(PIDInputOutputTest, DerivativeGainOutput) { } TEST(PIDInputOutputTest, IZoneNoOutput) { - frc::PIDController controller{0.0, 0.0, 0.0}; + wpi::math::PIDController controller{0.0, 0.0, 0.0}; controller.SetI(1); controller.SetIZone(1); @@ -62,7 +62,7 @@ TEST(PIDInputOutputTest, IZoneNoOutput) { } TEST(PIDInputOutputTest, IZoneOutput) { - frc::PIDController controller{0.0, 0.0, 0.0}; + wpi::math::PIDController controller{0.0, 0.0, 0.0}; controller.SetI(1); controller.SetIZone(1); diff --git a/wpimath/src/test/native/cpp/controller/PIDToleranceTest.cpp b/wpimath/src/test/native/cpp/controller/PIDToleranceTest.cpp index 5b13d5e6ef..dc46cc5e88 100644 --- a/wpimath/src/test/native/cpp/controller/PIDToleranceTest.cpp +++ b/wpimath/src/test/native/cpp/controller/PIDToleranceTest.cpp @@ -11,14 +11,14 @@ static constexpr double kRange = 200; static constexpr double kTolerance = 10.0; TEST(PIDToleranceTest, InitialTolerance) { - frc::PIDController controller{0.5, 0.0, 0.0}; + wpi::math::PIDController controller{0.5, 0.0, 0.0}; controller.EnableContinuousInput(-kRange / 2, kRange / 2); EXPECT_FALSE(controller.AtSetpoint()); } TEST(PIDToleranceTest, AbsoluteTolerance) { - frc::PIDController controller{0.5, 0.0, 0.0}; + wpi::math::PIDController controller{0.5, 0.0, 0.0}; controller.EnableContinuousInput(-kRange / 2, kRange / 2); EXPECT_FALSE(controller.AtSetpoint()); diff --git a/wpimath/src/test/native/cpp/controller/ProfiledPIDInputOutputTest.cpp b/wpimath/src/test/native/cpp/controller/ProfiledPIDInputOutputTest.cpp index 23e9940e1f..77b943ccac 100644 --- a/wpimath/src/test/native/cpp/controller/ProfiledPIDInputOutputTest.cpp +++ b/wpimath/src/test/native/cpp/controller/ProfiledPIDInputOutputTest.cpp @@ -12,86 +12,86 @@ #include "wpi/units/angular_velocity.hpp" TEST(ProfiledPIDInputOutputTest, ContinuousInput1) { - frc::ProfiledPIDController controller{ + wpi::math::ProfiledPIDController controller{ 0.0, 0.0, 0.0, {360_deg_per_s, 180_deg_per_s_sq}}; controller.SetP(1); controller.EnableContinuousInput(-180_deg, 180_deg); - static constexpr units::degree_t kSetpoint{-179.0}; - static constexpr units::degree_t kMeasurement{-179.0}; - static constexpr units::degree_t kGoal{179.0}; + static constexpr wpi::units::degree_t kSetpoint{-179.0}; + static constexpr wpi::units::degree_t kMeasurement{-179.0}; + static constexpr wpi::units::degree_t kGoal{179.0}; controller.Reset(kSetpoint); EXPECT_LT(controller.Calculate(kMeasurement, kGoal), 0.0); // Error must be less than half the input range at all times - EXPECT_LT(units::math::abs(controller.GetSetpoint().position - kMeasurement), + EXPECT_LT(wpi::units::math::abs(controller.GetSetpoint().position - kMeasurement), 180_deg); } TEST(ProfiledPIDInputOutputTest, ContinuousInput2) { - frc::ProfiledPIDController controller{ + wpi::math::ProfiledPIDController controller{ 0.0, 0.0, 0.0, {360_deg_per_s, 180_deg_per_s_sq}}; controller.SetP(1); - controller.EnableContinuousInput(-units::radian_t{std::numbers::pi}, - units::radian_t{std::numbers::pi}); + controller.EnableContinuousInput(-wpi::units::radian_t{std::numbers::pi}, + wpi::units::radian_t{std::numbers::pi}); - static constexpr units::radian_t kSetpoint{-3.4826633343199735}; - static constexpr units::radian_t kMeasurement{-3.1352207333939606}; - static constexpr units::radian_t kGoal{-3.534162788601621}; + static constexpr wpi::units::radian_t kSetpoint{-3.4826633343199735}; + static constexpr wpi::units::radian_t kMeasurement{-3.1352207333939606}; + static constexpr wpi::units::radian_t kGoal{-3.534162788601621}; controller.Reset(kSetpoint); EXPECT_LT(controller.Calculate(kMeasurement, kGoal), 0.0); // Error must be less than half the input range at all times - EXPECT_LT(units::math::abs(controller.GetSetpoint().position - kMeasurement), - units::radian_t{std::numbers::pi}); + EXPECT_LT(wpi::units::math::abs(controller.GetSetpoint().position - kMeasurement), + wpi::units::radian_t{std::numbers::pi}); } TEST(ProfiledPIDInputOutputTest, ContinuousInput3) { - frc::ProfiledPIDController controller{ + wpi::math::ProfiledPIDController controller{ 0.0, 0.0, 0.0, {360_deg_per_s, 180_deg_per_s_sq}}; controller.SetP(1); - controller.EnableContinuousInput(-units::radian_t{std::numbers::pi}, - units::radian_t{std::numbers::pi}); + controller.EnableContinuousInput(-wpi::units::radian_t{std::numbers::pi}, + wpi::units::radian_t{std::numbers::pi}); - static constexpr units::radian_t kSetpoint{-3.5176604690006377}; - static constexpr units::radian_t kMeasurement{3.1191729343822456}; - static constexpr units::radian_t kGoal{2.709680418117445}; + static constexpr wpi::units::radian_t kSetpoint{-3.5176604690006377}; + static constexpr wpi::units::radian_t kMeasurement{3.1191729343822456}; + static constexpr wpi::units::radian_t kGoal{2.709680418117445}; controller.Reset(kSetpoint); EXPECT_LT(controller.Calculate(kMeasurement, kGoal), 0.0); // Error must be less than half the input range at all times - EXPECT_LT(units::math::abs(controller.GetSetpoint().position - kMeasurement), - units::radian_t{std::numbers::pi}); + EXPECT_LT(wpi::units::math::abs(controller.GetSetpoint().position - kMeasurement), + wpi::units::radian_t{std::numbers::pi}); } TEST(ProfiledPIDInputOutputTest, ContinuousInput4) { - frc::ProfiledPIDController controller{ + wpi::math::ProfiledPIDController controller{ 0.0, 0.0, 0.0, {360_deg_per_s, 180_deg_per_s_sq}}; controller.SetP(1); controller.EnableContinuousInput(0_rad, - units::radian_t{2.0 * std::numbers::pi}); + wpi::units::radian_t{2.0 * std::numbers::pi}); - static constexpr units::radian_t kSetpoint{2.78}; - static constexpr units::radian_t kMeasurement{3.12}; - static constexpr units::radian_t kGoal{2.71}; + static constexpr wpi::units::radian_t kSetpoint{2.78}; + static constexpr wpi::units::radian_t kMeasurement{3.12}; + static constexpr wpi::units::radian_t kGoal{2.71}; controller.Reset(kSetpoint); EXPECT_LT(controller.Calculate(kMeasurement, kGoal), 0.0); // Error must be less than half the input range at all times - EXPECT_LT(units::math::abs(controller.GetSetpoint().position - kMeasurement), - units::radian_t{std::numbers::pi}); + EXPECT_LT(wpi::units::math::abs(controller.GetSetpoint().position - kMeasurement), + wpi::units::radian_t{std::numbers::pi}); } TEST(ProfiledPIDInputOutputTest, ProportionalGainOutput) { - frc::ProfiledPIDController controller{ + wpi::math::ProfiledPIDController controller{ 0.0, 0.0, 0.0, {360_deg_per_s, 180_deg_per_s_sq}}; controller.SetP(4); @@ -100,7 +100,7 @@ TEST(ProfiledPIDInputOutputTest, ProportionalGainOutput) { } TEST(ProfiledPIDInputOutputTest, IntegralGainOutput) { - frc::ProfiledPIDController controller{ + wpi::math::ProfiledPIDController controller{ 0.0, 0.0, 0.0, {360_deg_per_s, 180_deg_per_s_sq}}; controller.SetI(4); @@ -115,7 +115,7 @@ TEST(ProfiledPIDInputOutputTest, IntegralGainOutput) { } TEST(ProfiledPIDInputOutputTest, DerivativeGainOutput) { - frc::ProfiledPIDController controller{ + wpi::math::ProfiledPIDController controller{ 0.0, 0.0, 0.0, {360_deg_per_s, 180_deg_per_s_sq}}; controller.SetD(4); diff --git a/wpimath/src/test/native/cpp/controller/SimpleMotorFeedforwardTest.cpp b/wpimath/src/test/native/cpp/controller/SimpleMotorFeedforwardTest.cpp index 8545e663ca..8531adc129 100644 --- a/wpimath/src/test/native/cpp/controller/SimpleMotorFeedforwardTest.cpp +++ b/wpimath/src/test/native/cpp/controller/SimpleMotorFeedforwardTest.cpp @@ -14,19 +14,19 @@ #include "wpi/units/time.hpp" #include "wpi/units/velocity.hpp" -namespace frc { +namespace wpi::math { TEST(SimpleMotorFeedforwardTest, Calculate) { constexpr auto Ks = 0.5_V; constexpr auto Kv = 3_V / 1_mps; constexpr auto Ka = 0.6_V / 1_mps_sq; - constexpr units::second_t dt = 20_ms; + constexpr wpi::units::second_t dt = 20_ms; constexpr Matrixd<1, 1> A{{-Kv.value() / Ka.value()}}; constexpr Matrixd<1, 1> B{{1.0 / Ka.value()}}; - frc::LinearPlantInversionFeedforward<1, 1> plantInversion{A, B, dt}; - frc::SimpleMotorFeedforward simpleMotor{Ks, Kv, Ka}; + wpi::math::LinearPlantInversionFeedforward<1, 1> plantInversion{A, B, dt}; + wpi::math::SimpleMotorFeedforward simpleMotor{Ks, Kv, Ka}; constexpr Vectord<1> r{{2.0}}; constexpr Vectord<1> nextR{{3.0}}; @@ -46,11 +46,11 @@ TEST(SimpleMotorFeedforwardTest, NegativeGains) { constexpr auto Ks = 0.5_V; constexpr auto Kv = -3_V / 1_mps; constexpr auto Ka = -0.6_V / 1_mps_sq; - constexpr units::second_t dt = 0_ms; - frc::SimpleMotorFeedforward simpleMotor{Ks, Kv, Ka, dt}; + constexpr wpi::units::second_t dt = 0_ms; + wpi::math::SimpleMotorFeedforward simpleMotor{Ks, Kv, Ka, dt}; EXPECT_EQ(simpleMotor.GetKv().value(), 0); EXPECT_EQ(simpleMotor.GetKa().value(), 0); EXPECT_EQ(simpleMotor.GetDt().value(), 0.02); } -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/test/native/cpp/controller/proto/ArmFeedforwardProtoTest.cpp b/wpimath/src/test/native/cpp/controller/proto/ArmFeedforwardProtoTest.cpp index 7e7f1d1e90..aa73850915 100644 --- a/wpimath/src/test/native/cpp/controller/proto/ArmFeedforwardProtoTest.cpp +++ b/wpimath/src/test/native/cpp/controller/proto/ArmFeedforwardProtoTest.cpp @@ -7,7 +7,7 @@ #include "wpi/math/controller/ArmFeedforward.hpp" #include "wpi/util/SmallVector.hpp" -using namespace frc; +using namespace wpi::math; namespace { @@ -19,8 +19,8 @@ const ArmFeedforward kExpectedData{Ks, Kg, Kv, Ka}; } // namespace TEST(ArmFeedforwardProtoTest, Roundtrip) { - wpi::ProtobufMessage message; - wpi::SmallVector buf; + wpi::util::ProtobufMessage message; + wpi::util::SmallVector buf; ASSERT_TRUE(message.Pack(buf, kExpectedData)); auto unpacked_data = message.Unpack(buf); diff --git a/wpimath/src/test/native/cpp/controller/proto/DifferentialDriveFeedforwardProtoTest.cpp b/wpimath/src/test/native/cpp/controller/proto/DifferentialDriveFeedforwardProtoTest.cpp index ded81ce33c..e171790b3c 100644 --- a/wpimath/src/test/native/cpp/controller/proto/DifferentialDriveFeedforwardProtoTest.cpp +++ b/wpimath/src/test/native/cpp/controller/proto/DifferentialDriveFeedforwardProtoTest.cpp @@ -7,7 +7,7 @@ #include "../../ProtoTestBase.hpp" #include "wpi/math/controller/DifferentialDriveFeedforward.hpp" -using namespace frc; +using namespace wpi::math; struct DifferentialDriveFeedforwardProtoTestData { using Type = DifferentialDriveFeedforward; diff --git a/wpimath/src/test/native/cpp/controller/proto/DifferentialDriveWheelVoltagesProtoTest.cpp b/wpimath/src/test/native/cpp/controller/proto/DifferentialDriveWheelVoltagesProtoTest.cpp index 0aba8c90e1..f79cfbd40a 100644 --- a/wpimath/src/test/native/cpp/controller/proto/DifferentialDriveWheelVoltagesProtoTest.cpp +++ b/wpimath/src/test/native/cpp/controller/proto/DifferentialDriveWheelVoltagesProtoTest.cpp @@ -7,19 +7,19 @@ #include "wpi/math/controller/DifferentialDriveWheelVoltages.hpp" #include "wpi/util/SmallVector.hpp" -using namespace frc; +using namespace wpi::math; namespace { -using ProtoType = wpi::Protobuf; +using ProtoType = wpi::util::Protobuf; const DifferentialDriveWheelVoltages kExpectedData = DifferentialDriveWheelVoltages{0.174_V, 0.191_V}; } // namespace TEST(DifferentialDriveWheelVoltagesProtoTest, Roundtrip) { - wpi::ProtobufMessage message; - wpi::SmallVector buf; + wpi::util::ProtobufMessage message; + wpi::util::SmallVector buf; ASSERT_TRUE(message.Pack(buf, kExpectedData)); auto unpacked_data = message.Unpack(buf); diff --git a/wpimath/src/test/native/cpp/controller/proto/ElevatorFeedforwardProtoTest.cpp b/wpimath/src/test/native/cpp/controller/proto/ElevatorFeedforwardProtoTest.cpp index 483d9986cc..c48c93c8e7 100644 --- a/wpimath/src/test/native/cpp/controller/proto/ElevatorFeedforwardProtoTest.cpp +++ b/wpimath/src/test/native/cpp/controller/proto/ElevatorFeedforwardProtoTest.cpp @@ -7,7 +7,7 @@ #include "wpi/math/controller/ElevatorFeedforward.hpp" #include "wpi/util/SmallVector.hpp" -using namespace frc; +using namespace wpi::math; namespace { @@ -20,8 +20,8 @@ constexpr ElevatorFeedforward kExpectedData{Ks, Kg, Kv, Ka}; } // namespace TEST(ElevatorFeedforwardProtoTest, Roundtrip) { - wpi::ProtobufMessage message; - wpi::SmallVector buf; + wpi::util::ProtobufMessage message; + wpi::util::SmallVector buf; ASSERT_TRUE(message.Pack(buf, kExpectedData)); auto unpacked_data = message.Unpack(buf); diff --git a/wpimath/src/test/native/cpp/controller/proto/SimpleMotorFeedforwardProtoTest.cpp b/wpimath/src/test/native/cpp/controller/proto/SimpleMotorFeedforwardProtoTest.cpp index 627f0ba25e..8babb9fad9 100644 --- a/wpimath/src/test/native/cpp/controller/proto/SimpleMotorFeedforwardProtoTest.cpp +++ b/wpimath/src/test/native/cpp/controller/proto/SimpleMotorFeedforwardProtoTest.cpp @@ -10,15 +10,15 @@ #include "wpi/units/acceleration.hpp" #include "wpi/units/velocity.hpp" -using namespace frc; +using namespace wpi::math; template struct SimpleMotorFeedforwardProtoTestData { using Type = SimpleMotorFeedforward; inline static const Type kTestData = { - units::volt_t{0.4}, units::volt_t{4.0} / (units::unit_t{1} / 1_s), - units::volt_t{0.7} / (units::unit_t{1} / 1_s / 1_s), 25_ms}; + wpi::units::volt_t{0.4}, wpi::units::volt_t{4.0} / (wpi::units::unit_t{1} / 1_s), + wpi::units::volt_t{0.7} / (wpi::units::unit_t{1} / 1_s / 1_s), 25_ms}; static void CheckEq(const Type& testData, const Type& data) { EXPECT_EQ(testData.GetKs().value(), data.GetKs().value()); @@ -30,10 +30,10 @@ struct SimpleMotorFeedforwardProtoTestData { INSTANTIATE_TYPED_TEST_SUITE_P( SimpleMotorFeedforwardMeters, ProtoTest, - SimpleMotorFeedforwardProtoTestData); + SimpleMotorFeedforwardProtoTestData); INSTANTIATE_TYPED_TEST_SUITE_P( SimpleMotorFeedforwardFeet, ProtoTest, - SimpleMotorFeedforwardProtoTestData); + SimpleMotorFeedforwardProtoTestData); INSTANTIATE_TYPED_TEST_SUITE_P( SimpleMotorFeedforwardRadians, ProtoTest, - SimpleMotorFeedforwardProtoTestData); + SimpleMotorFeedforwardProtoTestData); diff --git a/wpimath/src/test/native/cpp/controller/struct/ArmFeedforwardStructTest.cpp b/wpimath/src/test/native/cpp/controller/struct/ArmFeedforwardStructTest.cpp index 5106c5e4cf..db91eab691 100644 --- a/wpimath/src/test/native/cpp/controller/struct/ArmFeedforwardStructTest.cpp +++ b/wpimath/src/test/native/cpp/controller/struct/ArmFeedforwardStructTest.cpp @@ -6,11 +6,11 @@ #include "wpi/math/controller/ArmFeedforward.hpp" -using namespace frc; +using namespace wpi::math; namespace { -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; static constexpr auto Ks = 1.91_V; static constexpr auto Kg = 2.29_V; diff --git a/wpimath/src/test/native/cpp/controller/struct/DifferentialDriveFeedforwardStructTest.cpp b/wpimath/src/test/native/cpp/controller/struct/DifferentialDriveFeedforwardStructTest.cpp index c702a35040..cda91bc46d 100644 --- a/wpimath/src/test/native/cpp/controller/struct/DifferentialDriveFeedforwardStructTest.cpp +++ b/wpimath/src/test/native/cpp/controller/struct/DifferentialDriveFeedforwardStructTest.cpp @@ -7,7 +7,7 @@ #include "../../StructTestBase.hpp" #include "wpi/math/controller/DifferentialDriveFeedforward.hpp" -using namespace frc; +using namespace wpi::math; struct DifferentialDriveFeedforwardStructTestData { using Type = DifferentialDriveFeedforward; diff --git a/wpimath/src/test/native/cpp/controller/struct/DifferentialDriveWheelVoltagesStructTest.cpp b/wpimath/src/test/native/cpp/controller/struct/DifferentialDriveWheelVoltagesStructTest.cpp index 13679b84b7..bc0b762540 100644 --- a/wpimath/src/test/native/cpp/controller/struct/DifferentialDriveWheelVoltagesStructTest.cpp +++ b/wpimath/src/test/native/cpp/controller/struct/DifferentialDriveWheelVoltagesStructTest.cpp @@ -6,11 +6,11 @@ #include "wpi/math/controller/DifferentialDriveWheelVoltages.hpp" -using namespace frc; +using namespace wpi::math; namespace { -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; const DifferentialDriveWheelVoltages kExpectedData{ DifferentialDriveWheelVoltages{0.174_V, 0.191_V}}; } // namespace diff --git a/wpimath/src/test/native/cpp/controller/struct/ElevatorFeedforwardStructTest.cpp b/wpimath/src/test/native/cpp/controller/struct/ElevatorFeedforwardStructTest.cpp index b324271c6c..49686726e2 100644 --- a/wpimath/src/test/native/cpp/controller/struct/ElevatorFeedforwardStructTest.cpp +++ b/wpimath/src/test/native/cpp/controller/struct/ElevatorFeedforwardStructTest.cpp @@ -6,11 +6,11 @@ #include "wpi/math/controller/ElevatorFeedforward.hpp" -using namespace frc; +using namespace wpi::math; namespace { -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; static constexpr auto Ks = 1.91_V; static constexpr auto Kg = 2.29_V; diff --git a/wpimath/src/test/native/cpp/controller/struct/SimpleMotorFeedforwardStructTest.cpp b/wpimath/src/test/native/cpp/controller/struct/SimpleMotorFeedforwardStructTest.cpp index ede414fc04..2eeb8152fd 100644 --- a/wpimath/src/test/native/cpp/controller/struct/SimpleMotorFeedforwardStructTest.cpp +++ b/wpimath/src/test/native/cpp/controller/struct/SimpleMotorFeedforwardStructTest.cpp @@ -10,15 +10,15 @@ #include "wpi/units/acceleration.hpp" #include "wpi/units/velocity.hpp" -using namespace frc; +using namespace wpi::math; template struct SimpleMotorFeedforwardStructTestData { using Type = SimpleMotorFeedforward; inline static const Type kTestData = { - units::volt_t{0.4}, units::volt_t{4.0} / (units::unit_t{1} / 1_s), - units::volt_t{0.7} / (units::unit_t{1} / 1_s / 1_s), 25_ms}; + wpi::units::volt_t{0.4}, wpi::units::volt_t{4.0} / (wpi::units::unit_t{1} / 1_s), + wpi::units::volt_t{0.7} / (wpi::units::unit_t{1} / 1_s / 1_s), 25_ms}; static void CheckEq(const Type& testData, const Type& data) { EXPECT_EQ(testData.GetKs().value(), data.GetKs().value()); @@ -30,10 +30,10 @@ struct SimpleMotorFeedforwardStructTestData { INSTANTIATE_TYPED_TEST_SUITE_P( SimpleMotorFeedforwardMeters, StructTest, - SimpleMotorFeedforwardStructTestData); + SimpleMotorFeedforwardStructTestData); INSTANTIATE_TYPED_TEST_SUITE_P( SimpleMotorFeedforwardFeet, StructTest, - SimpleMotorFeedforwardStructTestData); + SimpleMotorFeedforwardStructTestData); INSTANTIATE_TYPED_TEST_SUITE_P( SimpleMotorFeedforwardRadians, StructTest, - SimpleMotorFeedforwardStructTestData); + SimpleMotorFeedforwardStructTestData); diff --git a/wpimath/src/test/native/cpp/estimator/AngleStatisticsTest.cpp b/wpimath/src/test/native/cpp/estimator/AngleStatisticsTest.cpp index 5d9d8773d2..eee38e77d8 100644 --- a/wpimath/src/test/native/cpp/estimator/AngleStatisticsTest.cpp +++ b/wpimath/src/test/native/cpp/estimator/AngleStatisticsTest.cpp @@ -10,7 +10,7 @@ #include "wpi/math/linalg/EigenCore.hpp" TEST(AngleStatisticsTest, Mean) { - frc::Matrixd<3, 3> sigmas{ + wpi::math::Matrixd<3, 3> sigmas{ {1, 1.2, 0}, {359 * std::numbers::pi / 180, 3 * std::numbers::pi / 180, 0}, {1, 2, 0}}; @@ -19,7 +19,7 @@ TEST(AngleStatisticsTest, Mean) { weights.fill(1.0 / sigmas.cols()); EXPECT_TRUE(Eigen::Vector3d(0.7333333, 0.01163323, 1) - .isApprox(frc::AngleMean<3, 3>(sigmas, weights, 1), 1e-3)); + .isApprox(wpi::math::AngleMean<3, 3>(sigmas, weights, 1), 1e-3)); } TEST(AngleStatisticsTest, Mean_DynamicSize) { @@ -32,7 +32,7 @@ TEST(AngleStatisticsTest, Mean_DynamicSize) { weights.fill(1.0 / sigmas.cols()); EXPECT_TRUE(Eigen::Vector3d(0.7333333, 0.01163323, 1) - .isApprox(frc::AngleMean( + .isApprox(wpi::math::AngleMean( sigmas, weights, 1), 1e-3)); } @@ -41,7 +41,7 @@ TEST(AngleStatisticsTest, Residual) { Eigen::Vector3d a{1, 1 * std::numbers::pi / 180, 2}; Eigen::Vector3d b{1, 359 * std::numbers::pi / 180, 1}; - EXPECT_TRUE(frc::AngleResidual<3>(a, b, 1).isApprox( + EXPECT_TRUE(wpi::math::AngleResidual<3>(a, b, 1).isApprox( Eigen::Vector3d{0, 2 * std::numbers::pi / 180, 1})); } @@ -49,7 +49,7 @@ TEST(AngleStatisticsTest, Residual_DynamicSize) { Eigen::VectorXd a{{1, 1 * std::numbers::pi / 180, 2}}; Eigen::VectorXd b{{1, 359 * std::numbers::pi / 180, 1}}; - EXPECT_TRUE(frc::AngleResidual(a, b, 1).isApprox( + EXPECT_TRUE(wpi::math::AngleResidual(a, b, 1).isApprox( Eigen::VectorXd{{0, 2 * std::numbers::pi / 180, 1}})); } @@ -57,13 +57,13 @@ TEST(AngleStatisticsTest, Add) { Eigen::Vector3d a{1, 1 * std::numbers::pi / 180, 2}; Eigen::Vector3d b{1, 359 * std::numbers::pi / 180, 1}; - EXPECT_TRUE(frc::AngleAdd<3>(a, b, 1).isApprox(Eigen::Vector3d{2, 0, 3})); + EXPECT_TRUE(wpi::math::AngleAdd<3>(a, b, 1).isApprox(Eigen::Vector3d{2, 0, 3})); } TEST(AngleStatisticsTest, Add_DynamicSize) { Eigen::VectorXd a{{1, 1 * std::numbers::pi / 180, 2}}; Eigen::VectorXd b{{1, 359 * std::numbers::pi / 180, 1}}; - EXPECT_TRUE(frc::AngleAdd(a, b, 1).isApprox( + EXPECT_TRUE(wpi::math::AngleAdd(a, b, 1).isApprox( Eigen::VectorXd{{2, 0, 3}})); } diff --git a/wpimath/src/test/native/cpp/estimator/DifferentialDrivePoseEstimator3dTest.cpp b/wpimath/src/test/native/cpp/estimator/DifferentialDrivePoseEstimator3dTest.cpp index 34112b4502..43ce31e41c 100644 --- a/wpimath/src/test/native/cpp/estimator/DifferentialDrivePoseEstimator3dTest.cpp +++ b/wpimath/src/test/native/cpp/estimator/DifferentialDrivePoseEstimator3dTest.cpp @@ -22,43 +22,43 @@ #include "wpi/util/print.hpp" void testFollowTrajectory( - const frc::DifferentialDriveKinematics& kinematics, - frc::DifferentialDrivePoseEstimator3d& estimator, - const frc::Trajectory& trajectory, - std::function + const wpi::math::DifferentialDriveKinematics& kinematics, + wpi::math::DifferentialDrivePoseEstimator3d& estimator, + const wpi::math::Trajectory& trajectory, + std::function chassisSpeedsGenerator, - std::function + std::function visionMeasurementGenerator, - const frc::Pose2d& startingPose, const frc::Pose2d& endingPose, - const units::second_t dt, const units::second_t kVisionUpdateRate, - const units::second_t kVisionUpdateDelay, const bool checkError, + const wpi::math::Pose2d& startingPose, const wpi::math::Pose2d& endingPose, + const wpi::units::second_t dt, const wpi::units::second_t kVisionUpdateRate, + const wpi::units::second_t kVisionUpdateDelay, const bool checkError, const bool debug) { - units::meter_t leftDistance = 0_m; - units::meter_t rightDistance = 0_m; + wpi::units::meter_t leftDistance = 0_m; + wpi::units::meter_t rightDistance = 0_m; - estimator.ResetPosition(frc::Rotation3d{}, leftDistance, rightDistance, - frc::Pose3d{startingPose}); + estimator.ResetPosition(wpi::math::Rotation3d{}, leftDistance, rightDistance, + wpi::math::Pose3d{startingPose}); std::default_random_engine generator; std::normal_distribution distribution(0.0, 1.0); - units::second_t t = 0_s; + wpi::units::second_t t = 0_s; - std::vector> visionPoses; - std::vector> + std::vector> visionPoses; + std::vector> visionLog; double maxError = -std::numeric_limits::max(); double errorSum = 0; if (debug) { - wpi::print( + wpi::util::print( "time, est_x, est_y, est_theta, true_x, true_y, true_theta, left, " "right\n"); } while (t < trajectory.TotalTime()) { - frc::Trajectory::State groundTruthState = trajectory.Sample(t); + wpi::math::Trajectory::State groundTruthState = trajectory.Sample(t); // We are due for a new vision measurement if it's been `visionUpdateRate` // seconds since the last vision measurement @@ -66,9 +66,9 @@ void testFollowTrajectory( visionPoses.back().first + kVisionUpdateRate < t) { auto visionPose = visionMeasurementGenerator(groundTruthState) + - frc::Transform2d{frc::Translation2d{distribution(generator) * 0.1_m, + wpi::math::Transform2d{wpi::math::Translation2d{distribution(generator) * 0.1_m, distribution(generator) * 0.1_m}, - frc::Rotation2d{distribution(generator) * 0.05_rad}}; + wpi::math::Rotation2d{distribution(generator) * 0.05_rad}}; visionPoses.push_back({t, visionPose}); } @@ -77,7 +77,7 @@ void testFollowTrajectory( if (!visionPoses.empty() && visionPoses.front().first + kVisionUpdateDelay < t) { auto visionEntry = visionPoses.front(); - estimator.AddVisionMeasurement(frc::Pose3d{visionEntry.second}, + estimator.AddVisionMeasurement(wpi::math::Pose3d{visionEntry.second}, visionEntry.first); visionPoses.erase(visionPoses.begin()); visionLog.push_back({t, visionEntry.first, visionEntry.second}); @@ -92,13 +92,13 @@ void testFollowTrajectory( auto xhat = estimator.UpdateWithTime( t, - frc::Rotation3d{groundTruthState.pose.Rotation() + - frc::Rotation2d{distribution(generator) * 0.05_rad} - + wpi::math::Rotation3d{groundTruthState.pose.Rotation() + + wpi::math::Rotation2d{distribution(generator) * 0.05_rad} - trajectory.InitialPose().Rotation()}, leftDistance, rightDistance); if (debug) { - wpi::print( + wpi::util::print( "{}, {}, {}, {}, {}, {}, {}, {}, {}\n", t.value(), xhat.X().value(), xhat.Y().value(), xhat.Rotation().ToRotation2d().Radians().value(), groundTruthState.pose.X().value(), groundTruthState.pose.Y().value(), @@ -119,14 +119,14 @@ void testFollowTrajectory( } if (debug) { - wpi::print("apply_time, measured_time, vision_x, vision_y, vision_theta\n"); + wpi::util::print("apply_time, measured_time, vision_x, vision_y, vision_theta\n"); - units::second_t apply_time; - units::second_t measure_time; - frc::Pose2d vision_pose; + wpi::units::second_t apply_time; + wpi::units::second_t measure_time; + wpi::math::Pose2d vision_pose; for (auto record : visionLog) { std::tie(apply_time, measure_time, vision_pose) = record; - wpi::print("{}, {}, {}, {}, {}\n", apply_time.value(), + wpi::util::print("{}, {}, {}, {}, {}\n", apply_time.value(), measure_time.value(), vision_pose.X().value(), vision_pose.Y().value(), vision_pose.Rotation().Radians().value()); @@ -153,73 +153,73 @@ void testFollowTrajectory( } TEST(DifferentialDrivePoseEstimator3dTest, Accuracy) { - frc::DifferentialDriveKinematics kinematics{1.0_m}; + wpi::math::DifferentialDriveKinematics kinematics{1.0_m}; - frc::DifferentialDrivePoseEstimator3d estimator{kinematics, - frc::Rotation3d{}, + wpi::math::DifferentialDrivePoseEstimator3d estimator{kinematics, + wpi::math::Rotation3d{}, 0_m, 0_m, - frc::Pose3d{}, + wpi::math::Pose3d{}, {0.02, 0.02, 0.02, 0.01}, {0.1, 0.1, 0.1, 0.1}}; - frc::Trajectory trajectory = frc::TrajectoryGenerator::GenerateTrajectory( - std::vector{frc::Pose2d{0_m, 0_m, 45_deg}, frc::Pose2d{3_m, 0_m, -90_deg}, - frc::Pose2d{0_m, 0_m, 135_deg}, - frc::Pose2d{-3_m, 0_m, -90_deg}, - frc::Pose2d{0_m, 0_m, 45_deg}}, - frc::TrajectoryConfig(2_mps, 2_mps_sq)); + wpi::math::Trajectory trajectory = wpi::math::TrajectoryGenerator::GenerateTrajectory( + std::vector{wpi::math::Pose2d{0_m, 0_m, 45_deg}, wpi::math::Pose2d{3_m, 0_m, -90_deg}, + wpi::math::Pose2d{0_m, 0_m, 135_deg}, + wpi::math::Pose2d{-3_m, 0_m, -90_deg}, + wpi::math::Pose2d{0_m, 0_m, 45_deg}}, + wpi::math::TrajectoryConfig(2_mps, 2_mps_sq)); testFollowTrajectory( kinematics, estimator, trajectory, - [&](frc::Trajectory::State& state) { - return frc::ChassisSpeeds{state.velocity, 0_mps, + [&](wpi::math::Trajectory::State& state) { + return wpi::math::ChassisSpeeds{state.velocity, 0_mps, state.velocity * state.curvature}; }, - [&](frc::Trajectory::State& state) { return state.pose; }, - trajectory.InitialPose(), {0_m, 0_m, frc::Rotation2d{45_deg}}, 20_ms, + [&](wpi::math::Trajectory::State& state) { return state.pose; }, + trajectory.InitialPose(), {0_m, 0_m, wpi::math::Rotation2d{45_deg}}, 20_ms, 100_ms, 250_ms, true, false); } TEST(DifferentialDrivePoseEstimator3dTest, BadInitialPose) { - frc::DifferentialDriveKinematics kinematics{1.0_m}; + wpi::math::DifferentialDriveKinematics kinematics{1.0_m}; - frc::DifferentialDrivePoseEstimator3d estimator{kinematics, - frc::Rotation3d{}, + wpi::math::DifferentialDrivePoseEstimator3d estimator{kinematics, + wpi::math::Rotation3d{}, 0_m, 0_m, - frc::Pose3d{}, + wpi::math::Pose3d{}, {0.02, 0.02, 0.02, 0.01}, {0.1, 0.1, 0.1, 0.1}}; - frc::Trajectory trajectory = frc::TrajectoryGenerator::GenerateTrajectory( - std::vector{frc::Pose2d{0_m, 0_m, 45_deg}, frc::Pose2d{3_m, 0_m, -90_deg}, - frc::Pose2d{0_m, 0_m, 135_deg}, - frc::Pose2d{-3_m, 0_m, -90_deg}, - frc::Pose2d{0_m, 0_m, 45_deg}}, - frc::TrajectoryConfig(2_mps, 2_mps_sq)); + wpi::math::Trajectory trajectory = wpi::math::TrajectoryGenerator::GenerateTrajectory( + std::vector{wpi::math::Pose2d{0_m, 0_m, 45_deg}, wpi::math::Pose2d{3_m, 0_m, -90_deg}, + wpi::math::Pose2d{0_m, 0_m, 135_deg}, + wpi::math::Pose2d{-3_m, 0_m, -90_deg}, + wpi::math::Pose2d{0_m, 0_m, 45_deg}}, + wpi::math::TrajectoryConfig(2_mps, 2_mps_sq)); - for (units::degree_t offset_direction_degs = 0_deg; + for (wpi::units::degree_t offset_direction_degs = 0_deg; offset_direction_degs < 360_deg; offset_direction_degs += 45_deg) { - for (units::degree_t offset_heading_degs = 0_deg; + for (wpi::units::degree_t offset_heading_degs = 0_deg; offset_heading_degs < 360_deg; offset_heading_degs += 45_deg) { - auto pose_offset = frc::Rotation2d{offset_direction_degs}; - auto heading_offset = frc::Rotation2d{offset_heading_degs}; + auto pose_offset = wpi::math::Rotation2d{offset_direction_degs}; + auto heading_offset = wpi::math::Rotation2d{offset_heading_degs}; auto initial_pose = trajectory.InitialPose() + - frc::Transform2d{frc::Translation2d{pose_offset.Cos() * 1_m, + wpi::math::Transform2d{wpi::math::Translation2d{pose_offset.Cos() * 1_m, pose_offset.Sin() * 1_m}, heading_offset}; testFollowTrajectory( kinematics, estimator, trajectory, - [&](frc::Trajectory::State& state) { - return frc::ChassisSpeeds{state.velocity, 0_mps, + [&](wpi::math::Trajectory::State& state) { + return wpi::math::ChassisSpeeds{state.velocity, 0_mps, state.velocity * state.curvature}; }, - [&](frc::Trajectory::State& state) { return state.pose; }, - initial_pose, {0_m, 0_m, frc::Rotation2d{45_deg}}, 20_ms, 100_ms, + [&](wpi::math::Trajectory::State& state) { return state.pose; }, + initial_pose, {0_m, 0_m, wpi::math::Rotation2d{45_deg}}, 20_ms, 100_ms, 250_ms, false, false); } } @@ -231,33 +231,33 @@ TEST(DifferentialDrivePoseEstimator3dTest, SimultaneousVisionMeasurements) { // The alternative result is that only one vision measurement affects the // outcome. If that were the case, after 1000 measurements, the estimated // pose would converge to that measurement. - frc::DifferentialDriveKinematics kinematics{1.0_m}; + wpi::math::DifferentialDriveKinematics kinematics{1.0_m}; - frc::DifferentialDrivePoseEstimator3d estimator{ + wpi::math::DifferentialDrivePoseEstimator3d estimator{ kinematics, - frc::Rotation3d{}, + wpi::math::Rotation3d{}, 0_m, 0_m, - frc::Pose3d{1_m, 2_m, 0_m, frc::Rotation3d{0_deg, 0_deg, 270_deg}}, + wpi::math::Pose3d{1_m, 2_m, 0_m, wpi::math::Rotation3d{0_deg, 0_deg, 270_deg}}, {0.02, 0.02, 0.02, 0.01}, {0.1, 0.1, 0.1, 0.1}}; - estimator.UpdateWithTime(0_s, frc::Rotation3d{}, 0_m, 0_m); + estimator.UpdateWithTime(0_s, wpi::math::Rotation3d{}, 0_m, 0_m); for (int i = 0; i < 1000; i++) { estimator.AddVisionMeasurement( - frc::Pose3d{0_m, 0_m, 0_m, frc::Rotation3d{0_deg, 0_deg, 0_deg}}, 0_s); + wpi::math::Pose3d{0_m, 0_m, 0_m, wpi::math::Rotation3d{0_deg, 0_deg, 0_deg}}, 0_s); estimator.AddVisionMeasurement( - frc::Pose3d{3_m, 1_m, 0_m, frc::Rotation3d{0_deg, 0_deg, 90_deg}}, 0_s); + wpi::math::Pose3d{3_m, 1_m, 0_m, wpi::math::Rotation3d{0_deg, 0_deg, 90_deg}}, 0_s); estimator.AddVisionMeasurement( - frc::Pose3d{2_m, 4_m, 0_m, frc::Rotation3d{0_deg, 0_deg, 180_deg}}, + wpi::math::Pose3d{2_m, 4_m, 0_m, wpi::math::Rotation3d{0_deg, 0_deg, 180_deg}}, 0_s); } { - auto dx = units::math::abs(estimator.GetEstimatedPosition().X() - 0_m); - auto dy = units::math::abs(estimator.GetEstimatedPosition().Y() - 0_m); - auto dtheta = units::math::abs( + auto dx = wpi::units::math::abs(estimator.GetEstimatedPosition().X() - 0_m); + auto dy = wpi::units::math::abs(estimator.GetEstimatedPosition().Y() - 0_m); + auto dtheta = wpi::units::math::abs( estimator.GetEstimatedPosition().Rotation().ToRotation2d().Radians() - 0_deg); @@ -265,9 +265,9 @@ TEST(DifferentialDrivePoseEstimator3dTest, SimultaneousVisionMeasurements) { } { - auto dx = units::math::abs(estimator.GetEstimatedPosition().X() - 3_m); - auto dy = units::math::abs(estimator.GetEstimatedPosition().Y() - 1_m); - auto dtheta = units::math::abs( + auto dx = wpi::units::math::abs(estimator.GetEstimatedPosition().X() - 3_m); + auto dy = wpi::units::math::abs(estimator.GetEstimatedPosition().Y() - 1_m); + auto dtheta = wpi::units::math::abs( estimator.GetEstimatedPosition().Rotation().ToRotation2d().Radians() - 90_deg); @@ -275,9 +275,9 @@ TEST(DifferentialDrivePoseEstimator3dTest, SimultaneousVisionMeasurements) { } { - auto dx = units::math::abs(estimator.GetEstimatedPosition().X() - 2_m); - auto dy = units::math::abs(estimator.GetEstimatedPosition().Y() - 4_m); - auto dtheta = units::math::abs( + auto dx = wpi::units::math::abs(estimator.GetEstimatedPosition().X() - 2_m); + auto dy = wpi::units::math::abs(estimator.GetEstimatedPosition().Y() - 4_m); + auto dtheta = wpi::units::math::abs( estimator.GetEstimatedPosition().Rotation().ToRotation2d().Radians() - 180_deg); @@ -286,22 +286,22 @@ TEST(DifferentialDrivePoseEstimator3dTest, SimultaneousVisionMeasurements) { } TEST(DifferentialDrivePoseEstimator3dTest, TestDiscardStaleVisionMeasurements) { - frc::DifferentialDriveKinematics kinematics{1_m}; + wpi::math::DifferentialDriveKinematics kinematics{1_m}; - frc::DifferentialDrivePoseEstimator3d estimator{ - kinematics, frc::Rotation3d{}, 0_m, 0_m, frc::Pose3d{}, + wpi::math::DifferentialDrivePoseEstimator3d estimator{ + kinematics, wpi::math::Rotation3d{}, 0_m, 0_m, wpi::math::Pose3d{}, {0.1, 0.1, 0.1, 0.1}, {0.45, 0.45, 0.45, 0.45}}; // Add enough measurements to fill up the buffer for (auto time = 0_s; time < 4_s; time += 20_ms) { - estimator.UpdateWithTime(time, frc::Rotation3d{}, 0_m, 0_m); + estimator.UpdateWithTime(time, wpi::math::Rotation3d{}, 0_m, 0_m); } auto odometryPose = estimator.GetEstimatedPosition(); // Apply a vision measurement from 3 seconds ago estimator.AddVisionMeasurement( - frc::Pose3d{10_m, 10_m, 0_m, frc::Rotation3d{0_rad, 0_rad, 0.1_rad}}, 1_s, + wpi::math::Pose3d{10_m, 10_m, 0_m, wpi::math::Rotation3d{0_rad, 0_rad, 0.1_rad}}, 1_s, {0.1, 0.1, 0.1, 0.1}); EXPECT_NEAR(odometryPose.X().value(), @@ -319,9 +319,9 @@ TEST(DifferentialDrivePoseEstimator3dTest, TestDiscardStaleVisionMeasurements) { } TEST(DifferentialDrivePoseEstimator3dTest, TestSampleAt) { - frc::DifferentialDriveKinematics kinematics{1_m}; - frc::DifferentialDrivePoseEstimator3d estimator{ - kinematics, frc::Rotation3d{}, 0_m, 0_m, frc::Pose3d{}, + wpi::math::DifferentialDriveKinematics kinematics{1_m}; + wpi::math::DifferentialDrivePoseEstimator3d estimator{ + kinematics, wpi::math::Rotation3d{}, 0_m, 0_m, wpi::math::Pose3d{}, {1.0, 1.0, 1.0, 1.0}, {1.0, 1.0, 1.0, 1.0}}; // Returns empty when null @@ -331,60 +331,60 @@ TEST(DifferentialDrivePoseEstimator3dTest, TestSampleAt) { // Add a tiny tolerance for the upper bound because of floating point rounding // error for (double time = 1; time <= 2 + 1e-9; time += 0.02) { - estimator.UpdateWithTime(units::second_t{time}, frc::Rotation3d{}, - units::meter_t{time}, units::meter_t{time}); + estimator.UpdateWithTime(wpi::units::second_t{time}, wpi::math::Rotation3d{}, + wpi::units::meter_t{time}, wpi::units::meter_t{time}); } // Sample at an added time - EXPECT_EQ(std::optional(frc::Pose3d{1.02_m, 0_m, 0_m, frc::Rotation3d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose3d{1.02_m, 0_m, 0_m, wpi::math::Rotation3d{}}), estimator.SampleAt(1.02_s)); // Sample between updates (test interpolation) - EXPECT_EQ(std::optional(frc::Pose3d{1.01_m, 0_m, 0_m, frc::Rotation3d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose3d{1.01_m, 0_m, 0_m, wpi::math::Rotation3d{}}), estimator.SampleAt(1.01_s)); // Sampling before the oldest value returns the oldest value - EXPECT_EQ(std::optional(frc::Pose3d{1_m, 0_m, 0_m, frc::Rotation3d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose3d{1_m, 0_m, 0_m, wpi::math::Rotation3d{}}), estimator.SampleAt(0.5_s)); // Sampling after the newest value returns the newest value - EXPECT_EQ(std::optional(frc::Pose3d{2_m, 0_m, 0_m, frc::Rotation3d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose3d{2_m, 0_m, 0_m, wpi::math::Rotation3d{}}), estimator.SampleAt(2.5_s)); // Add a vision measurement after the odometry measurements (while keeping all // of the old odometry measurements) estimator.AddVisionMeasurement( - frc::Pose3d{2_m, 0_m, 0_m, frc::Rotation3d{0_rad, 0_rad, 1_rad}}, 2.2_s); + wpi::math::Pose3d{2_m, 0_m, 0_m, wpi::math::Rotation3d{0_rad, 0_rad, 1_rad}}, 2.2_s); // Make sure nothing changed (except the newest value) - EXPECT_EQ(std::optional(frc::Pose3d{1.02_m, 0_m, 0_m, frc::Rotation3d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose3d{1.02_m, 0_m, 0_m, wpi::math::Rotation3d{}}), estimator.SampleAt(1.02_s)); - EXPECT_EQ(std::optional(frc::Pose3d{1.01_m, 0_m, 0_m, frc::Rotation3d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose3d{1.01_m, 0_m, 0_m, wpi::math::Rotation3d{}}), estimator.SampleAt(1.01_s)); - EXPECT_EQ(std::optional(frc::Pose3d{1_m, 0_m, 0_m, frc::Rotation3d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose3d{1_m, 0_m, 0_m, wpi::math::Rotation3d{}}), estimator.SampleAt(0.5_s)); // Add a vision measurement before the odometry measurements that's still in // the buffer estimator.AddVisionMeasurement( - frc::Pose3d{1_m, 0.2_m, 0_m, frc::Rotation3d{}}, 0.9_s); + wpi::math::Pose3d{1_m, 0.2_m, 0_m, wpi::math::Rotation3d{}}, 0.9_s); // Everything should be the same except Y is 0.1 (halfway between 0 and 0.2) - EXPECT_EQ(std::optional(frc::Pose3d{1.02_m, 0.1_m, 0_m, frc::Rotation3d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose3d{1.02_m, 0.1_m, 0_m, wpi::math::Rotation3d{}}), estimator.SampleAt(1.02_s)); - EXPECT_EQ(std::optional(frc::Pose3d{1.01_m, 0.1_m, 0_m, frc::Rotation3d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose3d{1.01_m, 0.1_m, 0_m, wpi::math::Rotation3d{}}), estimator.SampleAt(1.01_s)); - EXPECT_EQ(std::optional(frc::Pose3d{1_m, 0.1_m, 0_m, frc::Rotation3d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose3d{1_m, 0.1_m, 0_m, wpi::math::Rotation3d{}}), estimator.SampleAt(0.5_s)); - EXPECT_EQ(std::optional(frc::Pose3d{2_m, 0.1_m, 0_m, frc::Rotation3d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose3d{2_m, 0.1_m, 0_m, wpi::math::Rotation3d{}}), estimator.SampleAt(2.5_s)); } TEST(DifferentialDrivePoseEstimator3dTest, TestReset) { - frc::DifferentialDriveKinematics kinematics{1_m}; - frc::DifferentialDrivePoseEstimator3d estimator{ + wpi::math::DifferentialDriveKinematics kinematics{1_m}; + wpi::math::DifferentialDrivePoseEstimator3d estimator{ kinematics, - frc::Rotation3d{}, + wpi::math::Rotation3d{}, 0_m, 0_m, - frc::Pose3d{-1_m, -1_m, -1_m, frc::Rotation3d{0_rad, 0_rad, 1_rad}}, + wpi::math::Pose3d{-1_m, -1_m, -1_m, wpi::math::Rotation3d{0_rad, 0_rad, 1_rad}}, {1.0, 1.0, 1.0, 1.0}, {1.0, 1.0, 1.0, 1.0}}; @@ -397,8 +397,8 @@ TEST(DifferentialDrivePoseEstimator3dTest, TestReset) { EXPECT_DOUBLE_EQ(1, estimator.GetEstimatedPosition().Rotation().Z().value()); // Test reset position - estimator.ResetPosition(frc::Rotation3d{}, 1_m, 1_m, - frc::Pose3d{1_m, 0_m, 0_m, frc::Rotation3d{}}); + estimator.ResetPosition(wpi::math::Rotation3d{}, 1_m, 1_m, + wpi::math::Pose3d{1_m, 0_m, 0_m, wpi::math::Rotation3d{}}); EXPECT_DOUBLE_EQ(1, estimator.GetEstimatedPosition().X().value()); EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Y().value()); @@ -408,7 +408,7 @@ TEST(DifferentialDrivePoseEstimator3dTest, TestReset) { EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Rotation().Z().value()); // Test orientation and wheel positions - estimator.Update(frc::Rotation3d{}, 2_m, 2_m); + estimator.Update(wpi::math::Rotation3d{}, 2_m, 2_m); EXPECT_DOUBLE_EQ(2, estimator.GetEstimatedPosition().X().value()); EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Y().value()); @@ -418,7 +418,7 @@ TEST(DifferentialDrivePoseEstimator3dTest, TestReset) { EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Rotation().Z().value()); // Test reset rotation - estimator.ResetRotation(frc::Rotation3d{0_deg, 0_deg, 90_deg}); + estimator.ResetRotation(wpi::math::Rotation3d{0_deg, 0_deg, 90_deg}); EXPECT_DOUBLE_EQ(2, estimator.GetEstimatedPosition().X().value()); EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Y().value()); @@ -429,7 +429,7 @@ TEST(DifferentialDrivePoseEstimator3dTest, TestReset) { estimator.GetEstimatedPosition().Rotation().Z().value()); // Test orientation - estimator.Update(frc::Rotation3d{}, 3_m, 3_m); + estimator.Update(wpi::math::Rotation3d{}, 3_m, 3_m); EXPECT_DOUBLE_EQ(2, estimator.GetEstimatedPosition().X().value()); EXPECT_DOUBLE_EQ(1, estimator.GetEstimatedPosition().Y().value()); @@ -440,7 +440,7 @@ TEST(DifferentialDrivePoseEstimator3dTest, TestReset) { estimator.GetEstimatedPosition().Rotation().Z().value()); // Test reset translation - estimator.ResetTranslation(frc::Translation3d{-1_m, -1_m, -1_m}); + estimator.ResetTranslation(wpi::math::Translation3d{-1_m, -1_m, -1_m}); EXPECT_DOUBLE_EQ(-1, estimator.GetEstimatedPosition().X().value()); EXPECT_DOUBLE_EQ(-1, estimator.GetEstimatedPosition().Y().value()); @@ -451,7 +451,7 @@ TEST(DifferentialDrivePoseEstimator3dTest, TestReset) { estimator.GetEstimatedPosition().Rotation().Z().value()); // Test reset pose - estimator.ResetPose(frc::Pose3d{}); + estimator.ResetPose(wpi::math::Pose3d{}); EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().X().value()); EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Y().value()); diff --git a/wpimath/src/test/native/cpp/estimator/DifferentialDrivePoseEstimatorTest.cpp b/wpimath/src/test/native/cpp/estimator/DifferentialDrivePoseEstimatorTest.cpp index 121b26dcba..988a0c88b2 100644 --- a/wpimath/src/test/native/cpp/estimator/DifferentialDrivePoseEstimatorTest.cpp +++ b/wpimath/src/test/native/cpp/estimator/DifferentialDrivePoseEstimatorTest.cpp @@ -23,43 +23,43 @@ #include "wpi/util/print.hpp" void testFollowTrajectory( - const frc::DifferentialDriveKinematics& kinematics, - frc::DifferentialDrivePoseEstimator& estimator, - const frc::Trajectory& trajectory, - std::function + const wpi::math::DifferentialDriveKinematics& kinematics, + wpi::math::DifferentialDrivePoseEstimator& estimator, + const wpi::math::Trajectory& trajectory, + std::function chassisSpeedsGenerator, - std::function + std::function visionMeasurementGenerator, - const frc::Pose2d& startingPose, const frc::Pose2d& endingPose, - const units::second_t dt, const units::second_t kVisionUpdateRate, - const units::second_t kVisionUpdateDelay, const bool checkError, + const wpi::math::Pose2d& startingPose, const wpi::math::Pose2d& endingPose, + const wpi::units::second_t dt, const wpi::units::second_t kVisionUpdateRate, + const wpi::units::second_t kVisionUpdateDelay, const bool checkError, const bool debug) { - units::meter_t leftDistance = 0_m; - units::meter_t rightDistance = 0_m; + wpi::units::meter_t leftDistance = 0_m; + wpi::units::meter_t rightDistance = 0_m; - estimator.ResetPosition(frc::Rotation2d{}, leftDistance, rightDistance, + estimator.ResetPosition(wpi::math::Rotation2d{}, leftDistance, rightDistance, startingPose); std::default_random_engine generator; std::normal_distribution distribution(0.0, 1.0); - units::second_t t = 0_s; + wpi::units::second_t t = 0_s; - std::vector> visionPoses; - std::vector> + std::vector> visionPoses; + std::vector> visionLog; double maxError = -std::numeric_limits::max(); double errorSum = 0; if (debug) { - wpi::print( + wpi::util::print( "time, est_x, est_y, est_theta, true_x, true_y, true_theta, left, " "right\n"); } while (t < trajectory.TotalTime()) { - frc::Trajectory::State groundTruthState = trajectory.Sample(t); + wpi::math::Trajectory::State groundTruthState = trajectory.Sample(t); // We are due for a new vision measurement if it's been `visionUpdateRate` // seconds since the last vision measurement @@ -67,9 +67,9 @@ void testFollowTrajectory( visionPoses.back().first + kVisionUpdateRate < t) { auto visionPose = visionMeasurementGenerator(groundTruthState) + - frc::Transform2d{frc::Translation2d{distribution(generator) * 0.1_m, + wpi::math::Transform2d{wpi::math::Translation2d{distribution(generator) * 0.1_m, distribution(generator) * 0.1_m}, - frc::Rotation2d{distribution(generator) * 0.05_rad}}; + wpi::math::Rotation2d{distribution(generator) * 0.05_rad}}; visionPoses.push_back({t, visionPose}); } @@ -93,12 +93,12 @@ void testFollowTrajectory( auto xhat = estimator.UpdateWithTime( t, groundTruthState.pose.Rotation() + - frc::Rotation2d{distribution(generator) * 0.05_rad} - + wpi::math::Rotation2d{distribution(generator) * 0.05_rad} - trajectory.InitialPose().Rotation(), leftDistance, rightDistance); if (debug) { - wpi::print( + wpi::util::print( "{}, {}, {}, {}, {}, {}, {}, {}, {}\n", t.value(), xhat.X().value(), xhat.Y().value(), xhat.Rotation().Radians().value(), groundTruthState.pose.X().value(), groundTruthState.pose.Y().value(), @@ -119,14 +119,14 @@ void testFollowTrajectory( } if (debug) { - wpi::print("apply_time, measured_time, vision_x, vision_y, vision_theta\n"); + wpi::util::print("apply_time, measured_time, vision_x, vision_y, vision_theta\n"); - units::second_t apply_time; - units::second_t measure_time; - frc::Pose2d vision_pose; + wpi::units::second_t apply_time; + wpi::units::second_t measure_time; + wpi::math::Pose2d vision_pose; for (auto record : visionLog) { std::tie(apply_time, measure_time, vision_pose) = record; - wpi::print("{}, {}, {}, {}, {}\n", apply_time.value(), + wpi::util::print("{}, {}, {}, {}, {}\n", apply_time.value(), measure_time.value(), vision_pose.X().value(), vision_pose.Y().value(), vision_pose.Rotation().Radians().value()); @@ -149,65 +149,65 @@ void testFollowTrajectory( } TEST(DifferentialDrivePoseEstimatorTest, Accuracy) { - frc::DifferentialDriveKinematics kinematics{1.0_m}; + wpi::math::DifferentialDriveKinematics kinematics{1.0_m}; - frc::DifferentialDrivePoseEstimator estimator{ - kinematics, frc::Rotation2d{}, 0_m, 0_m, frc::Pose2d{}, + wpi::math::DifferentialDrivePoseEstimator estimator{ + kinematics, wpi::math::Rotation2d{}, 0_m, 0_m, wpi::math::Pose2d{}, {0.02, 0.02, 0.01}, {0.1, 0.1, 0.1}}; - frc::Trajectory trajectory = frc::TrajectoryGenerator::GenerateTrajectory( - std::vector{frc::Pose2d{0_m, 0_m, 45_deg}, frc::Pose2d{3_m, 0_m, -90_deg}, - frc::Pose2d{0_m, 0_m, 135_deg}, - frc::Pose2d{-3_m, 0_m, -90_deg}, - frc::Pose2d{0_m, 0_m, 45_deg}}, - frc::TrajectoryConfig(2_mps, 2_mps_sq)); + wpi::math::Trajectory trajectory = wpi::math::TrajectoryGenerator::GenerateTrajectory( + std::vector{wpi::math::Pose2d{0_m, 0_m, 45_deg}, wpi::math::Pose2d{3_m, 0_m, -90_deg}, + wpi::math::Pose2d{0_m, 0_m, 135_deg}, + wpi::math::Pose2d{-3_m, 0_m, -90_deg}, + wpi::math::Pose2d{0_m, 0_m, 45_deg}}, + wpi::math::TrajectoryConfig(2_mps, 2_mps_sq)); testFollowTrajectory( kinematics, estimator, trajectory, - [&](frc::Trajectory::State& state) { - return frc::ChassisSpeeds{state.velocity, 0_mps, + [&](wpi::math::Trajectory::State& state) { + return wpi::math::ChassisSpeeds{state.velocity, 0_mps, state.velocity * state.curvature}; }, - [&](frc::Trajectory::State& state) { return state.pose; }, - trajectory.InitialPose(), {0_m, 0_m, frc::Rotation2d{45_deg}}, 20_ms, + [&](wpi::math::Trajectory::State& state) { return state.pose; }, + trajectory.InitialPose(), {0_m, 0_m, wpi::math::Rotation2d{45_deg}}, 20_ms, 100_ms, 250_ms, true, false); } TEST(DifferentialDrivePoseEstimatorTest, BadInitialPose) { - frc::DifferentialDriveKinematics kinematics{1.0_m}; + wpi::math::DifferentialDriveKinematics kinematics{1.0_m}; - frc::DifferentialDrivePoseEstimator estimator{ - kinematics, frc::Rotation2d{}, 0_m, 0_m, frc::Pose2d{}, + wpi::math::DifferentialDrivePoseEstimator estimator{ + kinematics, wpi::math::Rotation2d{}, 0_m, 0_m, wpi::math::Pose2d{}, {0.02, 0.02, 0.01}, {0.1, 0.1, 0.1}}; - frc::Trajectory trajectory = frc::TrajectoryGenerator::GenerateTrajectory( - std::vector{frc::Pose2d{0_m, 0_m, 45_deg}, frc::Pose2d{3_m, 0_m, -90_deg}, - frc::Pose2d{0_m, 0_m, 135_deg}, - frc::Pose2d{-3_m, 0_m, -90_deg}, - frc::Pose2d{0_m, 0_m, 45_deg}}, - frc::TrajectoryConfig(2_mps, 2_mps_sq)); + wpi::math::Trajectory trajectory = wpi::math::TrajectoryGenerator::GenerateTrajectory( + std::vector{wpi::math::Pose2d{0_m, 0_m, 45_deg}, wpi::math::Pose2d{3_m, 0_m, -90_deg}, + wpi::math::Pose2d{0_m, 0_m, 135_deg}, + wpi::math::Pose2d{-3_m, 0_m, -90_deg}, + wpi::math::Pose2d{0_m, 0_m, 45_deg}}, + wpi::math::TrajectoryConfig(2_mps, 2_mps_sq)); - for (units::degree_t offset_direction_degs = 0_deg; + for (wpi::units::degree_t offset_direction_degs = 0_deg; offset_direction_degs < 360_deg; offset_direction_degs += 45_deg) { - for (units::degree_t offset_heading_degs = 0_deg; + for (wpi::units::degree_t offset_heading_degs = 0_deg; offset_heading_degs < 360_deg; offset_heading_degs += 45_deg) { - auto pose_offset = frc::Rotation2d{offset_direction_degs}; - auto heading_offset = frc::Rotation2d{offset_heading_degs}; + auto pose_offset = wpi::math::Rotation2d{offset_direction_degs}; + auto heading_offset = wpi::math::Rotation2d{offset_heading_degs}; auto initial_pose = trajectory.InitialPose() + - frc::Transform2d{frc::Translation2d{pose_offset.Cos() * 1_m, + wpi::math::Transform2d{wpi::math::Translation2d{pose_offset.Cos() * 1_m, pose_offset.Sin() * 1_m}, heading_offset}; testFollowTrajectory( kinematics, estimator, trajectory, - [&](frc::Trajectory::State& state) { - return frc::ChassisSpeeds{state.velocity, 0_mps, + [&](wpi::math::Trajectory::State& state) { + return wpi::math::ChassisSpeeds{state.velocity, 0_mps, state.velocity * state.curvature}; }, - [&](frc::Trajectory::State& state) { return state.pose; }, - initial_pose, {0_m, 0_m, frc::Rotation2d{45_deg}}, 20_ms, 100_ms, + [&](wpi::math::Trajectory::State& state) { return state.pose; }, + initial_pose, {0_m, 0_m, wpi::math::Rotation2d{45_deg}}, 20_ms, 100_ms, 250_ms, false, false); } } @@ -219,50 +219,50 @@ TEST(DifferentialDrivePoseEstimatorTest, SimultaneousVisionMeasurements) { // The alternative result is that only one vision measurement affects the // outcome. If that were the case, after 1000 measurements, the estimated // pose would converge to that measurement. - frc::DifferentialDriveKinematics kinematics{1.0_m}; + wpi::math::DifferentialDriveKinematics kinematics{1.0_m}; - frc::DifferentialDrivePoseEstimator estimator{ + wpi::math::DifferentialDrivePoseEstimator estimator{ kinematics, - frc::Rotation2d{}, + wpi::math::Rotation2d{}, 0_m, 0_m, - frc::Pose2d{1_m, 2_m, frc::Rotation2d{270_deg}}, + wpi::math::Pose2d{1_m, 2_m, wpi::math::Rotation2d{270_deg}}, {0.02, 0.02, 0.01}, {0.1, 0.1, 0.1}}; - estimator.UpdateWithTime(0_s, frc::Rotation2d{}, 0_m, 0_m); + estimator.UpdateWithTime(0_s, wpi::math::Rotation2d{}, 0_m, 0_m); for (int i = 0; i < 1000; i++) { estimator.AddVisionMeasurement( - frc::Pose2d{0_m, 0_m, frc::Rotation2d{0_deg}}, 0_s); + wpi::math::Pose2d{0_m, 0_m, wpi::math::Rotation2d{0_deg}}, 0_s); estimator.AddVisionMeasurement( - frc::Pose2d{3_m, 1_m, frc::Rotation2d{90_deg}}, 0_s); + wpi::math::Pose2d{3_m, 1_m, wpi::math::Rotation2d{90_deg}}, 0_s); estimator.AddVisionMeasurement( - frc::Pose2d{2_m, 4_m, frc::Rotation2d{180_deg}}, 0_s); + wpi::math::Pose2d{2_m, 4_m, wpi::math::Rotation2d{180_deg}}, 0_s); } { - auto dx = units::math::abs(estimator.GetEstimatedPosition().X() - 0_m); - auto dy = units::math::abs(estimator.GetEstimatedPosition().Y() - 0_m); - auto dtheta = units::math::abs( + auto dx = wpi::units::math::abs(estimator.GetEstimatedPosition().X() - 0_m); + auto dy = wpi::units::math::abs(estimator.GetEstimatedPosition().Y() - 0_m); + auto dtheta = wpi::units::math::abs( estimator.GetEstimatedPosition().Rotation().Radians() - 0_deg); EXPECT_TRUE(dx > 0.08_m || dy > 0.08_m || dtheta > 0.08_rad); } { - auto dx = units::math::abs(estimator.GetEstimatedPosition().X() - 3_m); - auto dy = units::math::abs(estimator.GetEstimatedPosition().Y() - 1_m); - auto dtheta = units::math::abs( + auto dx = wpi::units::math::abs(estimator.GetEstimatedPosition().X() - 3_m); + auto dy = wpi::units::math::abs(estimator.GetEstimatedPosition().Y() - 1_m); + auto dtheta = wpi::units::math::abs( estimator.GetEstimatedPosition().Rotation().Radians() - 90_deg); EXPECT_TRUE(dx > 0.08_m || dy > 0.08_m || dtheta > 0.08_rad); } { - auto dx = units::math::abs(estimator.GetEstimatedPosition().X() - 2_m); - auto dy = units::math::abs(estimator.GetEstimatedPosition().Y() - 4_m); - auto dtheta = units::math::abs( + auto dx = wpi::units::math::abs(estimator.GetEstimatedPosition().X() - 2_m); + auto dy = wpi::units::math::abs(estimator.GetEstimatedPosition().Y() - 4_m); + auto dtheta = wpi::units::math::abs( estimator.GetEstimatedPosition().Rotation().Radians() - 180_deg); EXPECT_TRUE(dx > 0.08_m || dy > 0.08_m || dtheta > 0.08_rad); @@ -270,22 +270,22 @@ TEST(DifferentialDrivePoseEstimatorTest, SimultaneousVisionMeasurements) { } TEST(DifferentialDrivePoseEstimatorTest, TestDiscardStaleVisionMeasurements) { - frc::DifferentialDriveKinematics kinematics{1_m}; + wpi::math::DifferentialDriveKinematics kinematics{1_m}; - frc::DifferentialDrivePoseEstimator estimator{ - kinematics, frc::Rotation2d{}, 0_m, 0_m, frc::Pose2d{}, + wpi::math::DifferentialDrivePoseEstimator estimator{ + kinematics, wpi::math::Rotation2d{}, 0_m, 0_m, wpi::math::Pose2d{}, {0.1, 0.1, 0.1}, {0.45, 0.45, 0.45}}; // Add enough measurements to fill up the buffer for (auto time = 0_s; time < 4_s; time += 20_ms) { - estimator.UpdateWithTime(time, frc::Rotation2d{}, 0_m, 0_m); + estimator.UpdateWithTime(time, wpi::math::Rotation2d{}, 0_m, 0_m); } auto odometryPose = estimator.GetEstimatedPosition(); // Apply a vision measurement from 3 seconds ago estimator.AddVisionMeasurement( - frc::Pose2d{frc::Translation2d{10_m, 10_m}, frc::Rotation2d{0.1_rad}}, + wpi::math::Pose2d{wpi::math::Translation2d{10_m, 10_m}, wpi::math::Rotation2d{0.1_rad}}, 1_s, {0.1, 0.1, 0.1}); EXPECT_NEAR(odometryPose.X().value(), @@ -298,9 +298,9 @@ TEST(DifferentialDrivePoseEstimatorTest, TestDiscardStaleVisionMeasurements) { } TEST(DifferentialDrivePoseEstimatorTest, TestSampleAt) { - frc::DifferentialDriveKinematics kinematics{1_m}; - frc::DifferentialDrivePoseEstimator estimator{ - kinematics, frc::Rotation2d{}, 0_m, 0_m, frc::Pose2d{}, + wpi::math::DifferentialDriveKinematics kinematics{1_m}; + wpi::math::DifferentialDrivePoseEstimator estimator{ + kinematics, wpi::math::Rotation2d{}, 0_m, 0_m, wpi::math::Pose2d{}, {1.0, 1.0, 1.0}, {1.0, 1.0, 1.0}}; // Returns empty when null @@ -310,60 +310,60 @@ TEST(DifferentialDrivePoseEstimatorTest, TestSampleAt) { // Add a tiny tolerance for the upper bound because of floating point rounding // error for (double time = 1; time <= 2 + 1e-9; time += 0.02) { - estimator.UpdateWithTime(units::second_t{time}, frc::Rotation2d{}, - units::meter_t{time}, units::meter_t{time}); + estimator.UpdateWithTime(wpi::units::second_t{time}, wpi::math::Rotation2d{}, + wpi::units::meter_t{time}, wpi::units::meter_t{time}); } // Sample at an added time - EXPECT_EQ(std::optional(frc::Pose2d{1.02_m, 0_m, frc::Rotation2d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose2d{1.02_m, 0_m, wpi::math::Rotation2d{}}), estimator.SampleAt(1.02_s)); // Sample between updates (test interpolation) - EXPECT_EQ(std::optional(frc::Pose2d{1.01_m, 0_m, frc::Rotation2d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose2d{1.01_m, 0_m, wpi::math::Rotation2d{}}), estimator.SampleAt(1.01_s)); // Sampling before the oldest value returns the oldest value - EXPECT_EQ(std::optional(frc::Pose2d{1_m, 0_m, frc::Rotation2d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose2d{1_m, 0_m, wpi::math::Rotation2d{}}), estimator.SampleAt(0.5_s)); // Sampling after the newest value returns the newest value - EXPECT_EQ(std::optional(frc::Pose2d{2_m, 0_m, frc::Rotation2d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose2d{2_m, 0_m, wpi::math::Rotation2d{}}), estimator.SampleAt(2.5_s)); // Add a vision measurement after the odometry measurements (while keeping all // of the old odometry measurements) - estimator.AddVisionMeasurement(frc::Pose2d{2_m, 0_m, frc::Rotation2d{1_rad}}, + estimator.AddVisionMeasurement(wpi::math::Pose2d{2_m, 0_m, wpi::math::Rotation2d{1_rad}}, 2.2_s); // Make sure nothing changed (except the newest value) - EXPECT_EQ(std::optional(frc::Pose2d{1.02_m, 0_m, frc::Rotation2d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose2d{1.02_m, 0_m, wpi::math::Rotation2d{}}), estimator.SampleAt(1.02_s)); - EXPECT_EQ(std::optional(frc::Pose2d{1.01_m, 0_m, frc::Rotation2d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose2d{1.01_m, 0_m, wpi::math::Rotation2d{}}), estimator.SampleAt(1.01_s)); - EXPECT_EQ(std::optional(frc::Pose2d{1_m, 0_m, frc::Rotation2d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose2d{1_m, 0_m, wpi::math::Rotation2d{}}), estimator.SampleAt(0.5_s)); // Add a vision measurement before the odometry measurements that's still in // the buffer - estimator.AddVisionMeasurement(frc::Pose2d{1_m, 0.2_m, frc::Rotation2d{}}, + estimator.AddVisionMeasurement(wpi::math::Pose2d{1_m, 0.2_m, wpi::math::Rotation2d{}}, 0.9_s); // Everything should be the same except Y is 0.1 (halfway between 0 and 0.2) - EXPECT_EQ(std::optional(frc::Pose2d{1.02_m, 0.1_m, frc::Rotation2d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose2d{1.02_m, 0.1_m, wpi::math::Rotation2d{}}), estimator.SampleAt(1.02_s)); - EXPECT_EQ(std::optional(frc::Pose2d{1.01_m, 0.1_m, frc::Rotation2d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose2d{1.01_m, 0.1_m, wpi::math::Rotation2d{}}), estimator.SampleAt(1.01_s)); - EXPECT_EQ(std::optional(frc::Pose2d{1_m, 0.1_m, frc::Rotation2d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose2d{1_m, 0.1_m, wpi::math::Rotation2d{}}), estimator.SampleAt(0.5_s)); - EXPECT_EQ(std::optional(frc::Pose2d{2_m, 0.1_m, frc::Rotation2d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose2d{2_m, 0.1_m, wpi::math::Rotation2d{}}), estimator.SampleAt(2.5_s)); } TEST(DifferentialDrivePoseEstimatorTest, TestReset) { - frc::DifferentialDriveKinematics kinematics{1_m}; - frc::DifferentialDrivePoseEstimator estimator{ + wpi::math::DifferentialDriveKinematics kinematics{1_m}; + wpi::math::DifferentialDrivePoseEstimator estimator{ kinematics, - frc::Rotation2d{}, + wpi::math::Rotation2d{}, 0_m, 0_m, - frc::Pose2d{-1_m, -1_m, frc::Rotation2d{1_rad}}, + wpi::math::Pose2d{-1_m, -1_m, wpi::math::Rotation2d{1_rad}}, {1.0, 1.0, 1.0}, {1.0, 1.0, 1.0}}; @@ -374,8 +374,8 @@ TEST(DifferentialDrivePoseEstimatorTest, TestReset) { 1, estimator.GetEstimatedPosition().Rotation().Radians().value()); // Test reset position - estimator.ResetPosition(frc::Rotation2d{}, 1_m, 1_m, - frc::Pose2d{1_m, 0_m, frc::Rotation2d{}}); + estimator.ResetPosition(wpi::math::Rotation2d{}, 1_m, 1_m, + wpi::math::Pose2d{1_m, 0_m, wpi::math::Rotation2d{}}); EXPECT_DOUBLE_EQ(1, estimator.GetEstimatedPosition().X().value()); EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Y().value()); @@ -383,7 +383,7 @@ TEST(DifferentialDrivePoseEstimatorTest, TestReset) { 0, estimator.GetEstimatedPosition().Rotation().Radians().value()); // Test orientation and wheel positions - estimator.Update(frc::Rotation2d{}, 2_m, 2_m); + estimator.Update(wpi::math::Rotation2d{}, 2_m, 2_m); EXPECT_DOUBLE_EQ(2, estimator.GetEstimatedPosition().X().value()); EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Y().value()); @@ -391,7 +391,7 @@ TEST(DifferentialDrivePoseEstimatorTest, TestReset) { 0, estimator.GetEstimatedPosition().Rotation().Radians().value()); // Test reset rotation - estimator.ResetRotation(frc::Rotation2d{90_deg}); + estimator.ResetRotation(wpi::math::Rotation2d{90_deg}); EXPECT_DOUBLE_EQ(2, estimator.GetEstimatedPosition().X().value()); EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Y().value()); @@ -400,7 +400,7 @@ TEST(DifferentialDrivePoseEstimatorTest, TestReset) { estimator.GetEstimatedPosition().Rotation().Radians().value()); // Test orientation - estimator.Update(frc::Rotation2d{}, 3_m, 3_m); + estimator.Update(wpi::math::Rotation2d{}, 3_m, 3_m); EXPECT_DOUBLE_EQ(2, estimator.GetEstimatedPosition().X().value()); EXPECT_DOUBLE_EQ(1, estimator.GetEstimatedPosition().Y().value()); @@ -409,7 +409,7 @@ TEST(DifferentialDrivePoseEstimatorTest, TestReset) { estimator.GetEstimatedPosition().Rotation().Radians().value()); // Test reset translation - estimator.ResetTranslation(frc::Translation2d{-1_m, -1_m}); + estimator.ResetTranslation(wpi::math::Translation2d{-1_m, -1_m}); EXPECT_DOUBLE_EQ(-1, estimator.GetEstimatedPosition().X().value()); EXPECT_DOUBLE_EQ(-1, estimator.GetEstimatedPosition().Y().value()); @@ -418,7 +418,7 @@ TEST(DifferentialDrivePoseEstimatorTest, TestReset) { estimator.GetEstimatedPosition().Rotation().Radians().value()); // Test reset pose - estimator.ResetPose(frc::Pose2d{}); + estimator.ResetPose(wpi::math::Pose2d{}); EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().X().value()); EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Y().value()); diff --git a/wpimath/src/test/native/cpp/estimator/ExtendedKalmanFilterTest.cpp b/wpimath/src/test/native/cpp/estimator/ExtendedKalmanFilterTest.cpp index d3dd4ccd27..9af0aedb81 100644 --- a/wpimath/src/test/native/cpp/estimator/ExtendedKalmanFilterTest.cpp +++ b/wpimath/src/test/native/cpp/estimator/ExtendedKalmanFilterTest.cpp @@ -18,8 +18,8 @@ namespace { -frc::Vectord<5> Dynamics(const frc::Vectord<5>& x, const frc::Vectord<2>& u) { - auto motors = frc::DCMotor::CIM(2); +wpi::math::Vectord<5> Dynamics(const wpi::math::Vectord<5>& x, const wpi::math::Vectord<2>& u) { + auto motors = wpi::math::DCMotor::CIM(2); // constexpr double Glow = 15.32; // Low gear ratio constexpr double Ghigh = 7.08; // High gear ratio @@ -29,18 +29,18 @@ frc::Vectord<5> Dynamics(const frc::Vectord<5>& x, const frc::Vectord<2>& u) { constexpr auto J = 5.6_kg_sq_m; // Robot moment of inertia auto C1 = -std::pow(Ghigh, 2) * motors.Kt / - (motors.Kv * motors.R * units::math::pow<2>(r)); + (motors.Kv * motors.R * wpi::units::math::pow<2>(r)); auto C2 = Ghigh * motors.Kt / (motors.R * r); - auto k1 = (1 / m + units::math::pow<2>(rb) / J); - auto k2 = (1 / m - units::math::pow<2>(rb) / J); + auto k1 = (1 / m + wpi::units::math::pow<2>(rb) / J); + auto k2 = (1 / m - wpi::units::math::pow<2>(rb) / J); - units::meters_per_second_t vl{x(3)}; - units::meters_per_second_t vr{x(4)}; - units::volt_t Vl{u(0)}; - units::volt_t Vr{u(1)}; + wpi::units::meters_per_second_t vl{x(3)}; + wpi::units::meters_per_second_t vr{x(4)}; + wpi::units::volt_t Vl{u(0)}; + wpi::units::volt_t Vr{u(1)}; auto v = 0.5 * (vl + vr); - return frc::Vectord<5>{ + return wpi::math::Vectord<5>{ v.value() * std::cos(x(2)), v.value() * std::sin(x(2)), ((vr - vl) / (2.0 * rb)).value(), k1.value() * ((C1 * vl).value() + (C2 * Vl).value()) + @@ -49,59 +49,59 @@ frc::Vectord<5> Dynamics(const frc::Vectord<5>& x, const frc::Vectord<2>& u) { k1.value() * ((C1 * vr).value() + (C2 * Vr).value())}; } -frc::Vectord<3> LocalMeasurementModel( - const frc::Vectord<5>& x, [[maybe_unused]] const frc::Vectord<2>& u) { - return frc::Vectord<3>{x(2), x(3), x(4)}; +wpi::math::Vectord<3> LocalMeasurementModel( + const wpi::math::Vectord<5>& x, [[maybe_unused]] const wpi::math::Vectord<2>& u) { + return wpi::math::Vectord<3>{x(2), x(3), x(4)}; } -frc::Vectord<5> GlobalMeasurementModel( - const frc::Vectord<5>& x, [[maybe_unused]] const frc::Vectord<2>& u) { - return frc::Vectord<5>{x(0), x(1), x(2), x(3), x(4)}; +wpi::math::Vectord<5> GlobalMeasurementModel( + const wpi::math::Vectord<5>& x, [[maybe_unused]] const wpi::math::Vectord<2>& u) { + return wpi::math::Vectord<5>{x(0), x(1), x(2), x(3), x(4)}; } } // namespace TEST(ExtendedKalmanFilterTest, Init) { - constexpr units::second_t dt = 5_ms; + constexpr wpi::units::second_t dt = 5_ms; - frc::ExtendedKalmanFilter<5, 2, 3> observer{Dynamics, + wpi::math::ExtendedKalmanFilter<5, 2, 3> observer{Dynamics, LocalMeasurementModel, {0.5, 0.5, 10.0, 1.0, 1.0}, {0.0001, 0.01, 0.01}, dt}; - frc::Vectord<2> u{12.0, 12.0}; + wpi::math::Vectord<2> u{12.0, 12.0}; observer.Predict(u, dt); auto localY = LocalMeasurementModel(observer.Xhat(), u); observer.Correct(u, localY); auto globalY = GlobalMeasurementModel(observer.Xhat(), u); - auto R = frc::MakeCovMatrix(0.01, 0.01, 0.0001, 0.01, 0.01); + auto R = wpi::math::MakeCovMatrix(0.01, 0.01, 0.0001, 0.01, 0.01); observer.Correct<5>(u, globalY, GlobalMeasurementModel, R); } TEST(ExtendedKalmanFilterTest, Convergence) { - constexpr units::second_t dt = 5_ms; + constexpr wpi::units::second_t dt = 5_ms; constexpr auto rb = 0.8382_m / 2.0; // Robot radius - frc::ExtendedKalmanFilter<5, 2, 3> observer{Dynamics, + wpi::math::ExtendedKalmanFilter<5, 2, 3> observer{Dynamics, LocalMeasurementModel, {0.5, 0.5, 10.0, 1.0, 1.0}, {0.0001, 0.5, 0.5}, dt}; auto waypoints = - std::vector{frc::Pose2d{2.75_m, 22.521_m, 0_rad}, - frc::Pose2d{24.73_m, 19.68_m, 5.846_rad}}; - auto trajectory = frc::TrajectoryGenerator::GenerateTrajectory( + std::vector{wpi::math::Pose2d{2.75_m, 22.521_m, 0_rad}, + wpi::math::Pose2d{24.73_m, 19.68_m, 5.846_rad}}; + auto trajectory = wpi::math::TrajectoryGenerator::GenerateTrajectory( waypoints, {8.8_mps, 0.1_mps_sq}); - frc::Vectord<5> r = frc::Vectord<5>::Zero(); - frc::Vectord<2> u = frc::Vectord<2>::Zero(); + wpi::math::Vectord<5> r = wpi::math::Vectord<5>::Zero(); + wpi::math::Vectord<2> u = wpi::math::Vectord<2>::Zero(); - auto B = frc::NumericalJacobianU<5, 5, 2>(Dynamics, frc::Vectord<5>::Zero(), - frc::Vectord<2>::Zero()); + auto B = wpi::math::NumericalJacobianU<5, 5, 2>(Dynamics, wpi::math::Vectord<5>::Zero(), + wpi::math::Vectord<2>::Zero()); - observer.SetXhat(frc::Vectord<5>{ + observer.SetXhat(wpi::math::Vectord<5>{ trajectory.InitialPose().Translation().X().value(), trajectory.InitialPose().Translation().Y().value(), trajectory.InitialPose().Rotation().Radians().value(), 0.0, 0.0}); @@ -109,20 +109,20 @@ TEST(ExtendedKalmanFilterTest, Convergence) { auto totalTime = trajectory.TotalTime(); for (size_t i = 0; i < (totalTime / dt).value(); ++i) { auto ref = trajectory.Sample(dt * i); - units::meters_per_second_t vl = + wpi::units::meters_per_second_t vl = ref.velocity * (1 - (ref.curvature * rb).value()); - units::meters_per_second_t vr = + wpi::units::meters_per_second_t vr = ref.velocity * (1 + (ref.curvature * rb).value()); - frc::Vectord<5> nextR{ + wpi::math::Vectord<5> nextR{ ref.pose.Translation().X().value(), ref.pose.Translation().Y().value(), ref.pose.Rotation().Radians().value(), vl.value(), vr.value()}; - auto localY = LocalMeasurementModel(nextR, frc::Vectord<2>::Zero()); - observer.Correct(u, localY + frc::MakeWhiteNoiseVector(0.0001, 0.5, 0.5)); + auto localY = LocalMeasurementModel(nextR, wpi::math::Vectord<2>::Zero()); + observer.Correct(u, localY + wpi::math::MakeWhiteNoiseVector(0.0001, 0.5, 0.5)); - frc::Vectord<5> rdot = (nextR - r) / dt.value(); - u = B.householderQr().solve(rdot - Dynamics(r, frc::Vectord<2>::Zero())); + wpi::math::Vectord<5> rdot = (nextR - r) / dt.value(); + u = B.householderQr().solve(rdot - Dynamics(r, wpi::math::Vectord<2>::Zero())); observer.Predict(u, dt); @@ -133,7 +133,7 @@ TEST(ExtendedKalmanFilterTest, Convergence) { observer.Correct(u, localY); auto globalY = GlobalMeasurementModel(observer.Xhat(), u); - auto R = frc::MakeCovMatrix(0.01, 0.01, 0.0001, 0.5, 0.5); + auto R = wpi::math::MakeCovMatrix(0.01, 0.01, 0.0001, 0.5, 0.5); observer.Correct<5>(u, globalY, GlobalMeasurementModel, R); auto finalPosition = trajectory.Sample(trajectory.TotalTime()); diff --git a/wpimath/src/test/native/cpp/estimator/KalmanFilterTest.cpp b/wpimath/src/test/native/cpp/estimator/KalmanFilterTest.cpp index 4e0444ce97..9fabc5479d 100644 --- a/wpimath/src/test/native/cpp/estimator/KalmanFilterTest.cpp +++ b/wpimath/src/test/native/cpp/estimator/KalmanFilterTest.cpp @@ -15,7 +15,7 @@ #include "wpi/units/time.hpp" TEST(KalmanFilterTest, Flywheel) { - auto motor = frc::DCMotor::NEO(); - auto flywheel = frc::LinearSystemId::FlywheelSystem(motor, 1_kg_sq_m, 1.0); - frc::KalmanFilter<1, 1, 1> kf{flywheel, {1}, {1}, 5_ms}; + auto motor = wpi::math::DCMotor::NEO(); + auto flywheel = wpi::math::LinearSystemId::FlywheelSystem(motor, 1_kg_sq_m, 1.0); + wpi::math::KalmanFilter<1, 1, 1> kf{flywheel, {1}, {1}, 5_ms}; } diff --git a/wpimath/src/test/native/cpp/estimator/MecanumDrivePoseEstimator3dTest.cpp b/wpimath/src/test/native/cpp/estimator/MecanumDrivePoseEstimator3dTest.cpp index d0097cffe0..5dbd7eff32 100644 --- a/wpimath/src/test/native/cpp/estimator/MecanumDrivePoseEstimator3dTest.cpp +++ b/wpimath/src/test/native/cpp/estimator/MecanumDrivePoseEstimator3dTest.cpp @@ -16,40 +16,40 @@ #include "wpi/util/print.hpp" void testFollowTrajectory( - const frc::MecanumDriveKinematics& kinematics, - frc::MecanumDrivePoseEstimator3d& estimator, - const frc::Trajectory& trajectory, - std::function + const wpi::math::MecanumDriveKinematics& kinematics, + wpi::math::MecanumDrivePoseEstimator3d& estimator, + const wpi::math::Trajectory& trajectory, + std::function chassisSpeedsGenerator, - std::function + std::function visionMeasurementGenerator, - const frc::Pose2d& startingPose, const frc::Pose2d& endingPose, - const units::second_t dt, const units::second_t kVisionUpdateRate, - const units::second_t kVisionUpdateDelay, const bool checkError, + const wpi::math::Pose2d& startingPose, const wpi::math::Pose2d& endingPose, + const wpi::units::second_t dt, const wpi::units::second_t kVisionUpdateRate, + const wpi::units::second_t kVisionUpdateDelay, const bool checkError, const bool debug) { - frc::MecanumDriveWheelPositions wheelPositions{}; + wpi::math::MecanumDriveWheelPositions wheelPositions{}; - estimator.ResetPosition(frc::Rotation3d{}, wheelPositions, - frc::Pose3d{startingPose}); + estimator.ResetPosition(wpi::math::Rotation3d{}, wheelPositions, + wpi::math::Pose3d{startingPose}); std::default_random_engine generator; std::normal_distribution distribution(0.0, 1.0); - units::second_t t = 0_s; + wpi::units::second_t t = 0_s; - std::vector> visionPoses; - std::vector> + std::vector> visionPoses; + std::vector> visionLog; double maxError = -std::numeric_limits::max(); double errorSum = 0; if (debug) { - wpi::print("time, est_x, est_y, est_theta, true_x, true_y, true_theta\n"); + wpi::util::print("time, est_x, est_y, est_theta, true_x, true_y, true_theta\n"); } while (t < trajectory.TotalTime()) { - frc::Trajectory::State groundTruthState = trajectory.Sample(t); + wpi::math::Trajectory::State groundTruthState = trajectory.Sample(t); // We are due for a new vision measurement if it's been `visionUpdateRate` // seconds since the last vision measurement @@ -57,9 +57,9 @@ void testFollowTrajectory( visionPoses.back().first + kVisionUpdateRate < t) { auto visionPose = visionMeasurementGenerator(groundTruthState) + - frc::Transform2d{frc::Translation2d{distribution(generator) * 0.1_m, + wpi::math::Transform2d{wpi::math::Translation2d{distribution(generator) * 0.1_m, distribution(generator) * 0.1_m}, - frc::Rotation2d{distribution(generator) * 0.05_rad}}; + wpi::math::Rotation2d{distribution(generator) * 0.05_rad}}; visionPoses.push_back({t, visionPose}); } @@ -68,7 +68,7 @@ void testFollowTrajectory( if (!visionPoses.empty() && visionPoses.front().first + kVisionUpdateDelay < t) { auto visionEntry = visionPoses.front(); - estimator.AddVisionMeasurement(frc::Pose3d{visionEntry.second}, + estimator.AddVisionMeasurement(wpi::math::Pose3d{visionEntry.second}, visionEntry.first); visionPoses.erase(visionPoses.begin()); visionLog.push_back({t, visionEntry.first, visionEntry.second}); @@ -85,13 +85,13 @@ void testFollowTrajectory( auto xhat = estimator.UpdateWithTime( t, - frc::Rotation3d{groundTruthState.pose.Rotation() + - frc::Rotation2d{distribution(generator) * 0.05_rad} - + wpi::math::Rotation3d{groundTruthState.pose.Rotation() + + wpi::math::Rotation2d{distribution(generator) * 0.05_rad} - trajectory.InitialPose().Rotation()}, wheelPositions); if (debug) { - wpi::print( + wpi::util::print( "{}, {}, {}, {}, {}, {}, {}\n", t.value(), xhat.X().value(), xhat.Y().value(), xhat.Rotation().ToRotation2d().Radians().value(), groundTruthState.pose.X().value(), groundTruthState.pose.Y().value(), @@ -111,14 +111,14 @@ void testFollowTrajectory( } if (debug) { - wpi::print("apply_time, measured_time, vision_x, vision_y, vision_theta\n"); + wpi::util::print("apply_time, measured_time, vision_x, vision_y, vision_theta\n"); - units::second_t apply_time; - units::second_t measure_time; - frc::Pose2d vision_pose; + wpi::units::second_t apply_time; + wpi::units::second_t measure_time; + wpi::math::Pose2d vision_pose; for (auto record : visionLog) { std::tie(apply_time, measure_time, vision_pose) = record; - wpi::print("{}, {}, {}, {}, {}\n", apply_time.value(), + wpi::util::print("{}, {}, {}, {}, {}\n", apply_time.value(), measure_time.value(), vision_pose.X().value(), vision_pose.Y().value(), vision_pose.Rotation().Radians().value()); @@ -145,73 +145,73 @@ void testFollowTrajectory( } TEST(MecanumDrivePoseEstimator3dTest, AccuracyFacingTrajectory) { - frc::MecanumDriveKinematics kinematics{ - frc::Translation2d{1_m, 1_m}, frc::Translation2d{1_m, -1_m}, - frc::Translation2d{-1_m, -1_m}, frc::Translation2d{-1_m, 1_m}}; + wpi::math::MecanumDriveKinematics kinematics{ + wpi::math::Translation2d{1_m, 1_m}, wpi::math::Translation2d{1_m, -1_m}, + wpi::math::Translation2d{-1_m, -1_m}, wpi::math::Translation2d{-1_m, 1_m}}; - frc::MecanumDriveWheelPositions wheelPositions; + wpi::math::MecanumDriveWheelPositions wheelPositions; - frc::MecanumDrivePoseEstimator3d estimator{ - kinematics, frc::Rotation3d{}, wheelPositions, - frc::Pose3d{}, {0.1, 0.1, 0.1, 0.1}, {0.45, 0.45, 0.45, 0.45}}; + wpi::math::MecanumDrivePoseEstimator3d estimator{ + kinematics, wpi::math::Rotation3d{}, wheelPositions, + wpi::math::Pose3d{}, {0.1, 0.1, 0.1, 0.1}, {0.45, 0.45, 0.45, 0.45}}; - frc::Trajectory trajectory = frc::TrajectoryGenerator::GenerateTrajectory( - std::vector{frc::Pose2d{0_m, 0_m, 45_deg}, frc::Pose2d{3_m, 0_m, -90_deg}, - frc::Pose2d{0_m, 0_m, 135_deg}, - frc::Pose2d{-3_m, 0_m, -90_deg}, - frc::Pose2d{0_m, 0_m, 45_deg}}, - frc::TrajectoryConfig(2.0_mps, 2.0_mps_sq)); + wpi::math::Trajectory trajectory = wpi::math::TrajectoryGenerator::GenerateTrajectory( + std::vector{wpi::math::Pose2d{0_m, 0_m, 45_deg}, wpi::math::Pose2d{3_m, 0_m, -90_deg}, + wpi::math::Pose2d{0_m, 0_m, 135_deg}, + wpi::math::Pose2d{-3_m, 0_m, -90_deg}, + wpi::math::Pose2d{0_m, 0_m, 45_deg}}, + wpi::math::TrajectoryConfig(2.0_mps, 2.0_mps_sq)); testFollowTrajectory( kinematics, estimator, trajectory, - [&](frc::Trajectory::State& state) { - return frc::ChassisSpeeds{state.velocity, 0_mps, + [&](wpi::math::Trajectory::State& state) { + return wpi::math::ChassisSpeeds{state.velocity, 0_mps, state.velocity * state.curvature}; }, - [&](frc::Trajectory::State& state) { return state.pose; }, - trajectory.InitialPose(), {0_m, 0_m, frc::Rotation2d{45_deg}}, 20_ms, + [&](wpi::math::Trajectory::State& state) { return state.pose; }, + trajectory.InitialPose(), {0_m, 0_m, wpi::math::Rotation2d{45_deg}}, 20_ms, 100_ms, 250_ms, true, false); } TEST(MecanumDrivePoseEstimator3dTest, BadInitialPose) { - frc::MecanumDriveKinematics kinematics{ - frc::Translation2d{1_m, 1_m}, frc::Translation2d{1_m, -1_m}, - frc::Translation2d{-1_m, -1_m}, frc::Translation2d{-1_m, 1_m}}; + wpi::math::MecanumDriveKinematics kinematics{ + wpi::math::Translation2d{1_m, 1_m}, wpi::math::Translation2d{1_m, -1_m}, + wpi::math::Translation2d{-1_m, -1_m}, wpi::math::Translation2d{-1_m, 1_m}}; - frc::MecanumDriveWheelPositions wheelPositions; + wpi::math::MecanumDriveWheelPositions wheelPositions; - frc::MecanumDrivePoseEstimator3d estimator{ - kinematics, frc::Rotation3d{}, wheelPositions, - frc::Pose3d{}, {0.1, 0.1, 0.1, 0.1}, {0.45, 0.45, 0.45, 0.1}}; + wpi::math::MecanumDrivePoseEstimator3d estimator{ + kinematics, wpi::math::Rotation3d{}, wheelPositions, + wpi::math::Pose3d{}, {0.1, 0.1, 0.1, 0.1}, {0.45, 0.45, 0.45, 0.1}}; - frc::Trajectory trajectory = frc::TrajectoryGenerator::GenerateTrajectory( - std::vector{frc::Pose2d{0_m, 0_m, 45_deg}, frc::Pose2d{3_m, 0_m, -90_deg}, - frc::Pose2d{0_m, 0_m, 135_deg}, - frc::Pose2d{-3_m, 0_m, -90_deg}, - frc::Pose2d{0_m, 0_m, 45_deg}}, - frc::TrajectoryConfig(2.0_mps, 2.0_mps_sq)); + wpi::math::Trajectory trajectory = wpi::math::TrajectoryGenerator::GenerateTrajectory( + std::vector{wpi::math::Pose2d{0_m, 0_m, 45_deg}, wpi::math::Pose2d{3_m, 0_m, -90_deg}, + wpi::math::Pose2d{0_m, 0_m, 135_deg}, + wpi::math::Pose2d{-3_m, 0_m, -90_deg}, + wpi::math::Pose2d{0_m, 0_m, 45_deg}}, + wpi::math::TrajectoryConfig(2.0_mps, 2.0_mps_sq)); - for (units::degree_t offset_direction_degs = 0_deg; + for (wpi::units::degree_t offset_direction_degs = 0_deg; offset_direction_degs < 360_deg; offset_direction_degs += 45_deg) { - for (units::degree_t offset_heading_degs = 0_deg; + for (wpi::units::degree_t offset_heading_degs = 0_deg; offset_heading_degs < 360_deg; offset_heading_degs += 45_deg) { - auto pose_offset = frc::Rotation2d{offset_direction_degs}; - auto heading_offset = frc::Rotation2d{offset_heading_degs}; + auto pose_offset = wpi::math::Rotation2d{offset_direction_degs}; + auto heading_offset = wpi::math::Rotation2d{offset_heading_degs}; auto initial_pose = trajectory.InitialPose() + - frc::Transform2d{frc::Translation2d{pose_offset.Cos() * 1_m, + wpi::math::Transform2d{wpi::math::Translation2d{pose_offset.Cos() * 1_m, pose_offset.Sin() * 1_m}, heading_offset}; testFollowTrajectory( kinematics, estimator, trajectory, - [&](frc::Trajectory::State& state) { - return frc::ChassisSpeeds{state.velocity, 0_mps, + [&](wpi::math::Trajectory::State& state) { + return wpi::math::ChassisSpeeds{state.velocity, 0_mps, state.velocity * state.curvature}; }, - [&](frc::Trajectory::State& state) { return state.pose; }, - initial_pose, {0_m, 0_m, frc::Rotation2d{45_deg}}, 20_ms, 100_ms, + [&](wpi::math::Trajectory::State& state) { return state.pose; }, + initial_pose, {0_m, 0_m, wpi::math::Rotation2d{45_deg}}, 20_ms, 100_ms, 250_ms, false, false); } } @@ -223,36 +223,36 @@ TEST(MecanumDrivePoseEstimator3dTest, SimultaneousVisionMeasurements) { // The alternative result is that only one vision measurement affects the // outcome. If that were the case, after 1000 measurements, the estimated // pose would converge to that measurement. - frc::MecanumDriveKinematics kinematics{ - frc::Translation2d{1_m, 1_m}, frc::Translation2d{1_m, -1_m}, - frc::Translation2d{-1_m, -1_m}, frc::Translation2d{-1_m, 1_m}}; + wpi::math::MecanumDriveKinematics kinematics{ + wpi::math::Translation2d{1_m, 1_m}, wpi::math::Translation2d{1_m, -1_m}, + wpi::math::Translation2d{-1_m, -1_m}, wpi::math::Translation2d{-1_m, 1_m}}; - frc::MecanumDriveWheelPositions wheelPositions; + wpi::math::MecanumDriveWheelPositions wheelPositions; - frc::MecanumDrivePoseEstimator3d estimator{ + wpi::math::MecanumDrivePoseEstimator3d estimator{ kinematics, - frc::Rotation3d{}, + wpi::math::Rotation3d{}, wheelPositions, - frc::Pose3d{1_m, 2_m, 0_m, frc::Rotation3d{0_deg, 0_deg, 270_deg}}, + wpi::math::Pose3d{1_m, 2_m, 0_m, wpi::math::Rotation3d{0_deg, 0_deg, 270_deg}}, {0.1, 0.1, 0.1, 0.1}, {0.45, 0.45, 0.45, 0.1}}; - estimator.UpdateWithTime(0_s, frc::Rotation3d{}, wheelPositions); + estimator.UpdateWithTime(0_s, wpi::math::Rotation3d{}, wheelPositions); for (int i = 0; i < 1000; i++) { estimator.AddVisionMeasurement( - frc::Pose3d{0_m, 0_m, 0_m, frc::Rotation3d{0_deg, 0_deg, 0_deg}}, 0_s); + wpi::math::Pose3d{0_m, 0_m, 0_m, wpi::math::Rotation3d{0_deg, 0_deg, 0_deg}}, 0_s); estimator.AddVisionMeasurement( - frc::Pose3d{3_m, 1_m, 0_m, frc::Rotation3d{0_deg, 0_deg, 90_deg}}, 0_s); + wpi::math::Pose3d{3_m, 1_m, 0_m, wpi::math::Rotation3d{0_deg, 0_deg, 90_deg}}, 0_s); estimator.AddVisionMeasurement( - frc::Pose3d{2_m, 4_m, 0_m, frc::Rotation3d{0_deg, 0_deg, 180_deg}}, + wpi::math::Pose3d{2_m, 4_m, 0_m, wpi::math::Rotation3d{0_deg, 0_deg, 180_deg}}, 0_s); } { - auto dx = units::math::abs(estimator.GetEstimatedPosition().X() - 0_m); - auto dy = units::math::abs(estimator.GetEstimatedPosition().Y() - 0_m); - auto dtheta = units::math::abs( + auto dx = wpi::units::math::abs(estimator.GetEstimatedPosition().X() - 0_m); + auto dy = wpi::units::math::abs(estimator.GetEstimatedPosition().Y() - 0_m); + auto dtheta = wpi::units::math::abs( estimator.GetEstimatedPosition().Rotation().ToRotation2d().Radians() - 0_deg); @@ -260,9 +260,9 @@ TEST(MecanumDrivePoseEstimator3dTest, SimultaneousVisionMeasurements) { } { - auto dx = units::math::abs(estimator.GetEstimatedPosition().X() - 3_m); - auto dy = units::math::abs(estimator.GetEstimatedPosition().Y() - 1_m); - auto dtheta = units::math::abs( + auto dx = wpi::units::math::abs(estimator.GetEstimatedPosition().X() - 3_m); + auto dy = wpi::units::math::abs(estimator.GetEstimatedPosition().Y() - 1_m); + auto dtheta = wpi::units::math::abs( estimator.GetEstimatedPosition().Rotation().ToRotation2d().Radians() - 90_deg); @@ -270,9 +270,9 @@ TEST(MecanumDrivePoseEstimator3dTest, SimultaneousVisionMeasurements) { } { - auto dx = units::math::abs(estimator.GetEstimatedPosition().X() - 2_m); - auto dy = units::math::abs(estimator.GetEstimatedPosition().Y() - 4_m); - auto dtheta = units::math::abs( + auto dx = wpi::units::math::abs(estimator.GetEstimatedPosition().X() - 2_m); + auto dy = wpi::units::math::abs(estimator.GetEstimatedPosition().Y() - 4_m); + auto dtheta = wpi::units::math::abs( estimator.GetEstimatedPosition().Rotation().ToRotation2d().Radians() - 180_deg); @@ -281,25 +281,25 @@ TEST(MecanumDrivePoseEstimator3dTest, SimultaneousVisionMeasurements) { } TEST(MecanumDrivePoseEstimator3dTest, TestDiscardStaleVisionMeasurements) { - frc::MecanumDriveKinematics kinematics{ - frc::Translation2d{1_m, 1_m}, frc::Translation2d{1_m, -1_m}, - frc::Translation2d{-1_m, -1_m}, frc::Translation2d{-1_m, 1_m}}; + wpi::math::MecanumDriveKinematics kinematics{ + wpi::math::Translation2d{1_m, 1_m}, wpi::math::Translation2d{1_m, -1_m}, + wpi::math::Translation2d{-1_m, -1_m}, wpi::math::Translation2d{-1_m, 1_m}}; - frc::MecanumDrivePoseEstimator3d estimator{ - kinematics, frc::Rotation3d{}, frc::MecanumDriveWheelPositions{}, - frc::Pose3d{}, {0.1, 0.1, 0.1, 0.1}, {0.45, 0.45, 0.45, 0.45}}; + wpi::math::MecanumDrivePoseEstimator3d estimator{ + kinematics, wpi::math::Rotation3d{}, wpi::math::MecanumDriveWheelPositions{}, + wpi::math::Pose3d{}, {0.1, 0.1, 0.1, 0.1}, {0.45, 0.45, 0.45, 0.45}}; // Add enough measurements to fill up the buffer for (auto time = 0_s; time < 4_s; time += 20_ms) { - estimator.UpdateWithTime(time, frc::Rotation3d{}, - frc::MecanumDriveWheelPositions{}); + estimator.UpdateWithTime(time, wpi::math::Rotation3d{}, + wpi::math::MecanumDriveWheelPositions{}); } auto odometryPose = estimator.GetEstimatedPosition(); // Apply a vision measurement from 3 seconds ago estimator.AddVisionMeasurement( - frc::Pose3d{10_m, 10_m, 0_m, frc::Rotation3d{0_rad, 0_rad, 0.1_rad}}, 1_s, + wpi::math::Pose3d{10_m, 10_m, 0_m, wpi::math::Rotation3d{0_rad, 0_rad, 0.1_rad}}, 1_s, {0.1, 0.1, 0.1, 0.1}); EXPECT_NEAR(odometryPose.X().value(), @@ -317,12 +317,12 @@ TEST(MecanumDrivePoseEstimator3dTest, TestDiscardStaleVisionMeasurements) { } TEST(MecanumDrivePoseEstimator3dTest, TestSampleAt) { - frc::MecanumDriveKinematics kinematics{ - frc::Translation2d{1_m, 1_m}, frc::Translation2d{1_m, -1_m}, - frc::Translation2d{-1_m, -1_m}, frc::Translation2d{-1_m, 1_m}}; - frc::MecanumDrivePoseEstimator3d estimator{ - kinematics, frc::Rotation3d{}, frc::MecanumDriveWheelPositions{}, - frc::Pose3d{}, {1.0, 1.0, 1.0, 1.0}, {1.0, 1.0, 1.0, 1.0}}; + wpi::math::MecanumDriveKinematics kinematics{ + wpi::math::Translation2d{1_m, 1_m}, wpi::math::Translation2d{1_m, -1_m}, + wpi::math::Translation2d{-1_m, -1_m}, wpi::math::Translation2d{-1_m, 1_m}}; + wpi::math::MecanumDrivePoseEstimator3d estimator{ + kinematics, wpi::math::Rotation3d{}, wpi::math::MecanumDriveWheelPositions{}, + wpi::math::Pose3d{}, {1.0, 1.0, 1.0, 1.0}, {1.0, 1.0, 1.0, 1.0}}; // Returns empty when null EXPECT_EQ(std::nullopt, estimator.SampleAt(1_s)); @@ -331,64 +331,64 @@ TEST(MecanumDrivePoseEstimator3dTest, TestSampleAt) { // Add a tiny tolerance for the upper bound because of floating point rounding // error for (double time = 1; time <= 2 + 1e-9; time += 0.02) { - frc::MecanumDriveWheelPositions wheelPositions{ - units::meter_t{time}, units::meter_t{time}, units::meter_t{time}, - units::meter_t{time}}; - estimator.UpdateWithTime(units::second_t{time}, frc::Rotation3d{}, + wpi::math::MecanumDriveWheelPositions wheelPositions{ + wpi::units::meter_t{time}, wpi::units::meter_t{time}, wpi::units::meter_t{time}, + wpi::units::meter_t{time}}; + estimator.UpdateWithTime(wpi::units::second_t{time}, wpi::math::Rotation3d{}, wheelPositions); } // Sample at an added time - EXPECT_EQ(std::optional(frc::Pose3d{1.02_m, 0_m, 0_m, frc::Rotation3d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose3d{1.02_m, 0_m, 0_m, wpi::math::Rotation3d{}}), estimator.SampleAt(1.02_s)); // Sample between updates (test interpolation) - EXPECT_EQ(std::optional(frc::Pose3d{1.01_m, 0_m, 0_m, frc::Rotation3d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose3d{1.01_m, 0_m, 0_m, wpi::math::Rotation3d{}}), estimator.SampleAt(1.01_s)); // Sampling before the oldest value returns the oldest value - EXPECT_EQ(std::optional(frc::Pose3d{1_m, 0_m, 0_m, frc::Rotation3d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose3d{1_m, 0_m, 0_m, wpi::math::Rotation3d{}}), estimator.SampleAt(0.5_s)); // Sampling after the newest value returns the newest value - EXPECT_EQ(std::optional(frc::Pose3d{2_m, 0_m, 0_m, frc::Rotation3d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose3d{2_m, 0_m, 0_m, wpi::math::Rotation3d{}}), estimator.SampleAt(2.5_s)); // Add a vision measurement after the odometry measurements (while keeping all // of the old odometry measurements) estimator.AddVisionMeasurement( - frc::Pose3d{2_m, 0_m, 0_m, frc::Rotation3d{0_rad, 0_rad, 1_rad}}, 2.2_s); + wpi::math::Pose3d{2_m, 0_m, 0_m, wpi::math::Rotation3d{0_rad, 0_rad, 1_rad}}, 2.2_s); // Make sure nothing changed (except the newest value) - EXPECT_EQ(std::optional(frc::Pose3d{1.02_m, 0_m, 0_m, frc::Rotation3d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose3d{1.02_m, 0_m, 0_m, wpi::math::Rotation3d{}}), estimator.SampleAt(1.02_s)); - EXPECT_EQ(std::optional(frc::Pose3d{1.01_m, 0_m, 0_m, frc::Rotation3d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose3d{1.01_m, 0_m, 0_m, wpi::math::Rotation3d{}}), estimator.SampleAt(1.01_s)); - EXPECT_EQ(std::optional(frc::Pose3d{1_m, 0_m, 0_m, frc::Rotation3d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose3d{1_m, 0_m, 0_m, wpi::math::Rotation3d{}}), estimator.SampleAt(0.5_s)); // Add a vision measurement before the odometry measurements that's still in // the buffer estimator.AddVisionMeasurement( - frc::Pose3d{1_m, 0.2_m, 0_m, frc::Rotation3d{}}, 0.9_s); + wpi::math::Pose3d{1_m, 0.2_m, 0_m, wpi::math::Rotation3d{}}, 0.9_s); // Everything should be the same except Y is 0.1 (halfway between 0 and 0.2) - EXPECT_EQ(std::optional(frc::Pose3d{1.02_m, 0.1_m, 0_m, frc::Rotation3d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose3d{1.02_m, 0.1_m, 0_m, wpi::math::Rotation3d{}}), estimator.SampleAt(1.02_s)); - EXPECT_EQ(std::optional(frc::Pose3d{1.01_m, 0.1_m, 0_m, frc::Rotation3d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose3d{1.01_m, 0.1_m, 0_m, wpi::math::Rotation3d{}}), estimator.SampleAt(1.01_s)); - EXPECT_EQ(std::optional(frc::Pose3d{1_m, 0.1_m, 0_m, frc::Rotation3d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose3d{1_m, 0.1_m, 0_m, wpi::math::Rotation3d{}}), estimator.SampleAt(0.5_s)); - EXPECT_EQ(std::optional(frc::Pose3d{2_m, 0.1_m, 0_m, frc::Rotation3d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose3d{2_m, 0.1_m, 0_m, wpi::math::Rotation3d{}}), estimator.SampleAt(2.5_s)); } TEST(MecanumDrivePoseEstimator3dTest, TestReset) { - frc::MecanumDriveKinematics kinematics{ - frc::Translation2d{1_m, 1_m}, frc::Translation2d{1_m, -1_m}, - frc::Translation2d{-1_m, -1_m}, frc::Translation2d{-1_m, 1_m}}; - frc::MecanumDrivePoseEstimator3d estimator{ + wpi::math::MecanumDriveKinematics kinematics{ + wpi::math::Translation2d{1_m, 1_m}, wpi::math::Translation2d{1_m, -1_m}, + wpi::math::Translation2d{-1_m, -1_m}, wpi::math::Translation2d{-1_m, 1_m}}; + wpi::math::MecanumDrivePoseEstimator3d estimator{ kinematics, - frc::Rotation3d{}, - frc::MecanumDriveWheelPositions{}, - frc::Pose3d{-1_m, -1_m, -1_m, frc::Rotation3d{0_rad, 0_rad, 1_rad}}, + wpi::math::Rotation3d{}, + wpi::math::MecanumDriveWheelPositions{}, + wpi::math::Pose3d{-1_m, -1_m, -1_m, wpi::math::Rotation3d{0_rad, 0_rad, 1_rad}}, {1.0, 1.0, 1.0, 1.0}, {1.0, 1.0, 1.0, 1.0}}; @@ -401,8 +401,8 @@ TEST(MecanumDrivePoseEstimator3dTest, TestReset) { EXPECT_DOUBLE_EQ(1, estimator.GetEstimatedPosition().Rotation().Z().value()); // Test reset position - estimator.ResetPosition(frc::Rotation3d{}, {1_m, 1_m, 1_m, 1_m}, - frc::Pose3d{1_m, 0_m, 0_m, frc::Rotation3d{}}); + estimator.ResetPosition(wpi::math::Rotation3d{}, {1_m, 1_m, 1_m, 1_m}, + wpi::math::Pose3d{1_m, 0_m, 0_m, wpi::math::Rotation3d{}}); EXPECT_DOUBLE_EQ(1, estimator.GetEstimatedPosition().X().value()); EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Y().value()); @@ -412,7 +412,7 @@ TEST(MecanumDrivePoseEstimator3dTest, TestReset) { EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Rotation().Z().value()); // Test orientation and wheel positions - estimator.Update(frc::Rotation3d{}, {2_m, 2_m, 2_m, 2_m}); + estimator.Update(wpi::math::Rotation3d{}, {2_m, 2_m, 2_m, 2_m}); EXPECT_DOUBLE_EQ(2, estimator.GetEstimatedPosition().X().value()); EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Y().value()); @@ -422,7 +422,7 @@ TEST(MecanumDrivePoseEstimator3dTest, TestReset) { EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Rotation().Z().value()); // Test reset rotation - estimator.ResetRotation(frc::Rotation3d{0_deg, 0_deg, 90_deg}); + estimator.ResetRotation(wpi::math::Rotation3d{0_deg, 0_deg, 90_deg}); EXPECT_DOUBLE_EQ(2, estimator.GetEstimatedPosition().X().value()); EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Y().value()); @@ -433,7 +433,7 @@ TEST(MecanumDrivePoseEstimator3dTest, TestReset) { estimator.GetEstimatedPosition().Rotation().Z().value()); // Test orientation - estimator.Update(frc::Rotation3d{}, {3_m, 3_m, 3_m, 3_m}); + estimator.Update(wpi::math::Rotation3d{}, {3_m, 3_m, 3_m, 3_m}); EXPECT_DOUBLE_EQ(2, estimator.GetEstimatedPosition().X().value()); EXPECT_DOUBLE_EQ(1, estimator.GetEstimatedPosition().Y().value()); @@ -444,7 +444,7 @@ TEST(MecanumDrivePoseEstimator3dTest, TestReset) { estimator.GetEstimatedPosition().Rotation().Z().value()); // Test reset translation - estimator.ResetTranslation(frc::Translation3d{-1_m, -1_m, -1_m}); + estimator.ResetTranslation(wpi::math::Translation3d{-1_m, -1_m, -1_m}); EXPECT_DOUBLE_EQ(-1, estimator.GetEstimatedPosition().X().value()); EXPECT_DOUBLE_EQ(-1, estimator.GetEstimatedPosition().Y().value()); @@ -455,7 +455,7 @@ TEST(MecanumDrivePoseEstimator3dTest, TestReset) { estimator.GetEstimatedPosition().Rotation().Z().value()); // Test reset pose - estimator.ResetPose(frc::Pose3d{}); + estimator.ResetPose(wpi::math::Pose3d{}); EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().X().value()); EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Y().value()); diff --git a/wpimath/src/test/native/cpp/estimator/MecanumDrivePoseEstimatorTest.cpp b/wpimath/src/test/native/cpp/estimator/MecanumDrivePoseEstimatorTest.cpp index 99fc0763a0..a305bc0bd2 100644 --- a/wpimath/src/test/native/cpp/estimator/MecanumDrivePoseEstimatorTest.cpp +++ b/wpimath/src/test/native/cpp/estimator/MecanumDrivePoseEstimatorTest.cpp @@ -17,39 +17,39 @@ #include "wpi/util/print.hpp" void testFollowTrajectory( - const frc::MecanumDriveKinematics& kinematics, - frc::MecanumDrivePoseEstimator& estimator, - const frc::Trajectory& trajectory, - std::function + const wpi::math::MecanumDriveKinematics& kinematics, + wpi::math::MecanumDrivePoseEstimator& estimator, + const wpi::math::Trajectory& trajectory, + std::function chassisSpeedsGenerator, - std::function + std::function visionMeasurementGenerator, - const frc::Pose2d& startingPose, const frc::Pose2d& endingPose, - const units::second_t dt, const units::second_t kVisionUpdateRate, - const units::second_t kVisionUpdateDelay, const bool checkError, + const wpi::math::Pose2d& startingPose, const wpi::math::Pose2d& endingPose, + const wpi::units::second_t dt, const wpi::units::second_t kVisionUpdateRate, + const wpi::units::second_t kVisionUpdateDelay, const bool checkError, const bool debug) { - frc::MecanumDriveWheelPositions wheelPositions{}; + wpi::math::MecanumDriveWheelPositions wheelPositions{}; - estimator.ResetPosition(frc::Rotation2d{}, wheelPositions, startingPose); + estimator.ResetPosition(wpi::math::Rotation2d{}, wheelPositions, startingPose); std::default_random_engine generator; std::normal_distribution distribution(0.0, 1.0); - units::second_t t = 0_s; + wpi::units::second_t t = 0_s; - std::vector> visionPoses; - std::vector> + std::vector> visionPoses; + std::vector> visionLog; double maxError = -std::numeric_limits::max(); double errorSum = 0; if (debug) { - wpi::print("time, est_x, est_y, est_theta, true_x, true_y, true_theta\n"); + wpi::util::print("time, est_x, est_y, est_theta, true_x, true_y, true_theta\n"); } while (t < trajectory.TotalTime()) { - frc::Trajectory::State groundTruthState = trajectory.Sample(t); + wpi::math::Trajectory::State groundTruthState = trajectory.Sample(t); // We are due for a new vision measurement if it's been `visionUpdateRate` // seconds since the last vision measurement @@ -57,9 +57,9 @@ void testFollowTrajectory( visionPoses.back().first + kVisionUpdateRate < t) { auto visionPose = visionMeasurementGenerator(groundTruthState) + - frc::Transform2d{frc::Translation2d{distribution(generator) * 0.1_m, + wpi::math::Transform2d{wpi::math::Translation2d{distribution(generator) * 0.1_m, distribution(generator) * 0.1_m}, - frc::Rotation2d{distribution(generator) * 0.05_rad}}; + wpi::math::Rotation2d{distribution(generator) * 0.05_rad}}; visionPoses.push_back({t, visionPose}); } @@ -85,12 +85,12 @@ void testFollowTrajectory( auto xhat = estimator.UpdateWithTime( t, groundTruthState.pose.Rotation() + - frc::Rotation2d{distribution(generator) * 0.05_rad} - + wpi::math::Rotation2d{distribution(generator) * 0.05_rad} - trajectory.InitialPose().Rotation(), wheelPositions); if (debug) { - wpi::print("{}, {}, {}, {}, {}, {}, {}\n", t.value(), xhat.X().value(), + wpi::util::print("{}, {}, {}, {}, {}, {}, {}\n", t.value(), xhat.X().value(), xhat.Y().value(), xhat.Rotation().Radians().value(), groundTruthState.pose.X().value(), groundTruthState.pose.Y().value(), @@ -110,14 +110,14 @@ void testFollowTrajectory( } if (debug) { - wpi::print("apply_time, measured_time, vision_x, vision_y, vision_theta\n"); + wpi::util::print("apply_time, measured_time, vision_x, vision_y, vision_theta\n"); - units::second_t apply_time; - units::second_t measure_time; - frc::Pose2d vision_pose; + wpi::units::second_t apply_time; + wpi::units::second_t measure_time; + wpi::math::Pose2d vision_pose; for (auto record : visionLog) { std::tie(apply_time, measure_time, vision_pose) = record; - wpi::print("{}, {}, {}, {}, {}\n", apply_time.value(), + wpi::util::print("{}, {}, {}, {}, {}\n", apply_time.value(), measure_time.value(), vision_pose.X().value(), vision_pose.Y().value(), vision_pose.Rotation().Radians().value()); @@ -140,73 +140,73 @@ void testFollowTrajectory( } TEST(MecanumDrivePoseEstimatorTest, AccuracyFacingTrajectory) { - frc::MecanumDriveKinematics kinematics{ - frc::Translation2d{1_m, 1_m}, frc::Translation2d{1_m, -1_m}, - frc::Translation2d{-1_m, -1_m}, frc::Translation2d{-1_m, 1_m}}; + wpi::math::MecanumDriveKinematics kinematics{ + wpi::math::Translation2d{1_m, 1_m}, wpi::math::Translation2d{1_m, -1_m}, + wpi::math::Translation2d{-1_m, -1_m}, wpi::math::Translation2d{-1_m, 1_m}}; - frc::MecanumDriveWheelPositions wheelPositions; + wpi::math::MecanumDriveWheelPositions wheelPositions; - frc::MecanumDrivePoseEstimator estimator{kinematics, frc::Rotation2d{}, - wheelPositions, frc::Pose2d{}, + wpi::math::MecanumDrivePoseEstimator estimator{kinematics, wpi::math::Rotation2d{}, + wheelPositions, wpi::math::Pose2d{}, {0.1, 0.1, 0.1}, {0.45, 0.45, 0.45}}; - frc::Trajectory trajectory = frc::TrajectoryGenerator::GenerateTrajectory( - std::vector{frc::Pose2d{0_m, 0_m, 45_deg}, frc::Pose2d{3_m, 0_m, -90_deg}, - frc::Pose2d{0_m, 0_m, 135_deg}, - frc::Pose2d{-3_m, 0_m, -90_deg}, - frc::Pose2d{0_m, 0_m, 45_deg}}, - frc::TrajectoryConfig(2.0_mps, 2.0_mps_sq)); + wpi::math::Trajectory trajectory = wpi::math::TrajectoryGenerator::GenerateTrajectory( + std::vector{wpi::math::Pose2d{0_m, 0_m, 45_deg}, wpi::math::Pose2d{3_m, 0_m, -90_deg}, + wpi::math::Pose2d{0_m, 0_m, 135_deg}, + wpi::math::Pose2d{-3_m, 0_m, -90_deg}, + wpi::math::Pose2d{0_m, 0_m, 45_deg}}, + wpi::math::TrajectoryConfig(2.0_mps, 2.0_mps_sq)); testFollowTrajectory( kinematics, estimator, trajectory, - [&](frc::Trajectory::State& state) { - return frc::ChassisSpeeds{state.velocity, 0_mps, + [&](wpi::math::Trajectory::State& state) { + return wpi::math::ChassisSpeeds{state.velocity, 0_mps, state.velocity * state.curvature}; }, - [&](frc::Trajectory::State& state) { return state.pose; }, - trajectory.InitialPose(), {0_m, 0_m, frc::Rotation2d{45_deg}}, 20_ms, + [&](wpi::math::Trajectory::State& state) { return state.pose; }, + trajectory.InitialPose(), {0_m, 0_m, wpi::math::Rotation2d{45_deg}}, 20_ms, 100_ms, 250_ms, true, false); } TEST(MecanumDrivePoseEstimatorTest, BadInitialPose) { - frc::MecanumDriveKinematics kinematics{ - frc::Translation2d{1_m, 1_m}, frc::Translation2d{1_m, -1_m}, - frc::Translation2d{-1_m, -1_m}, frc::Translation2d{-1_m, 1_m}}; + wpi::math::MecanumDriveKinematics kinematics{ + wpi::math::Translation2d{1_m, 1_m}, wpi::math::Translation2d{1_m, -1_m}, + wpi::math::Translation2d{-1_m, -1_m}, wpi::math::Translation2d{-1_m, 1_m}}; - frc::MecanumDriveWheelPositions wheelPositions; + wpi::math::MecanumDriveWheelPositions wheelPositions; - frc::MecanumDrivePoseEstimator estimator{kinematics, frc::Rotation2d{}, - wheelPositions, frc::Pose2d{}, + wpi::math::MecanumDrivePoseEstimator estimator{kinematics, wpi::math::Rotation2d{}, + wheelPositions, wpi::math::Pose2d{}, {0.1, 0.1, 0.1}, {0.45, 0.45, 0.1}}; - frc::Trajectory trajectory = frc::TrajectoryGenerator::GenerateTrajectory( - std::vector{frc::Pose2d{0_m, 0_m, 45_deg}, frc::Pose2d{3_m, 0_m, -90_deg}, - frc::Pose2d{0_m, 0_m, 135_deg}, - frc::Pose2d{-3_m, 0_m, -90_deg}, - frc::Pose2d{0_m, 0_m, 45_deg}}, - frc::TrajectoryConfig(2.0_mps, 2.0_mps_sq)); + wpi::math::Trajectory trajectory = wpi::math::TrajectoryGenerator::GenerateTrajectory( + std::vector{wpi::math::Pose2d{0_m, 0_m, 45_deg}, wpi::math::Pose2d{3_m, 0_m, -90_deg}, + wpi::math::Pose2d{0_m, 0_m, 135_deg}, + wpi::math::Pose2d{-3_m, 0_m, -90_deg}, + wpi::math::Pose2d{0_m, 0_m, 45_deg}}, + wpi::math::TrajectoryConfig(2.0_mps, 2.0_mps_sq)); - for (units::degree_t offset_direction_degs = 0_deg; + for (wpi::units::degree_t offset_direction_degs = 0_deg; offset_direction_degs < 360_deg; offset_direction_degs += 45_deg) { - for (units::degree_t offset_heading_degs = 0_deg; + for (wpi::units::degree_t offset_heading_degs = 0_deg; offset_heading_degs < 360_deg; offset_heading_degs += 45_deg) { - auto pose_offset = frc::Rotation2d{offset_direction_degs}; - auto heading_offset = frc::Rotation2d{offset_heading_degs}; + auto pose_offset = wpi::math::Rotation2d{offset_direction_degs}; + auto heading_offset = wpi::math::Rotation2d{offset_heading_degs}; auto initial_pose = trajectory.InitialPose() + - frc::Transform2d{frc::Translation2d{pose_offset.Cos() * 1_m, + wpi::math::Transform2d{wpi::math::Translation2d{pose_offset.Cos() * 1_m, pose_offset.Sin() * 1_m}, heading_offset}; testFollowTrajectory( kinematics, estimator, trajectory, - [&](frc::Trajectory::State& state) { - return frc::ChassisSpeeds{state.velocity, 0_mps, + [&](wpi::math::Trajectory::State& state) { + return wpi::math::ChassisSpeeds{state.velocity, 0_mps, state.velocity * state.curvature}; }, - [&](frc::Trajectory::State& state) { return state.pose; }, - initial_pose, {0_m, 0_m, frc::Rotation2d{45_deg}}, 20_ms, 100_ms, + [&](wpi::math::Trajectory::State& state) { return state.pose; }, + initial_pose, {0_m, 0_m, wpi::math::Rotation2d{45_deg}}, 20_ms, 100_ms, 250_ms, false, false); } } @@ -218,50 +218,50 @@ TEST(MecanumDrivePoseEstimatorTest, SimultaneousVisionMeasurements) { // The alternative result is that only one vision measurement affects the // outcome. If that were the case, after 1000 measurements, the estimated // pose would converge to that measurement. - frc::MecanumDriveKinematics kinematics{ - frc::Translation2d{1_m, 1_m}, frc::Translation2d{1_m, -1_m}, - frc::Translation2d{-1_m, -1_m}, frc::Translation2d{-1_m, 1_m}}; + wpi::math::MecanumDriveKinematics kinematics{ + wpi::math::Translation2d{1_m, 1_m}, wpi::math::Translation2d{1_m, -1_m}, + wpi::math::Translation2d{-1_m, -1_m}, wpi::math::Translation2d{-1_m, 1_m}}; - frc::MecanumDriveWheelPositions wheelPositions; + wpi::math::MecanumDriveWheelPositions wheelPositions; - frc::MecanumDrivePoseEstimator estimator{ - kinematics, frc::Rotation2d{}, - wheelPositions, frc::Pose2d{1_m, 2_m, frc::Rotation2d{270_deg}}, + wpi::math::MecanumDrivePoseEstimator estimator{ + kinematics, wpi::math::Rotation2d{}, + wheelPositions, wpi::math::Pose2d{1_m, 2_m, wpi::math::Rotation2d{270_deg}}, {0.1, 0.1, 0.1}, {0.45, 0.45, 0.1}}; - estimator.UpdateWithTime(0_s, frc::Rotation2d{}, wheelPositions); + estimator.UpdateWithTime(0_s, wpi::math::Rotation2d{}, wheelPositions); for (int i = 0; i < 1000; i++) { estimator.AddVisionMeasurement( - frc::Pose2d{0_m, 0_m, frc::Rotation2d{0_deg}}, 0_s); + wpi::math::Pose2d{0_m, 0_m, wpi::math::Rotation2d{0_deg}}, 0_s); estimator.AddVisionMeasurement( - frc::Pose2d{3_m, 1_m, frc::Rotation2d{90_deg}}, 0_s); + wpi::math::Pose2d{3_m, 1_m, wpi::math::Rotation2d{90_deg}}, 0_s); estimator.AddVisionMeasurement( - frc::Pose2d{2_m, 4_m, frc::Rotation2d{180_deg}}, 0_s); + wpi::math::Pose2d{2_m, 4_m, wpi::math::Rotation2d{180_deg}}, 0_s); } { - auto dx = units::math::abs(estimator.GetEstimatedPosition().X() - 0_m); - auto dy = units::math::abs(estimator.GetEstimatedPosition().Y() - 0_m); - auto dtheta = units::math::abs( + auto dx = wpi::units::math::abs(estimator.GetEstimatedPosition().X() - 0_m); + auto dy = wpi::units::math::abs(estimator.GetEstimatedPosition().Y() - 0_m); + auto dtheta = wpi::units::math::abs( estimator.GetEstimatedPosition().Rotation().Radians() - 0_deg); EXPECT_TRUE(dx > 0.08_m || dy > 0.08_m || dtheta > 0.08_rad); } { - auto dx = units::math::abs(estimator.GetEstimatedPosition().X() - 3_m); - auto dy = units::math::abs(estimator.GetEstimatedPosition().Y() - 1_m); - auto dtheta = units::math::abs( + auto dx = wpi::units::math::abs(estimator.GetEstimatedPosition().X() - 3_m); + auto dy = wpi::units::math::abs(estimator.GetEstimatedPosition().Y() - 1_m); + auto dtheta = wpi::units::math::abs( estimator.GetEstimatedPosition().Rotation().Radians() - 90_deg); EXPECT_TRUE(dx > 0.08_m || dy > 0.08_m || dtheta > 0.08_rad); } { - auto dx = units::math::abs(estimator.GetEstimatedPosition().X() - 2_m); - auto dy = units::math::abs(estimator.GetEstimatedPosition().Y() - 4_m); - auto dtheta = units::math::abs( + auto dx = wpi::units::math::abs(estimator.GetEstimatedPosition().X() - 2_m); + auto dy = wpi::units::math::abs(estimator.GetEstimatedPosition().Y() - 4_m); + auto dtheta = wpi::units::math::abs( estimator.GetEstimatedPosition().Rotation().Radians() - 180_deg); EXPECT_TRUE(dx > 0.08_m || dy > 0.08_m || dtheta > 0.08_rad); @@ -269,25 +269,25 @@ TEST(MecanumDrivePoseEstimatorTest, SimultaneousVisionMeasurements) { } TEST(MecanumDrivePoseEstimatorTest, TestDiscardStaleVisionMeasurements) { - frc::MecanumDriveKinematics kinematics{ - frc::Translation2d{1_m, 1_m}, frc::Translation2d{1_m, -1_m}, - frc::Translation2d{-1_m, -1_m}, frc::Translation2d{-1_m, 1_m}}; + wpi::math::MecanumDriveKinematics kinematics{ + wpi::math::Translation2d{1_m, 1_m}, wpi::math::Translation2d{1_m, -1_m}, + wpi::math::Translation2d{-1_m, -1_m}, wpi::math::Translation2d{-1_m, 1_m}}; - frc::MecanumDrivePoseEstimator estimator{ - kinematics, frc::Rotation2d{}, frc::MecanumDriveWheelPositions{}, - frc::Pose2d{}, {0.1, 0.1, 0.1}, {0.45, 0.45, 0.45}}; + wpi::math::MecanumDrivePoseEstimator estimator{ + kinematics, wpi::math::Rotation2d{}, wpi::math::MecanumDriveWheelPositions{}, + wpi::math::Pose2d{}, {0.1, 0.1, 0.1}, {0.45, 0.45, 0.45}}; // Add enough measurements to fill up the buffer for (auto time = 0_s; time < 4_s; time += 20_ms) { - estimator.UpdateWithTime(time, frc::Rotation2d{}, - frc::MecanumDriveWheelPositions{}); + estimator.UpdateWithTime(time, wpi::math::Rotation2d{}, + wpi::math::MecanumDriveWheelPositions{}); } auto odometryPose = estimator.GetEstimatedPosition(); // Apply a vision measurement from 3 seconds ago estimator.AddVisionMeasurement( - frc::Pose2d{frc::Translation2d{10_m, 10_m}, frc::Rotation2d{0.1_rad}}, + wpi::math::Pose2d{wpi::math::Translation2d{10_m, 10_m}, wpi::math::Rotation2d{0.1_rad}}, 1_s, {0.1, 0.1, 0.1}); EXPECT_NEAR(odometryPose.X().value(), @@ -300,12 +300,12 @@ TEST(MecanumDrivePoseEstimatorTest, TestDiscardStaleVisionMeasurements) { } TEST(MecanumDrivePoseEstimatorTest, TestSampleAt) { - frc::MecanumDriveKinematics kinematics{ - frc::Translation2d{1_m, 1_m}, frc::Translation2d{1_m, -1_m}, - frc::Translation2d{-1_m, -1_m}, frc::Translation2d{-1_m, 1_m}}; - frc::MecanumDrivePoseEstimator estimator{ - kinematics, frc::Rotation2d{}, frc::MecanumDriveWheelPositions{}, - frc::Pose2d{}, {1.0, 1.0, 1.0}, {1.0, 1.0, 1.0}}; + wpi::math::MecanumDriveKinematics kinematics{ + wpi::math::Translation2d{1_m, 1_m}, wpi::math::Translation2d{1_m, -1_m}, + wpi::math::Translation2d{-1_m, -1_m}, wpi::math::Translation2d{-1_m, 1_m}}; + wpi::math::MecanumDrivePoseEstimator estimator{ + kinematics, wpi::math::Rotation2d{}, wpi::math::MecanumDriveWheelPositions{}, + wpi::math::Pose2d{}, {1.0, 1.0, 1.0}, {1.0, 1.0, 1.0}}; // Returns empty when null EXPECT_EQ(std::nullopt, estimator.SampleAt(1_s)); @@ -314,64 +314,64 @@ TEST(MecanumDrivePoseEstimatorTest, TestSampleAt) { // Add a tiny tolerance for the upper bound because of floating point rounding // error for (double time = 1; time <= 2 + 1e-9; time += 0.02) { - frc::MecanumDriveWheelPositions wheelPositions{ - units::meter_t{time}, units::meter_t{time}, units::meter_t{time}, - units::meter_t{time}}; - estimator.UpdateWithTime(units::second_t{time}, frc::Rotation2d{}, + wpi::math::MecanumDriveWheelPositions wheelPositions{ + wpi::units::meter_t{time}, wpi::units::meter_t{time}, wpi::units::meter_t{time}, + wpi::units::meter_t{time}}; + estimator.UpdateWithTime(wpi::units::second_t{time}, wpi::math::Rotation2d{}, wheelPositions); } // Sample at an added time - EXPECT_EQ(std::optional(frc::Pose2d{1.02_m, 0_m, frc::Rotation2d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose2d{1.02_m, 0_m, wpi::math::Rotation2d{}}), estimator.SampleAt(1.02_s)); // Sample between updates (test interpolation) - EXPECT_EQ(std::optional(frc::Pose2d{1.01_m, 0_m, frc::Rotation2d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose2d{1.01_m, 0_m, wpi::math::Rotation2d{}}), estimator.SampleAt(1.01_s)); // Sampling before the oldest value returns the oldest value - EXPECT_EQ(std::optional(frc::Pose2d{1_m, 0_m, frc::Rotation2d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose2d{1_m, 0_m, wpi::math::Rotation2d{}}), estimator.SampleAt(0.5_s)); // Sampling after the newest value returns the newest value - EXPECT_EQ(std::optional(frc::Pose2d{2_m, 0_m, frc::Rotation2d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose2d{2_m, 0_m, wpi::math::Rotation2d{}}), estimator.SampleAt(2.5_s)); // Add a vision measurement after the odometry measurements (while keeping all // of the old odometry measurements) - estimator.AddVisionMeasurement(frc::Pose2d{2_m, 0_m, frc::Rotation2d{1_rad}}, + estimator.AddVisionMeasurement(wpi::math::Pose2d{2_m, 0_m, wpi::math::Rotation2d{1_rad}}, 2.2_s); // Make sure nothing changed (except the newest value) - EXPECT_EQ(std::optional(frc::Pose2d{1.02_m, 0_m, frc::Rotation2d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose2d{1.02_m, 0_m, wpi::math::Rotation2d{}}), estimator.SampleAt(1.02_s)); - EXPECT_EQ(std::optional(frc::Pose2d{1.01_m, 0_m, frc::Rotation2d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose2d{1.01_m, 0_m, wpi::math::Rotation2d{}}), estimator.SampleAt(1.01_s)); - EXPECT_EQ(std::optional(frc::Pose2d{1_m, 0_m, frc::Rotation2d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose2d{1_m, 0_m, wpi::math::Rotation2d{}}), estimator.SampleAt(0.5_s)); // Add a vision measurement before the odometry measurements that's still in // the buffer - estimator.AddVisionMeasurement(frc::Pose2d{1_m, 0.2_m, frc::Rotation2d{}}, + estimator.AddVisionMeasurement(wpi::math::Pose2d{1_m, 0.2_m, wpi::math::Rotation2d{}}, 0.9_s); // Everything should be the same except Y is 0.1 (halfway between 0 and 0.2) - EXPECT_EQ(std::optional(frc::Pose2d{1.02_m, 0.1_m, frc::Rotation2d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose2d{1.02_m, 0.1_m, wpi::math::Rotation2d{}}), estimator.SampleAt(1.02_s)); - EXPECT_EQ(std::optional(frc::Pose2d{1.01_m, 0.1_m, frc::Rotation2d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose2d{1.01_m, 0.1_m, wpi::math::Rotation2d{}}), estimator.SampleAt(1.01_s)); - EXPECT_EQ(std::optional(frc::Pose2d{1_m, 0.1_m, frc::Rotation2d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose2d{1_m, 0.1_m, wpi::math::Rotation2d{}}), estimator.SampleAt(0.5_s)); - EXPECT_EQ(std::optional(frc::Pose2d{2_m, 0.1_m, frc::Rotation2d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose2d{2_m, 0.1_m, wpi::math::Rotation2d{}}), estimator.SampleAt(2.5_s)); } TEST(MecanumDrivePoseEstimatorTest, TestReset) { - frc::MecanumDriveKinematics kinematics{ - frc::Translation2d{1_m, 1_m}, frc::Translation2d{1_m, -1_m}, - frc::Translation2d{-1_m, -1_m}, frc::Translation2d{-1_m, 1_m}}; - frc::MecanumDrivePoseEstimator estimator{ + wpi::math::MecanumDriveKinematics kinematics{ + wpi::math::Translation2d{1_m, 1_m}, wpi::math::Translation2d{1_m, -1_m}, + wpi::math::Translation2d{-1_m, -1_m}, wpi::math::Translation2d{-1_m, 1_m}}; + wpi::math::MecanumDrivePoseEstimator estimator{ kinematics, - frc::Rotation2d{}, - frc::MecanumDriveWheelPositions{}, - frc::Pose2d{-1_m, -1_m, frc::Rotation2d{1_rad}}, + wpi::math::Rotation2d{}, + wpi::math::MecanumDriveWheelPositions{}, + wpi::math::Pose2d{-1_m, -1_m, wpi::math::Rotation2d{1_rad}}, {1.0, 1.0, 1.0}, {1.0, 1.0, 1.0}}; @@ -382,8 +382,8 @@ TEST(MecanumDrivePoseEstimatorTest, TestReset) { 1, estimator.GetEstimatedPosition().Rotation().Radians().value()); // Test reset position - estimator.ResetPosition(frc::Rotation2d{}, {1_m, 1_m, 1_m, 1_m}, - frc::Pose2d{1_m, 0_m, frc::Rotation2d{}}); + estimator.ResetPosition(wpi::math::Rotation2d{}, {1_m, 1_m, 1_m, 1_m}, + wpi::math::Pose2d{1_m, 0_m, wpi::math::Rotation2d{}}); EXPECT_DOUBLE_EQ(1, estimator.GetEstimatedPosition().X().value()); EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Y().value()); @@ -391,7 +391,7 @@ TEST(MecanumDrivePoseEstimatorTest, TestReset) { 0, estimator.GetEstimatedPosition().Rotation().Radians().value()); // Test orientation and wheel positions - estimator.Update(frc::Rotation2d{}, {2_m, 2_m, 2_m, 2_m}); + estimator.Update(wpi::math::Rotation2d{}, {2_m, 2_m, 2_m, 2_m}); EXPECT_DOUBLE_EQ(2, estimator.GetEstimatedPosition().X().value()); EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Y().value()); @@ -399,7 +399,7 @@ TEST(MecanumDrivePoseEstimatorTest, TestReset) { 0, estimator.GetEstimatedPosition().Rotation().Radians().value()); // Test reset rotation - estimator.ResetRotation(frc::Rotation2d{90_deg}); + estimator.ResetRotation(wpi::math::Rotation2d{90_deg}); EXPECT_DOUBLE_EQ(2, estimator.GetEstimatedPosition().X().value()); EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Y().value()); @@ -408,7 +408,7 @@ TEST(MecanumDrivePoseEstimatorTest, TestReset) { estimator.GetEstimatedPosition().Rotation().Radians().value()); // Test orientation - estimator.Update(frc::Rotation2d{}, {3_m, 3_m, 3_m, 3_m}); + estimator.Update(wpi::math::Rotation2d{}, {3_m, 3_m, 3_m, 3_m}); EXPECT_DOUBLE_EQ(2, estimator.GetEstimatedPosition().X().value()); EXPECT_DOUBLE_EQ(1, estimator.GetEstimatedPosition().Y().value()); @@ -417,7 +417,7 @@ TEST(MecanumDrivePoseEstimatorTest, TestReset) { estimator.GetEstimatedPosition().Rotation().Radians().value()); // Test reset translation - estimator.ResetTranslation(frc::Translation2d{-1_m, -1_m}); + estimator.ResetTranslation(wpi::math::Translation2d{-1_m, -1_m}); EXPECT_DOUBLE_EQ(-1, estimator.GetEstimatedPosition().X().value()); EXPECT_DOUBLE_EQ(-1, estimator.GetEstimatedPosition().Y().value()); @@ -426,7 +426,7 @@ TEST(MecanumDrivePoseEstimatorTest, TestReset) { estimator.GetEstimatedPosition().Rotation().Radians().value()); // Test reset pose - estimator.ResetPose(frc::Pose2d{}); + estimator.ResetPose(wpi::math::Pose2d{}); EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().X().value()); EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Y().value()); diff --git a/wpimath/src/test/native/cpp/estimator/MerweScaledSigmaPointsTest.cpp b/wpimath/src/test/native/cpp/estimator/MerweScaledSigmaPointsTest.cpp index ec9b1d551c..ef3ed99e6e 100644 --- a/wpimath/src/test/native/cpp/estimator/MerweScaledSigmaPointsTest.cpp +++ b/wpimath/src/test/native/cpp/estimator/MerweScaledSigmaPointsTest.cpp @@ -7,24 +7,24 @@ #include "wpi/math/estimator/MerweScaledSigmaPoints.hpp" TEST(MerweScaledSigmaPointsTest, ZeroMean) { - frc::MerweScaledSigmaPoints<2> sigmaPoints; + wpi::math::MerweScaledSigmaPoints<2> sigmaPoints; auto points = sigmaPoints.SquareRootSigmaPoints( - frc::Vectord<2>{0.0, 0.0}, frc::Matrixd<2, 2>{{1.0, 0.0}, {0.0, 1.0}}); + wpi::math::Vectord<2>{0.0, 0.0}, wpi::math::Matrixd<2, 2>{{1.0, 0.0}, {0.0, 1.0}}); EXPECT_TRUE( - (points - frc::Matrixd<2, 5>{{0.0, 0.00173205, 0.0, -0.00173205, 0.0}, + (points - wpi::math::Matrixd<2, 5>{{0.0, 0.00173205, 0.0, -0.00173205, 0.0}, {0.0, 0.0, 0.00173205, 0.0, -0.00173205}}) .norm() < 1e-3); } TEST(MerweScaledSigmaPointsTest, NonzeroMean) { - frc::MerweScaledSigmaPoints<2> sigmaPoints; + wpi::math::MerweScaledSigmaPoints<2> sigmaPoints; auto points = sigmaPoints.SquareRootSigmaPoints( - frc::Vectord<2>{1.0, 2.0}, - frc::Matrixd<2, 2>{{1.0, 0.0}, {0.0, std::sqrt(10.0)}}); + wpi::math::Vectord<2>{1.0, 2.0}, + wpi::math::Matrixd<2, 2>{{1.0, 0.0}, {0.0, std::sqrt(10.0)}}); EXPECT_TRUE( - (points - frc::Matrixd<2, 5>{{1.0, 1.00173205, 1.0, 0.998268, 1.0}, + (points - wpi::math::Matrixd<2, 5>{{1.0, 1.00173205, 1.0, 0.998268, 1.0}, {2.0, 2.0, 2.00548, 2.0, 1.99452}}) .norm() < 1e-3); } diff --git a/wpimath/src/test/native/cpp/estimator/MerweUKFTest.cpp b/wpimath/src/test/native/cpp/estimator/MerweUKFTest.cpp index 1467163f64..7c8239ade0 100644 --- a/wpimath/src/test/native/cpp/estimator/MerweUKFTest.cpp +++ b/wpimath/src/test/native/cpp/estimator/MerweUKFTest.cpp @@ -25,9 +25,9 @@ namespace { // First test system, differential drive -frc::Vectord<5> DriveDynamics(const frc::Vectord<5>& x, - const frc::Vectord<2>& u) { - auto motors = frc::DCMotor::CIM(2); +wpi::math::Vectord<5> DriveDynamics(const wpi::math::Vectord<5>& x, + const wpi::math::Vectord<2>& u) { + auto motors = wpi::math::DCMotor::CIM(2); // constexpr double Glow = 15.32; // Low gear ratio constexpr double Ghigh = 7.08; // High gear ratio @@ -37,18 +37,18 @@ frc::Vectord<5> DriveDynamics(const frc::Vectord<5>& x, constexpr auto J = 5.6_kg_sq_m; // Robot moment of inertia auto C1 = -std::pow(Ghigh, 2) * motors.Kt / - (motors.Kv * motors.R * units::math::pow<2>(r)); + (motors.Kv * motors.R * wpi::units::math::pow<2>(r)); auto C2 = Ghigh * motors.Kt / (motors.R * r); - auto k1 = (1 / m + units::math::pow<2>(rb) / J); - auto k2 = (1 / m - units::math::pow<2>(rb) / J); + auto k1 = (1 / m + wpi::units::math::pow<2>(rb) / J); + auto k2 = (1 / m - wpi::units::math::pow<2>(rb) / J); - units::meters_per_second_t vl{x(3)}; - units::meters_per_second_t vr{x(4)}; - units::volt_t Vl{u(0)}; - units::volt_t Vr{u(1)}; + wpi::units::meters_per_second_t vl{x(3)}; + wpi::units::meters_per_second_t vr{x(4)}; + wpi::units::volt_t Vl{u(0)}; + wpi::units::volt_t Vr{u(1)}; auto v = 0.5 * (vl + vr); - return frc::Vectord<5>{ + return wpi::math::Vectord<5>{ v.value() * std::cos(x(2)), v.value() * std::sin(x(2)), ((vr - vl) / (2.0 * rb)).value(), k1.value() * ((C1 * vl).value() + (C2 * Vl).value()) + @@ -57,70 +57,70 @@ frc::Vectord<5> DriveDynamics(const frc::Vectord<5>& x, k1.value() * ((C1 * vr).value() + (C2 * Vr).value())}; } -frc::Vectord<3> DriveLocalMeasurementModel( - const frc::Vectord<5>& x, [[maybe_unused]] const frc::Vectord<2>& u) { - return frc::Vectord<3>{x(2), x(3), x(4)}; +wpi::math::Vectord<3> DriveLocalMeasurementModel( + const wpi::math::Vectord<5>& x, [[maybe_unused]] const wpi::math::Vectord<2>& u) { + return wpi::math::Vectord<3>{x(2), x(3), x(4)}; } -frc::Vectord<5> DriveGlobalMeasurementModel( - const frc::Vectord<5>& x, [[maybe_unused]] const frc::Vectord<2>& u) { - return frc::Vectord<5>{x(0), x(1), x(2), x(3), x(4)}; +wpi::math::Vectord<5> DriveGlobalMeasurementModel( + const wpi::math::Vectord<5>& x, [[maybe_unused]] const wpi::math::Vectord<2>& u) { + return wpi::math::Vectord<5>{x(0), x(1), x(2), x(3), x(4)}; } TEST(MerweUKFTest, DriveInit) { - constexpr units::second_t dt = 5_ms; + constexpr wpi::units::second_t dt = 5_ms; - frc::MerweUKF<5, 2, 3> observer{DriveDynamics, + wpi::math::MerweUKF<5, 2, 3> observer{DriveDynamics, DriveLocalMeasurementModel, {0.5, 0.5, 10.0, 1.0, 1.0}, {0.0001, 0.01, 0.01}, - frc::AngleMean<5, 2 * 5 + 1>(2), - frc::AngleMean<3, 2 * 5 + 1>(0), - frc::AngleResidual<5>(2), - frc::AngleResidual<3>(0), - frc::AngleAdd<5>(2), + wpi::math::AngleMean<5, 2 * 5 + 1>(2), + wpi::math::AngleMean<3, 2 * 5 + 1>(0), + wpi::math::AngleResidual<5>(2), + wpi::math::AngleResidual<3>(0), + wpi::math::AngleAdd<5>(2), dt}; - frc::Vectord<2> u{12.0, 12.0}; + wpi::math::Vectord<2> u{12.0, 12.0}; observer.Predict(u, dt); auto localY = DriveLocalMeasurementModel(observer.Xhat(), u); observer.Correct(u, localY); auto globalY = DriveGlobalMeasurementModel(observer.Xhat(), u); - auto R = frc::MakeCovMatrix(0.01, 0.01, 0.0001, 0.01, 0.01); + auto R = wpi::math::MakeCovMatrix(0.01, 0.01, 0.0001, 0.01, 0.01); observer.Correct<5>(u, globalY, DriveGlobalMeasurementModel, R, - frc::AngleMean<5, 2 * 5 + 1>(2), frc::AngleResidual<5>(2), - frc::AngleResidual<5>(2), frc::AngleAdd<5>(2)); + wpi::math::AngleMean<5, 2 * 5 + 1>(2), wpi::math::AngleResidual<5>(2), + wpi::math::AngleResidual<5>(2), wpi::math::AngleAdd<5>(2)); } TEST(MerweUKFTest, DriveConvergence) { - constexpr units::second_t dt = 5_ms; + constexpr wpi::units::second_t dt = 5_ms; constexpr auto rb = 0.8382_m / 2.0; // Robot radius - frc::MerweUKF<5, 2, 3> observer{DriveDynamics, + wpi::math::MerweUKF<5, 2, 3> observer{DriveDynamics, DriveLocalMeasurementModel, {0.5, 0.5, 10.0, 1.0, 1.0}, {0.0001, 0.5, 0.5}, - frc::AngleMean<5, 2 * 5 + 1>(2), - frc::AngleMean<3, 2 * 5 + 1>(0), - frc::AngleResidual<5>(2), - frc::AngleResidual<3>(0), - frc::AngleAdd<5>(2), + wpi::math::AngleMean<5, 2 * 5 + 1>(2), + wpi::math::AngleMean<3, 2 * 5 + 1>(0), + wpi::math::AngleResidual<5>(2), + wpi::math::AngleResidual<3>(0), + wpi::math::AngleAdd<5>(2), dt}; auto waypoints = - std::vector{frc::Pose2d{2.75_m, 22.521_m, 0_rad}, - frc::Pose2d{24.73_m, 19.68_m, 5.846_rad}}; - auto trajectory = frc::TrajectoryGenerator::GenerateTrajectory( + std::vector{wpi::math::Pose2d{2.75_m, 22.521_m, 0_rad}, + wpi::math::Pose2d{24.73_m, 19.68_m, 5.846_rad}}; + auto trajectory = wpi::math::TrajectoryGenerator::GenerateTrajectory( waypoints, {8.8_mps, 0.1_mps_sq}); - frc::Vectord<5> r = frc::Vectord<5>::Zero(); - frc::Vectord<2> u = frc::Vectord<2>::Zero(); + wpi::math::Vectord<5> r = wpi::math::Vectord<5>::Zero(); + wpi::math::Vectord<2> u = wpi::math::Vectord<2>::Zero(); - auto B = frc::NumericalJacobianU<5, 5, 2>( - DriveDynamics, frc::Vectord<5>::Zero(), frc::Vectord<2>::Zero()); + auto B = wpi::math::NumericalJacobianU<5, 5, 2>( + DriveDynamics, wpi::math::Vectord<5>::Zero(), wpi::math::Vectord<2>::Zero()); - observer.SetXhat(frc::Vectord<5>{ + observer.SetXhat(wpi::math::Vectord<5>{ trajectory.InitialPose().Translation().X().value(), trajectory.InitialPose().Translation().Y().value(), trajectory.InitialPose().Rotation().Radians().value(), 0.0, 0.0}); @@ -130,36 +130,36 @@ TEST(MerweUKFTest, DriveConvergence) { auto totalTime = trajectory.TotalTime(); for (size_t i = 0; i < (totalTime / dt).value(); ++i) { auto ref = trajectory.Sample(dt * i); - units::meters_per_second_t vl = + wpi::units::meters_per_second_t vl = ref.velocity * (1 - (ref.curvature * rb).value()); - units::meters_per_second_t vr = + wpi::units::meters_per_second_t vr = ref.velocity * (1 + (ref.curvature * rb).value()); - frc::Vectord<5> nextR{ + wpi::math::Vectord<5> nextR{ ref.pose.Translation().X().value(), ref.pose.Translation().Y().value(), ref.pose.Rotation().Radians().value(), vl.value(), vr.value()}; - auto localY = DriveLocalMeasurementModel(trueXhat, frc::Vectord<2>::Zero()); - observer.Correct(u, localY + frc::MakeWhiteNoiseVector(0.0001, 0.5, 0.5)); + auto localY = DriveLocalMeasurementModel(trueXhat, wpi::math::Vectord<2>::Zero()); + observer.Correct(u, localY + wpi::math::MakeWhiteNoiseVector(0.0001, 0.5, 0.5)); - frc::Vectord<5> rdot = (nextR - r) / dt.value(); + wpi::math::Vectord<5> rdot = (nextR - r) / dt.value(); u = B.householderQr().solve(rdot - - DriveDynamics(r, frc::Vectord<2>::Zero())); + DriveDynamics(r, wpi::math::Vectord<2>::Zero())); observer.Predict(u, dt); r = nextR; - trueXhat = frc::RK4(DriveDynamics, trueXhat, u, dt); + trueXhat = wpi::math::RK4(DriveDynamics, trueXhat, u, dt); } auto localY = DriveLocalMeasurementModel(trueXhat, u); observer.Correct(u, localY); auto globalY = DriveGlobalMeasurementModel(trueXhat, u); - auto R = frc::MakeCovMatrix(0.01, 0.01, 0.0001, 0.5, 0.5); + auto R = wpi::math::MakeCovMatrix(0.01, 0.01, 0.0001, 0.5, 0.5); observer.Correct<5>(u, globalY, DriveGlobalMeasurementModel, R, - frc::AngleMean<5, 2 * 5 + 1>(2), frc::AngleResidual<5>(2), - frc::AngleResidual<5>(2), frc::AngleAdd<5>(2) + wpi::math::AngleMean<5, 2 * 5 + 1>(2), wpi::math::AngleResidual<5>(2), + wpi::math::AngleResidual<5>(2), wpi::math::AngleAdd<5>(2) ); @@ -175,26 +175,26 @@ TEST(MerweUKFTest, DriveConvergence) { } TEST(MerweUKFTest, LinearUKF) { - constexpr units::second_t dt = 20_ms; - auto plant = frc::LinearSystemId::IdentifyVelocitySystem( + constexpr wpi::units::second_t dt = 20_ms; + auto plant = wpi::math::LinearSystemId::IdentifyVelocitySystem( 0.02_V / 1_mps, 0.006_V / 1_mps_sq); - frc::MerweUKF<1, 1, 1> observer{ - [&](const frc::Vectord<1>& x, const frc::Vectord<1>& u) { + wpi::math::MerweUKF<1, 1, 1> observer{ + [&](const wpi::math::Vectord<1>& x, const wpi::math::Vectord<1>& u) { return plant.A() * x + plant.B() * u; }, - [&](const frc::Vectord<1>& x, const frc::Vectord<1>& u) { + [&](const wpi::math::Vectord<1>& x, const wpi::math::Vectord<1>& u) { return plant.CalculateY(x, u); }, {0.05}, {1.0}, dt}; - frc::Matrixd<1, 1> discA; - frc::Matrixd<1, 1> discB; - frc::DiscretizeAB<1, 1>(plant.A(), plant.B(), dt, &discA, &discB); + wpi::math::Matrixd<1, 1> discA; + wpi::math::Matrixd<1, 1> discB; + wpi::math::DiscretizeAB<1, 1>(plant.A(), plant.B(), dt, &discA, &discB); - frc::Vectord<1> ref{100.0}; - frc::Vectord<1> u{0.0}; + wpi::math::Vectord<1> ref{100.0}; + wpi::math::Vectord<1> u{0.0}; for (int i = 0; i < 2.0 / dt.value(); ++i) { observer.Predict(u, dt); @@ -206,24 +206,24 @@ TEST(MerweUKFTest, LinearUKF) { } TEST(MerweUKFTest, RoundTripP) { - constexpr units::second_t dt = 5_ms; + constexpr wpi::units::second_t dt = 5_ms; - frc::MerweUKF<2, 2, 2> observer{ - [](const frc::Vectord<2>& x, const frc::Vectord<2>& u) { return x; }, - [](const frc::Vectord<2>& x, const frc::Vectord<2>& u) { return x; }, + wpi::math::MerweUKF<2, 2, 2> observer{ + [](const wpi::math::Vectord<2>& x, const wpi::math::Vectord<2>& u) { return x; }, + [](const wpi::math::Vectord<2>& x, const wpi::math::Vectord<2>& u) { return x; }, {0.0, 0.0}, {0.0, 0.0}, dt}; - frc::Matrixd<2, 2> P({{2, 1}, {1, 2}}); + wpi::math::Matrixd<2, 2> P({{2, 1}, {1, 2}}); observer.SetP(P); ASSERT_TRUE(observer.P().isApprox(P)); } // Second system, single motor feedforward estimator -frc::Vectord<4> MotorDynamics(const frc::Vectord<4>& x, - const frc::Vectord<1>& u) { +wpi::math::Vectord<4> MotorDynamics(const wpi::math::Vectord<4>& x, + const wpi::math::Vectord<1>& u) { double v = x(1); double kV = x(2); double kA = x(3); @@ -231,11 +231,11 @@ frc::Vectord<4> MotorDynamics(const frc::Vectord<4>& x, double V = u(0); double a = -kV / kA * v + 1.0 / kA * V; - return frc::Vectord<4>{v, a, 0.0, 0.0}; + return wpi::math::Vectord<4>{v, a, 0.0, 0.0}; } -frc::Vectord<3> MotorMeasurementModel(const frc::Vectord<4>& x, - const frc::Vectord<1>& u) { +wpi::math::Vectord<3> MotorMeasurementModel(const wpi::math::Vectord<4>& x, + const wpi::math::Vectord<1>& u) { double p = x(0); double v = x(1); double kV = x(2); @@ -244,11 +244,11 @@ frc::Vectord<3> MotorMeasurementModel(const frc::Vectord<4>& x, double V = u(0); double a = -kV / kA * v + 1.0 / kA * V; - return frc::Vectord<3>{p, v, a}; + return wpi::math::Vectord<3>{p, v, a}; } -frc::Vectord<1> MotorControlInput(double t) { - return frc::Vectord<1>{ +wpi::math::Vectord<1> MotorControlInput(double t) { + return wpi::math::Vectord<1>{ std::clamp(8 * std::sin(std::numbers::pi * std::sqrt(2.0) * t) + 6 * std::sin(std::numbers::pi * std::sqrt(3.0) * t) + 4 * std::sin(std::numbers::pi * std::sqrt(5.0) * t), @@ -256,7 +256,7 @@ frc::Vectord<1> MotorControlInput(double t) { } TEST(MerweUKFTest, MotorConvergence) { - constexpr units::second_t dt = 10_ms; + constexpr wpi::units::second_t dt = 10_ms; constexpr int steps = 500; constexpr double true_kV = 3; constexpr double true_kA = 0.2; @@ -265,36 +265,36 @@ TEST(MerweUKFTest, MotorConvergence) { constexpr double vel_stddev = 0.1; constexpr double accel_stddev = 0.1; - std::vector> states(steps + 1); - std::vector> inputs(steps); - std::vector> measurements(steps); - states[0] = frc::Vectord<4>{{0.0}, {0.0}, {true_kV}, {true_kA}}; + std::vector> states(steps + 1); + std::vector> inputs(steps); + std::vector> measurements(steps); + states[0] = wpi::math::Vectord<4>{{0.0}, {0.0}, {true_kV}, {true_kA}}; - constexpr frc::Matrixd<4, 4> A{{0.0, 1.0, 0.0, 0.0}, + constexpr wpi::math::Matrixd<4, 4> A{{0.0, 1.0, 0.0, 0.0}, {0.0, -true_kV / true_kA, 0.0, 0.0}, {0.0, 0.0, 0.0, 0.0}, {0.0, 0.0, 0.0, 0.0}}; - constexpr frc::Matrixd<4, 1> B{{0.0}, {1.0 / true_kA}, {0.0}, {0.0}}; + constexpr wpi::math::Matrixd<4, 1> B{{0.0}, {1.0 / true_kA}, {0.0}, {0.0}}; - frc::Matrixd<4, 4> discA; - frc::Matrixd<4, 1> discB; - frc::DiscretizeAB(A, B, dt, &discA, &discB); + wpi::math::Matrixd<4, 4> discA; + wpi::math::Matrixd<4, 1> discB; + wpi::math::DiscretizeAB(A, B, dt, &discA, &discB); for (int i = 0; i < steps; ++i) { inputs[i] = MotorControlInput(i * dt.value()); states[i + 1] = discA * states[i] + discB * inputs[i]; measurements[i] = MotorMeasurementModel(states[i + 1], inputs[i]) + - frc::MakeWhiteNoiseVector(pos_stddev, vel_stddev, accel_stddev); + wpi::math::MakeWhiteNoiseVector(pos_stddev, vel_stddev, accel_stddev); } - frc::Vectord<4> P0{0.001, 0.001, 10, 10}; + wpi::math::Vectord<4> P0{0.001, 0.001, 10, 10}; - frc::MerweUKF<4, 1, 3> observer{ - MotorDynamics, MotorMeasurementModel, wpi::array{0.1, 1.0, 1e-10, 1e-10}, - wpi::array{pos_stddev, vel_stddev, accel_stddev}, dt}; + wpi::math::MerweUKF<4, 1, 3> observer{ + MotorDynamics, MotorMeasurementModel, wpi::util::array{0.1, 1.0, 1e-10, 1e-10}, + wpi::util::array{pos_stddev, vel_stddev, accel_stddev}, dt}; - observer.SetXhat(frc::Vectord<4>{0.0, 0.0, 2.0, 2.0}); + observer.SetXhat(wpi::math::Vectord<4>{0.0, 0.0, 2.0, 2.0}); observer.SetP(P0.asDiagonal()); for (int i = 0; i < steps; ++i) { diff --git a/wpimath/src/test/native/cpp/estimator/S3SigmaPointsTest.cpp b/wpimath/src/test/native/cpp/estimator/S3SigmaPointsTest.cpp index f8857a70ef..f2cb0380f7 100644 --- a/wpimath/src/test/native/cpp/estimator/S3SigmaPointsTest.cpp +++ b/wpimath/src/test/native/cpp/estimator/S3SigmaPointsTest.cpp @@ -11,9 +11,9 @@ TEST(S3SigmaPointsTest, Simplex) { constexpr double beta = 2; constexpr size_t N = 2; - frc::S3SigmaPoints sigmaPoints{alpha, beta}; + wpi::math::S3SigmaPoints sigmaPoints{alpha, beta}; auto points = sigmaPoints.SquareRootSigmaPoints( - frc::Vectord::Zero(), frc::Matrixd::Identity()); + wpi::math::Vectord::Zero(), wpi::math::Matrixd::Identity()); auto v1 = points.template block<2, 1>(0, 1); auto v2 = points.template block<2, 1>(0, 2); @@ -27,24 +27,24 @@ TEST(S3SigmaPointsTest, Simplex) { } TEST(S3SigmaPointsTest, ZeroMean) { - frc::S3SigmaPoints<2> sigmaPoints; + wpi::math::S3SigmaPoints<2> sigmaPoints; auto points = sigmaPoints.SquareRootSigmaPoints( - frc::Vectord<2>{0.0, 0.0}, frc::Matrixd<2, 2>{{1.0, 0.0}, {0.0, 1.0}}); + wpi::math::Vectord<2>{0.0, 0.0}, wpi::math::Matrixd<2, 2>{{1.0, 0.0}, {0.0, 1.0}}); EXPECT_TRUE( - (points - frc::Matrixd<2, 4>{{0.0, -0.00122474, 0.00122474, 0.0}, + (points - wpi::math::Matrixd<2, 4>{{0.0, -0.00122474, 0.00122474, 0.0}, {0.0, -0.00070711, -0.00070711, 0.00141421}}) .norm() < 1e-7); } TEST(S3SigmaPointsTest, NonzeroMean) { - frc::S3SigmaPoints<2> sigmaPoints; + wpi::math::S3SigmaPoints<2> sigmaPoints; auto points = sigmaPoints.SquareRootSigmaPoints( - frc::Vectord<2>{1.0, 2.0}, - frc::Matrixd<2, 2>{{1.0, 0.0}, {0.0, std::sqrt(10.0)}}); + wpi::math::Vectord<2>{1.0, 2.0}, + wpi::math::Matrixd<2, 2>{{1.0, 0.0}, {0.0, std::sqrt(10.0)}}); EXPECT_TRUE( - (points - frc::Matrixd<2, 4>{{1.0, 0.99877526, 1.00122474, 1.0}, + (points - wpi::math::Matrixd<2, 4>{{1.0, 0.99877526, 1.00122474, 1.0}, {2.0, 1.99776393, 1.99776393, 2.00447214}}) .norm() < 1e-7); } diff --git a/wpimath/src/test/native/cpp/estimator/S3UKFTest.cpp b/wpimath/src/test/native/cpp/estimator/S3UKFTest.cpp index 018755b6a3..226b4d366d 100644 --- a/wpimath/src/test/native/cpp/estimator/S3UKFTest.cpp +++ b/wpimath/src/test/native/cpp/estimator/S3UKFTest.cpp @@ -25,9 +25,9 @@ namespace { // First test system, differential drive -frc::Vectord<5> DriveDynamics(const frc::Vectord<5>& x, - const frc::Vectord<2>& u) { - auto motors = frc::DCMotor::CIM(2); +wpi::math::Vectord<5> DriveDynamics(const wpi::math::Vectord<5>& x, + const wpi::math::Vectord<2>& u) { + auto motors = wpi::math::DCMotor::CIM(2); // constexpr double Glow = 15.32; // Low gear ratio constexpr double Ghigh = 7.08; // High gear ratio @@ -37,18 +37,18 @@ frc::Vectord<5> DriveDynamics(const frc::Vectord<5>& x, constexpr auto J = 5.6_kg_sq_m; // Robot moment of inertia auto C1 = -std::pow(Ghigh, 2) * motors.Kt / - (motors.Kv * motors.R * units::math::pow<2>(r)); + (motors.Kv * motors.R * wpi::units::math::pow<2>(r)); auto C2 = Ghigh * motors.Kt / (motors.R * r); - auto k1 = (1 / m + units::math::pow<2>(rb) / J); - auto k2 = (1 / m - units::math::pow<2>(rb) / J); + auto k1 = (1 / m + wpi::units::math::pow<2>(rb) / J); + auto k2 = (1 / m - wpi::units::math::pow<2>(rb) / J); - units::meters_per_second_t vl{x(3)}; - units::meters_per_second_t vr{x(4)}; - units::volt_t Vl{u(0)}; - units::volt_t Vr{u(1)}; + wpi::units::meters_per_second_t vl{x(3)}; + wpi::units::meters_per_second_t vr{x(4)}; + wpi::units::volt_t Vl{u(0)}; + wpi::units::volt_t Vr{u(1)}; auto v = 0.5 * (vl + vr); - return frc::Vectord<5>{ + return wpi::math::Vectord<5>{ v.value() * std::cos(x(2)), v.value() * std::sin(x(2)), ((vr - vl) / (2.0 * rb)).value(), k1.value() * ((C1 * vl).value() + (C2 * Vl).value()) + @@ -57,70 +57,70 @@ frc::Vectord<5> DriveDynamics(const frc::Vectord<5>& x, k1.value() * ((C1 * vr).value() + (C2 * Vr).value())}; } -frc::Vectord<3> DriveLocalMeasurementModel( - const frc::Vectord<5>& x, [[maybe_unused]] const frc::Vectord<2>& u) { - return frc::Vectord<3>{x(2), x(3), x(4)}; +wpi::math::Vectord<3> DriveLocalMeasurementModel( + const wpi::math::Vectord<5>& x, [[maybe_unused]] const wpi::math::Vectord<2>& u) { + return wpi::math::Vectord<3>{x(2), x(3), x(4)}; } -frc::Vectord<5> DriveGlobalMeasurementModel( - const frc::Vectord<5>& x, [[maybe_unused]] const frc::Vectord<2>& u) { - return frc::Vectord<5>{x(0), x(1), x(2), x(3), x(4)}; +wpi::math::Vectord<5> DriveGlobalMeasurementModel( + const wpi::math::Vectord<5>& x, [[maybe_unused]] const wpi::math::Vectord<2>& u) { + return wpi::math::Vectord<5>{x(0), x(1), x(2), x(3), x(4)}; } TEST(S3UKFTest, DriveInit) { constexpr auto dt = 5_ms; - frc::S3UKF<5, 2, 3> observer{DriveDynamics, + wpi::math::S3UKF<5, 2, 3> observer{DriveDynamics, DriveLocalMeasurementModel, {0.5, 0.5, 10.0, 1.0, 1.0}, {0.0001, 0.01, 0.01}, - frc::AngleMean<5, 5 + 2>(2), - frc::AngleMean<3, 5 + 2>(0), - frc::AngleResidual<5>(2), - frc::AngleResidual<3>(0), - frc::AngleAdd<5>(2), + wpi::math::AngleMean<5, 5 + 2>(2), + wpi::math::AngleMean<3, 5 + 2>(0), + wpi::math::AngleResidual<5>(2), + wpi::math::AngleResidual<3>(0), + wpi::math::AngleAdd<5>(2), dt}; - frc::Vectord<2> u{12.0, 12.0}; + wpi::math::Vectord<2> u{12.0, 12.0}; observer.Predict(u, dt); auto localY = DriveLocalMeasurementModel(observer.Xhat(), u); observer.Correct(u, localY); auto globalY = DriveGlobalMeasurementModel(observer.Xhat(), u); - auto R = frc::MakeCovMatrix(0.01, 0.01, 0.0001, 0.01, 0.01); + auto R = wpi::math::MakeCovMatrix(0.01, 0.01, 0.0001, 0.01, 0.01); observer.Correct<5>(u, globalY, DriveGlobalMeasurementModel, R, - frc::AngleMean<5, 5 + 2>(2), frc::AngleResidual<5>(2), - frc::AngleResidual<5>(2), frc::AngleAdd<5>(2)); + wpi::math::AngleMean<5, 5 + 2>(2), wpi::math::AngleResidual<5>(2), + wpi::math::AngleResidual<5>(2), wpi::math::AngleAdd<5>(2)); } TEST(S3UKFTest, DriveConvergence) { constexpr auto dt = 5_ms; constexpr auto rb = 0.8382_m / 2.0; // Robot radius - frc::S3UKF<5, 2, 3> observer{DriveDynamics, + wpi::math::S3UKF<5, 2, 3> observer{DriveDynamics, DriveLocalMeasurementModel, {0.5, 0.5, 10.0, 1.0, 1.0}, {0.0001, 0.5, 0.5}, - frc::AngleMean<5, 5 + 2>(2), - frc::AngleMean<3, 5 + 2>(0), - frc::AngleResidual<5>(2), - frc::AngleResidual<3>(0), - frc::AngleAdd<5>(2), + wpi::math::AngleMean<5, 5 + 2>(2), + wpi::math::AngleMean<3, 5 + 2>(0), + wpi::math::AngleResidual<5>(2), + wpi::math::AngleResidual<3>(0), + wpi::math::AngleAdd<5>(2), dt}; auto waypoints = - std::vector{frc::Pose2d{2.75_m, 22.521_m, 0_rad}, - frc::Pose2d{24.73_m, 19.68_m, 5.846_rad}}; - auto trajectory = frc::TrajectoryGenerator::GenerateTrajectory( + std::vector{wpi::math::Pose2d{2.75_m, 22.521_m, 0_rad}, + wpi::math::Pose2d{24.73_m, 19.68_m, 5.846_rad}}; + auto trajectory = wpi::math::TrajectoryGenerator::GenerateTrajectory( waypoints, {8.8_mps, 0.1_mps_sq}); - frc::Vectord<5> r = frc::Vectord<5>::Zero(); - frc::Vectord<2> u = frc::Vectord<2>::Zero(); + wpi::math::Vectord<5> r = wpi::math::Vectord<5>::Zero(); + wpi::math::Vectord<2> u = wpi::math::Vectord<2>::Zero(); - auto B = frc::NumericalJacobianU<5, 5, 2>( - DriveDynamics, frc::Vectord<5>::Zero(), frc::Vectord<2>::Zero()); + auto B = wpi::math::NumericalJacobianU<5, 5, 2>( + DriveDynamics, wpi::math::Vectord<5>::Zero(), wpi::math::Vectord<2>::Zero()); - observer.SetXhat(frc::Vectord<5>{ + observer.SetXhat(wpi::math::Vectord<5>{ trajectory.InitialPose().Translation().X().value(), trajectory.InitialPose().Translation().Y().value(), trajectory.InitialPose().Rotation().Radians().value(), 0.0, 0.0}); @@ -130,36 +130,36 @@ TEST(S3UKFTest, DriveConvergence) { auto totalTime = trajectory.TotalTime(); for (size_t i = 0; i < (totalTime / dt).value(); ++i) { auto ref = trajectory.Sample(dt * i); - units::meters_per_second_t vl = + wpi::units::meters_per_second_t vl = ref.velocity * (1 - (ref.curvature * rb).value()); - units::meters_per_second_t vr = + wpi::units::meters_per_second_t vr = ref.velocity * (1 + (ref.curvature * rb).value()); - frc::Vectord<5> nextR{ + wpi::math::Vectord<5> nextR{ ref.pose.Translation().X().value(), ref.pose.Translation().Y().value(), ref.pose.Rotation().Radians().value(), vl.value(), vr.value()}; - auto localY = DriveLocalMeasurementModel(trueXhat, frc::Vectord<2>::Zero()); - observer.Correct(u, localY + frc::MakeWhiteNoiseVector(0.0001, 0.5, 0.5)); + auto localY = DriveLocalMeasurementModel(trueXhat, wpi::math::Vectord<2>::Zero()); + observer.Correct(u, localY + wpi::math::MakeWhiteNoiseVector(0.0001, 0.5, 0.5)); - frc::Vectord<5> rdot = (nextR - r) / dt.value(); + wpi::math::Vectord<5> rdot = (nextR - r) / dt.value(); u = B.householderQr().solve(rdot - - DriveDynamics(r, frc::Vectord<2>::Zero())); + DriveDynamics(r, wpi::math::Vectord<2>::Zero())); observer.Predict(u, dt); r = nextR; - trueXhat = frc::RK4(DriveDynamics, trueXhat, u, dt); + trueXhat = wpi::math::RK4(DriveDynamics, trueXhat, u, dt); } auto localY = DriveLocalMeasurementModel(trueXhat, u); observer.Correct(u, localY); auto globalY = DriveGlobalMeasurementModel(trueXhat, u); - auto R = frc::MakeCovMatrix(0.01, 0.01, 0.0001, 0.5, 0.5); + auto R = wpi::math::MakeCovMatrix(0.01, 0.01, 0.0001, 0.5, 0.5); observer.Correct<5>(u, globalY, DriveGlobalMeasurementModel, R, - frc::AngleMean<5, 5 + 2>(2), frc::AngleResidual<5>(2), - frc::AngleResidual<5>(2), frc::AngleAdd<5>(2) + wpi::math::AngleMean<5, 5 + 2>(2), wpi::math::AngleResidual<5>(2), + wpi::math::AngleResidual<5>(2), wpi::math::AngleAdd<5>(2) ); @@ -175,26 +175,26 @@ TEST(S3UKFTest, DriveConvergence) { } TEST(S3UKFTest, LinearUKF) { - constexpr units::second_t dt = 20_ms; - auto plant = frc::LinearSystemId::IdentifyVelocitySystem( + constexpr wpi::units::second_t dt = 20_ms; + auto plant = wpi::math::LinearSystemId::IdentifyVelocitySystem( 0.02_V / 1_mps, 0.006_V / 1_mps_sq); - frc::S3UKF<1, 1, 1> observer{ - [&](const frc::Vectord<1>& x, const frc::Vectord<1>& u) { + wpi::math::S3UKF<1, 1, 1> observer{ + [&](const wpi::math::Vectord<1>& x, const wpi::math::Vectord<1>& u) { return plant.A() * x + plant.B() * u; }, - [&](const frc::Vectord<1>& x, const frc::Vectord<1>& u) { + [&](const wpi::math::Vectord<1>& x, const wpi::math::Vectord<1>& u) { return plant.CalculateY(x, u); }, {0.05}, {1.0}, dt}; - frc::Matrixd<1, 1> discA; - frc::Matrixd<1, 1> discB; - frc::DiscretizeAB<1, 1>(plant.A(), plant.B(), dt, &discA, &discB); + wpi::math::Matrixd<1, 1> discA; + wpi::math::Matrixd<1, 1> discB; + wpi::math::DiscretizeAB<1, 1>(plant.A(), plant.B(), dt, &discA, &discB); - frc::Vectord<1> ref{100.0}; - frc::Vectord<1> u{0.0}; + wpi::math::Vectord<1> ref{100.0}; + wpi::math::Vectord<1> u{0.0}; for (int i = 0; i < 2.0 / dt.value(); ++i) { observer.Predict(u, dt); @@ -208,22 +208,22 @@ TEST(S3UKFTest, LinearUKF) { TEST(S3UKFTest, RoundTripP) { constexpr auto dt = 5_ms; - frc::S3UKF<2, 2, 2> observer{ - [](const frc::Vectord<2>& x, const frc::Vectord<2>& u) { return x; }, - [](const frc::Vectord<2>& x, const frc::Vectord<2>& u) { return x; }, + wpi::math::S3UKF<2, 2, 2> observer{ + [](const wpi::math::Vectord<2>& x, const wpi::math::Vectord<2>& u) { return x; }, + [](const wpi::math::Vectord<2>& x, const wpi::math::Vectord<2>& u) { return x; }, {0.0, 0.0}, {0.0, 0.0}, dt}; - frc::Matrixd<2, 2> P({{2, 1}, {1, 2}}); + wpi::math::Matrixd<2, 2> P({{2, 1}, {1, 2}}); observer.SetP(P); ASSERT_TRUE(observer.P().isApprox(P)); } // Second system, single motor feedforward estimator -frc::Vectord<4> MotorDynamics(const frc::Vectord<4>& x, - const frc::Vectord<1>& u) { +wpi::math::Vectord<4> MotorDynamics(const wpi::math::Vectord<4>& x, + const wpi::math::Vectord<1>& u) { double v = x(1); double kV = x(2); double kA = x(3); @@ -231,11 +231,11 @@ frc::Vectord<4> MotorDynamics(const frc::Vectord<4>& x, double V = u(0); double a = -kV / kA * v + 1.0 / kA * V; - return frc::Vectord<4>{v, a, 0.0, 0.0}; + return wpi::math::Vectord<4>{v, a, 0.0, 0.0}; } -frc::Vectord<3> MotorMeasurementModel(const frc::Vectord<4>& x, - const frc::Vectord<1>& u) { +wpi::math::Vectord<3> MotorMeasurementModel(const wpi::math::Vectord<4>& x, + const wpi::math::Vectord<1>& u) { double p = x(0); double v = x(1); double kV = x(2); @@ -244,11 +244,11 @@ frc::Vectord<3> MotorMeasurementModel(const frc::Vectord<4>& x, double V = u(0); double a = -kV / kA * v + 1.0 / kA * V; - return frc::Vectord<3>{p, v, a}; + return wpi::math::Vectord<3>{p, v, a}; } -frc::Vectord<1> MotorControlInput(double t) { - return frc::Vectord<1>{ +wpi::math::Vectord<1> MotorControlInput(double t) { + return wpi::math::Vectord<1>{ std::clamp(8 * std::sin(std::numbers::pi * std::sqrt(2.0) * t) + 6 * std::sin(std::numbers::pi * std::sqrt(3.0) * t) + 4 * std::sin(std::numbers::pi * std::sqrt(5.0) * t), @@ -256,7 +256,7 @@ frc::Vectord<1> MotorControlInput(double t) { } TEST(S3UKFTest, MotorConvergence) { - constexpr units::second_t dt = 10_ms; + constexpr wpi::units::second_t dt = 10_ms; constexpr int steps = 500; constexpr double true_kV = 3; constexpr double true_kA = 0.2; @@ -265,36 +265,36 @@ TEST(S3UKFTest, MotorConvergence) { constexpr double vel_stddev = 0.1; constexpr double accel_stddev = 0.1; - std::vector> states(steps + 1); - std::vector> inputs(steps); - std::vector> measurements(steps); - states[0] = frc::Vectord<4>{{0.0}, {0.0}, {true_kV}, {true_kA}}; + std::vector> states(steps + 1); + std::vector> inputs(steps); + std::vector> measurements(steps); + states[0] = wpi::math::Vectord<4>{{0.0}, {0.0}, {true_kV}, {true_kA}}; - constexpr frc::Matrixd<4, 4> A{{0.0, 1.0, 0.0, 0.0}, + constexpr wpi::math::Matrixd<4, 4> A{{0.0, 1.0, 0.0, 0.0}, {0.0, -true_kV / true_kA, 0.0, 0.0}, {0.0, 0.0, 0.0, 0.0}, {0.0, 0.0, 0.0, 0.0}}; - constexpr frc::Matrixd<4, 1> B{{0.0}, {1.0 / true_kA}, {0.0}, {0.0}}; + constexpr wpi::math::Matrixd<4, 1> B{{0.0}, {1.0 / true_kA}, {0.0}, {0.0}}; - frc::Matrixd<4, 4> discA; - frc::Matrixd<4, 1> discB; - frc::DiscretizeAB(A, B, dt, &discA, &discB); + wpi::math::Matrixd<4, 4> discA; + wpi::math::Matrixd<4, 1> discB; + wpi::math::DiscretizeAB(A, B, dt, &discA, &discB); for (int i = 0; i < steps; ++i) { inputs[i] = MotorControlInput(i * dt.value()); states[i + 1] = discA * states[i] + discB * inputs[i]; measurements[i] = MotorMeasurementModel(states[i + 1], inputs[i]) + - frc::MakeWhiteNoiseVector(pos_stddev, vel_stddev, accel_stddev); + wpi::math::MakeWhiteNoiseVector(pos_stddev, vel_stddev, accel_stddev); } - frc::Vectord<4> P0{0.001, 0.001, 10, 10}; + wpi::math::Vectord<4> P0{0.001, 0.001, 10, 10}; - frc::S3UKF<4, 1, 3> observer{ - MotorDynamics, MotorMeasurementModel, wpi::array{0.1, 1.0, 1e-10, 1e-10}, - wpi::array{pos_stddev, vel_stddev, accel_stddev}, dt}; + wpi::math::S3UKF<4, 1, 3> observer{ + MotorDynamics, MotorMeasurementModel, wpi::util::array{0.1, 1.0, 1e-10, 1e-10}, + wpi::util::array{pos_stddev, vel_stddev, accel_stddev}, dt}; - observer.SetXhat(frc::Vectord<4>{0.0, 0.0, 2.0, 2.0}); + observer.SetXhat(wpi::math::Vectord<4>{0.0, 0.0, 2.0, 2.0}); observer.SetP(P0.asDiagonal()); for (int i = 0; i < steps; ++i) { diff --git a/wpimath/src/test/native/cpp/estimator/SwerveDrivePoseEstimator3dTest.cpp b/wpimath/src/test/native/cpp/estimator/SwerveDrivePoseEstimator3dTest.cpp index 2fedcf7813..c9d4de2219 100644 --- a/wpimath/src/test/native/cpp/estimator/SwerveDrivePoseEstimator3dTest.cpp +++ b/wpimath/src/test/native/cpp/estimator/SwerveDrivePoseEstimator3dTest.cpp @@ -18,40 +18,40 @@ #include "wpi/util/timestamp.h" void testFollowTrajectory( - const frc::SwerveDriveKinematics<4>& kinematics, - frc::SwerveDrivePoseEstimator3d<4>& estimator, - const frc::Trajectory& trajectory, - std::function + const wpi::math::SwerveDriveKinematics<4>& kinematics, + wpi::math::SwerveDrivePoseEstimator3d<4>& estimator, + const wpi::math::Trajectory& trajectory, + std::function chassisSpeedsGenerator, - std::function + std::function visionMeasurementGenerator, - const frc::Pose2d& startingPose, const frc::Pose2d& endingPose, - const units::second_t dt, const units::second_t kVisionUpdateRate, - const units::second_t kVisionUpdateDelay, const bool checkError, + const wpi::math::Pose2d& startingPose, const wpi::math::Pose2d& endingPose, + const wpi::units::second_t dt, const wpi::units::second_t kVisionUpdateRate, + const wpi::units::second_t kVisionUpdateDelay, const bool checkError, const bool debug) { - wpi::array positions{wpi::empty_array}; + wpi::util::array positions{wpi::util::empty_array}; - estimator.ResetPosition(frc::Rotation3d{}, positions, - frc::Pose3d{startingPose}); + estimator.ResetPosition(wpi::math::Rotation3d{}, positions, + wpi::math::Pose3d{startingPose}); std::default_random_engine generator; std::normal_distribution distribution(0.0, 1.0); - units::second_t t = 0_s; + wpi::units::second_t t = 0_s; - std::vector> visionPoses; - std::vector> + std::vector> visionPoses; + std::vector> visionLog; double maxError = -std::numeric_limits::max(); double errorSum = 0; if (debug) { - wpi::print("time, est_x, est_y, est_theta, true_x, true_y, true_theta\n"); + wpi::util::print("time, est_x, est_y, est_theta, true_x, true_y, true_theta\n"); } while (t < trajectory.TotalTime()) { - frc::Trajectory::State groundTruthState = trajectory.Sample(t); + wpi::math::Trajectory::State groundTruthState = trajectory.Sample(t); // We are due for a new vision measurement if it's been `visionUpdateRate` // seconds since the last vision measurement @@ -59,9 +59,9 @@ void testFollowTrajectory( visionPoses.back().first + kVisionUpdateRate < t) { auto visionPose = visionMeasurementGenerator(groundTruthState) + - frc::Transform2d{frc::Translation2d{distribution(generator) * 0.1_m, + wpi::math::Transform2d{wpi::math::Translation2d{distribution(generator) * 0.1_m, distribution(generator) * 0.1_m}, - frc::Rotation2d{distribution(generator) * 0.05_rad}}; + wpi::math::Rotation2d{distribution(generator) * 0.05_rad}}; visionPoses.push_back({t, visionPose}); } @@ -70,7 +70,7 @@ void testFollowTrajectory( if (!visionPoses.empty() && visionPoses.front().first + kVisionUpdateDelay < t) { auto visionEntry = visionPoses.front(); - estimator.AddVisionMeasurement(frc::Pose3d{visionEntry.second}, + estimator.AddVisionMeasurement(wpi::math::Pose3d{visionEntry.second}, visionEntry.first); visionPoses.erase(visionPoses.begin()); visionLog.push_back({t, visionEntry.first, visionEntry.second}); @@ -87,13 +87,13 @@ void testFollowTrajectory( auto xhat = estimator.UpdateWithTime( t, - frc::Rotation3d{groundTruthState.pose.Rotation() + - frc::Rotation2d{distribution(generator) * 0.05_rad} - + wpi::math::Rotation3d{groundTruthState.pose.Rotation() + + wpi::math::Rotation2d{distribution(generator) * 0.05_rad} - trajectory.InitialPose().Rotation()}, positions); if (debug) { - wpi::print( + wpi::util::print( "{}, {}, {}, {}, {}, {}, {}\n", t.value(), xhat.X().value(), xhat.Y().value(), xhat.Rotation().ToRotation2d().Radians().value(), groundTruthState.pose.X().value(), groundTruthState.pose.Y().value(), @@ -113,14 +113,14 @@ void testFollowTrajectory( } if (debug) { - wpi::print("apply_time, measured_time, vision_x, vision_y, vision_theta\n"); + wpi::util::print("apply_time, measured_time, vision_x, vision_y, vision_theta\n"); - units::second_t apply_time; - units::second_t measure_time; - frc::Pose2d vision_pose; + wpi::units::second_t apply_time; + wpi::units::second_t measure_time; + wpi::math::Pose2d vision_pose; for (auto record : visionLog) { std::tie(apply_time, measure_time, vision_pose) = record; - wpi::print("{}, {}, {}, {}, {}\n", apply_time.value(), + wpi::util::print("{}, {}, {}, {}, {}\n", apply_time.value(), measure_time.value(), vision_pose.X().value(), vision_pose.Y().value(), vision_pose.Rotation().Radians().value()); @@ -147,79 +147,79 @@ void testFollowTrajectory( } TEST(SwerveDrivePoseEstimator3dTest, AccuracyFacingTrajectory) { - frc::SwerveDriveKinematics<4> kinematics{ - frc::Translation2d{1_m, 1_m}, frc::Translation2d{1_m, -1_m}, - frc::Translation2d{-1_m, -1_m}, frc::Translation2d{-1_m, 1_m}}; + wpi::math::SwerveDriveKinematics<4> kinematics{ + wpi::math::Translation2d{1_m, 1_m}, wpi::math::Translation2d{1_m, -1_m}, + wpi::math::Translation2d{-1_m, -1_m}, wpi::math::Translation2d{-1_m, 1_m}}; - frc::SwerveModulePosition fl; - frc::SwerveModulePosition fr; - frc::SwerveModulePosition bl; - frc::SwerveModulePosition br; + wpi::math::SwerveModulePosition fl; + wpi::math::SwerveModulePosition fr; + wpi::math::SwerveModulePosition bl; + wpi::math::SwerveModulePosition br; - frc::SwerveDrivePoseEstimator3d<4> estimator{ - kinematics, frc::Rotation3d{}, {fl, fr, bl, br}, - frc::Pose3d{}, {0.1, 0.1, 0.1, 0.1}, {0.45, 0.45, 0.45, 0.45}}; + wpi::math::SwerveDrivePoseEstimator3d<4> estimator{ + kinematics, wpi::math::Rotation3d{}, {fl, fr, bl, br}, + wpi::math::Pose3d{}, {0.1, 0.1, 0.1, 0.1}, {0.45, 0.45, 0.45, 0.45}}; - frc::Trajectory trajectory = frc::TrajectoryGenerator::GenerateTrajectory( - std::vector{frc::Pose2d{0_m, 0_m, 45_deg}, frc::Pose2d{3_m, 0_m, -90_deg}, - frc::Pose2d{0_m, 0_m, 135_deg}, - frc::Pose2d{-3_m, 0_m, -90_deg}, - frc::Pose2d{0_m, 0_m, 45_deg}}, - frc::TrajectoryConfig(2_mps, 2.0_mps_sq)); + wpi::math::Trajectory trajectory = wpi::math::TrajectoryGenerator::GenerateTrajectory( + std::vector{wpi::math::Pose2d{0_m, 0_m, 45_deg}, wpi::math::Pose2d{3_m, 0_m, -90_deg}, + wpi::math::Pose2d{0_m, 0_m, 135_deg}, + wpi::math::Pose2d{-3_m, 0_m, -90_deg}, + wpi::math::Pose2d{0_m, 0_m, 45_deg}}, + wpi::math::TrajectoryConfig(2_mps, 2.0_mps_sq)); testFollowTrajectory( kinematics, estimator, trajectory, - [&](frc::Trajectory::State& state) { - return frc::ChassisSpeeds{state.velocity, 0_mps, + [&](wpi::math::Trajectory::State& state) { + return wpi::math::ChassisSpeeds{state.velocity, 0_mps, state.velocity * state.curvature}; }, - [&](frc::Trajectory::State& state) { return state.pose; }, - {0_m, 0_m, frc::Rotation2d{45_deg}}, {0_m, 0_m, frc::Rotation2d{45_deg}}, + [&](wpi::math::Trajectory::State& state) { return state.pose; }, + {0_m, 0_m, wpi::math::Rotation2d{45_deg}}, {0_m, 0_m, wpi::math::Rotation2d{45_deg}}, 20_ms, 100_ms, 250_ms, true, false); } TEST(SwerveDrivePoseEstimator3dTest, BadInitialPose) { - frc::SwerveDriveKinematics<4> kinematics{ - frc::Translation2d{1_m, 1_m}, frc::Translation2d{1_m, -1_m}, - frc::Translation2d{-1_m, -1_m}, frc::Translation2d{-1_m, 1_m}}; + wpi::math::SwerveDriveKinematics<4> kinematics{ + wpi::math::Translation2d{1_m, 1_m}, wpi::math::Translation2d{1_m, -1_m}, + wpi::math::Translation2d{-1_m, -1_m}, wpi::math::Translation2d{-1_m, 1_m}}; - frc::SwerveModulePosition fl; - frc::SwerveModulePosition fr; - frc::SwerveModulePosition bl; - frc::SwerveModulePosition br; + wpi::math::SwerveModulePosition fl; + wpi::math::SwerveModulePosition fr; + wpi::math::SwerveModulePosition bl; + wpi::math::SwerveModulePosition br; - frc::SwerveDrivePoseEstimator3d<4> estimator{ - kinematics, frc::Rotation3d{}, {fl, fr, bl, br}, - frc::Pose3d{}, {0.1, 0.1, 0.1, 0.1}, {0.9, 0.9, 0.9, 0.9}}; + wpi::math::SwerveDrivePoseEstimator3d<4> estimator{ + kinematics, wpi::math::Rotation3d{}, {fl, fr, bl, br}, + wpi::math::Pose3d{}, {0.1, 0.1, 0.1, 0.1}, {0.9, 0.9, 0.9, 0.9}}; - frc::Trajectory trajectory = frc::TrajectoryGenerator::GenerateTrajectory( - std::vector{frc::Pose2d{0_m, 0_m, 45_deg}, frc::Pose2d{3_m, 0_m, -90_deg}, - frc::Pose2d{0_m, 0_m, 135_deg}, - frc::Pose2d{-3_m, 0_m, -90_deg}, - frc::Pose2d{0_m, 0_m, 45_deg}}, - frc::TrajectoryConfig(2_mps, 2.0_mps_sq)); + wpi::math::Trajectory trajectory = wpi::math::TrajectoryGenerator::GenerateTrajectory( + std::vector{wpi::math::Pose2d{0_m, 0_m, 45_deg}, wpi::math::Pose2d{3_m, 0_m, -90_deg}, + wpi::math::Pose2d{0_m, 0_m, 135_deg}, + wpi::math::Pose2d{-3_m, 0_m, -90_deg}, + wpi::math::Pose2d{0_m, 0_m, 45_deg}}, + wpi::math::TrajectoryConfig(2_mps, 2.0_mps_sq)); - for (units::degree_t offset_direction_degs = 0_deg; + for (wpi::units::degree_t offset_direction_degs = 0_deg; offset_direction_degs < 360_deg; offset_direction_degs += 45_deg) { - for (units::degree_t offset_heading_degs = 0_deg; + for (wpi::units::degree_t offset_heading_degs = 0_deg; offset_heading_degs < 360_deg; offset_heading_degs += 45_deg) { - auto pose_offset = frc::Rotation2d{offset_direction_degs}; - auto heading_offset = frc::Rotation2d{offset_heading_degs}; + auto pose_offset = wpi::math::Rotation2d{offset_direction_degs}; + auto heading_offset = wpi::math::Rotation2d{offset_heading_degs}; auto initial_pose = trajectory.InitialPose() + - frc::Transform2d{frc::Translation2d{pose_offset.Cos() * 1_m, + wpi::math::Transform2d{wpi::math::Translation2d{pose_offset.Cos() * 1_m, pose_offset.Sin() * 1_m}, heading_offset}; testFollowTrajectory( kinematics, estimator, trajectory, - [&](frc::Trajectory::State& state) { - return frc::ChassisSpeeds{state.velocity, 0_mps, + [&](wpi::math::Trajectory::State& state) { + return wpi::math::ChassisSpeeds{state.velocity, 0_mps, state.velocity * state.curvature}; }, - [&](frc::Trajectory::State& state) { return state.pose; }, - initial_pose, {0_m, 0_m, frc::Rotation2d{45_deg}}, 20_ms, 100_ms, + [&](wpi::math::Trajectory::State& state) { return state.pose; }, + initial_pose, {0_m, 0_m, wpi::math::Rotation2d{45_deg}}, 20_ms, 100_ms, 250_ms, false, false); } } @@ -231,39 +231,39 @@ TEST(SwerveDrivePoseEstimator3dTest, SimultaneousVisionMeasurements) { // The alternative result is that only one vision measurement affects the // outcome. If that were the case, after 1000 measurements, the estimated // pose would converge to that measurement. - frc::SwerveDriveKinematics<4> kinematics{ - frc::Translation2d{1_m, 1_m}, frc::Translation2d{1_m, -1_m}, - frc::Translation2d{-1_m, -1_m}, frc::Translation2d{-1_m, 1_m}}; + wpi::math::SwerveDriveKinematics<4> kinematics{ + wpi::math::Translation2d{1_m, 1_m}, wpi::math::Translation2d{1_m, -1_m}, + wpi::math::Translation2d{-1_m, -1_m}, wpi::math::Translation2d{-1_m, 1_m}}; - frc::SwerveModulePosition fl; - frc::SwerveModulePosition fr; - frc::SwerveModulePosition bl; - frc::SwerveModulePosition br; + wpi::math::SwerveModulePosition fl; + wpi::math::SwerveModulePosition fr; + wpi::math::SwerveModulePosition bl; + wpi::math::SwerveModulePosition br; - frc::SwerveDrivePoseEstimator3d<4> estimator{ + wpi::math::SwerveDrivePoseEstimator3d<4> estimator{ kinematics, - frc::Rotation3d{}, + wpi::math::Rotation3d{}, {fl, fr, bl, br}, - frc::Pose3d{1_m, 2_m, 0_m, frc::Rotation3d{0_deg, 0_deg, 270_deg}}, + wpi::math::Pose3d{1_m, 2_m, 0_m, wpi::math::Rotation3d{0_deg, 0_deg, 270_deg}}, {0.1, 0.1, 0.1, 0.1}, {0.45, 0.45, 0.45, 0.45}}; - estimator.UpdateWithTime(0_s, frc::Rotation3d{}, {fl, fr, bl, br}); + estimator.UpdateWithTime(0_s, wpi::math::Rotation3d{}, {fl, fr, bl, br}); for (int i = 0; i < 1000; i++) { estimator.AddVisionMeasurement( - frc::Pose3d{0_m, 0_m, 0_m, frc::Rotation3d{0_deg, 0_deg, 0_deg}}, 0_s); + wpi::math::Pose3d{0_m, 0_m, 0_m, wpi::math::Rotation3d{0_deg, 0_deg, 0_deg}}, 0_s); estimator.AddVisionMeasurement( - frc::Pose3d{3_m, 1_m, 0_m, frc::Rotation3d{0_deg, 0_deg, 90_deg}}, 0_s); + wpi::math::Pose3d{3_m, 1_m, 0_m, wpi::math::Rotation3d{0_deg, 0_deg, 90_deg}}, 0_s); estimator.AddVisionMeasurement( - frc::Pose3d{2_m, 4_m, 0_m, frc::Rotation3d{0_deg, 0_deg, 180_deg}}, + wpi::math::Pose3d{2_m, 4_m, 0_m, wpi::math::Rotation3d{0_deg, 0_deg, 180_deg}}, 0_s); } { - auto dx = units::math::abs(estimator.GetEstimatedPosition().X() - 0_m); - auto dy = units::math::abs(estimator.GetEstimatedPosition().Y() - 0_m); - auto dtheta = units::math::abs( + auto dx = wpi::units::math::abs(estimator.GetEstimatedPosition().X() - 0_m); + auto dy = wpi::units::math::abs(estimator.GetEstimatedPosition().Y() - 0_m); + auto dtheta = wpi::units::math::abs( estimator.GetEstimatedPosition().Rotation().ToRotation2d().Radians() - 0_deg); @@ -271,9 +271,9 @@ TEST(SwerveDrivePoseEstimator3dTest, SimultaneousVisionMeasurements) { } { - auto dx = units::math::abs(estimator.GetEstimatedPosition().X() - 3_m); - auto dy = units::math::abs(estimator.GetEstimatedPosition().Y() - 1_m); - auto dtheta = units::math::abs( + auto dx = wpi::units::math::abs(estimator.GetEstimatedPosition().X() - 3_m); + auto dy = wpi::units::math::abs(estimator.GetEstimatedPosition().Y() - 1_m); + auto dtheta = wpi::units::math::abs( estimator.GetEstimatedPosition().Rotation().ToRotation2d().Radians() - 90_deg); @@ -281,9 +281,9 @@ TEST(SwerveDrivePoseEstimator3dTest, SimultaneousVisionMeasurements) { } { - auto dx = units::math::abs(estimator.GetEstimatedPosition().X() - 2_m); - auto dy = units::math::abs(estimator.GetEstimatedPosition().Y() - 4_m); - auto dtheta = units::math::abs( + auto dx = wpi::units::math::abs(estimator.GetEstimatedPosition().X() - 2_m); + auto dy = wpi::units::math::abs(estimator.GetEstimatedPosition().Y() - 4_m); + auto dtheta = wpi::units::math::abs( estimator.GetEstimatedPosition().Rotation().ToRotation2d().Radians() - 180_deg); @@ -292,29 +292,29 @@ TEST(SwerveDrivePoseEstimator3dTest, SimultaneousVisionMeasurements) { } TEST(SwerveDrivePoseEstimator3dTest, TestDiscardStaleVisionMeasurements) { - frc::SwerveDriveKinematics<4> kinematics{ - frc::Translation2d{1_m, 1_m}, frc::Translation2d{1_m, -1_m}, - frc::Translation2d{-1_m, -1_m}, frc::Translation2d{-1_m, 1_m}}; + wpi::math::SwerveDriveKinematics<4> kinematics{ + wpi::math::Translation2d{1_m, 1_m}, wpi::math::Translation2d{1_m, -1_m}, + wpi::math::Translation2d{-1_m, -1_m}, wpi::math::Translation2d{-1_m, 1_m}}; - frc::SwerveModulePosition fl; - frc::SwerveModulePosition fr; - frc::SwerveModulePosition bl; - frc::SwerveModulePosition br; + wpi::math::SwerveModulePosition fl; + wpi::math::SwerveModulePosition fr; + wpi::math::SwerveModulePosition bl; + wpi::math::SwerveModulePosition br; - frc::SwerveDrivePoseEstimator3d<4> estimator{ - kinematics, frc::Rotation3d{}, {fl, fr, bl, br}, - frc::Pose3d{}, {0.1, 0.1, 0.1, 0.1}, {0.45, 0.45, 0.45, 0.45}}; + wpi::math::SwerveDrivePoseEstimator3d<4> estimator{ + kinematics, wpi::math::Rotation3d{}, {fl, fr, bl, br}, + wpi::math::Pose3d{}, {0.1, 0.1, 0.1, 0.1}, {0.45, 0.45, 0.45, 0.45}}; // Add enough measurements to fill up the buffer for (auto time = 0_s; time < 4_s; time += 20_ms) { - estimator.UpdateWithTime(time, frc::Rotation3d{}, {fl, fr, bl, br}); + estimator.UpdateWithTime(time, wpi::math::Rotation3d{}, {fl, fr, bl, br}); } auto odometryPose = estimator.GetEstimatedPosition(); // Apply a vision measurement from 3 seconds ago estimator.AddVisionMeasurement( - frc::Pose3d{10_m, 10_m, 0_m, frc::Rotation3d{0_rad, 0_rad, 0.1_rad}}, 1_s, + wpi::math::Pose3d{10_m, 10_m, 0_m, wpi::math::Rotation3d{0_rad, 0_rad, 0.1_rad}}, 1_s, {0.1, 0.1, 0.1, 0.1}); EXPECT_NEAR(odometryPose.X().value(), @@ -332,15 +332,15 @@ TEST(SwerveDrivePoseEstimator3dTest, TestDiscardStaleVisionMeasurements) { } TEST(SwerveDrivePoseEstimator3dTest, TestSampleAt) { - frc::SwerveDriveKinematics<4> kinematics{ - frc::Translation2d{1_m, 1_m}, frc::Translation2d{1_m, -1_m}, - frc::Translation2d{-1_m, -1_m}, frc::Translation2d{-1_m, 1_m}}; - frc::SwerveDrivePoseEstimator3d estimator{ + wpi::math::SwerveDriveKinematics<4> kinematics{ + wpi::math::Translation2d{1_m, 1_m}, wpi::math::Translation2d{1_m, -1_m}, + wpi::math::Translation2d{-1_m, -1_m}, wpi::math::Translation2d{-1_m, 1_m}}; + wpi::math::SwerveDrivePoseEstimator3d estimator{ kinematics, - frc::Rotation3d{}, - {frc::SwerveModulePosition{}, frc::SwerveModulePosition{}, - frc::SwerveModulePosition{}, frc::SwerveModulePosition{}}, - frc::Pose3d{}, + wpi::math::Rotation3d{}, + {wpi::math::SwerveModulePosition{}, wpi::math::SwerveModulePosition{}, + wpi::math::SwerveModulePosition{}, wpi::math::SwerveModulePosition{}}, + wpi::math::Pose3d{}, {1.0, 1.0, 1.0, 1.0}, {1.0, 1.0, 1.0, 1.0}}; @@ -351,67 +351,67 @@ TEST(SwerveDrivePoseEstimator3dTest, TestSampleAt) { // Add a tiny tolerance for the upper bound because of floating point rounding // error for (double time = 1; time <= 2 + 1e-9; time += 0.02) { - wpi::array wheelPositions{ - {frc::SwerveModulePosition{units::meter_t{time}, frc::Rotation2d{}}, - frc::SwerveModulePosition{units::meter_t{time}, frc::Rotation2d{}}, - frc::SwerveModulePosition{units::meter_t{time}, frc::Rotation2d{}}, - frc::SwerveModulePosition{units::meter_t{time}, frc::Rotation2d{}}}}; - estimator.UpdateWithTime(units::second_t{time}, frc::Rotation3d{}, + wpi::util::array wheelPositions{ + {wpi::math::SwerveModulePosition{wpi::units::meter_t{time}, wpi::math::Rotation2d{}}, + wpi::math::SwerveModulePosition{wpi::units::meter_t{time}, wpi::math::Rotation2d{}}, + wpi::math::SwerveModulePosition{wpi::units::meter_t{time}, wpi::math::Rotation2d{}}, + wpi::math::SwerveModulePosition{wpi::units::meter_t{time}, wpi::math::Rotation2d{}}}}; + estimator.UpdateWithTime(wpi::units::second_t{time}, wpi::math::Rotation3d{}, wheelPositions); } // Sample at an added time - EXPECT_EQ(std::optional(frc::Pose3d{1.02_m, 0_m, 0_m, frc::Rotation3d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose3d{1.02_m, 0_m, 0_m, wpi::math::Rotation3d{}}), estimator.SampleAt(1.02_s)); // Sample between updates (test interpolation) - EXPECT_EQ(std::optional(frc::Pose3d{1.01_m, 0_m, 0_m, frc::Rotation3d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose3d{1.01_m, 0_m, 0_m, wpi::math::Rotation3d{}}), estimator.SampleAt(1.01_s)); // Sampling before the oldest value returns the oldest value - EXPECT_EQ(std::optional(frc::Pose3d{1_m, 0_m, 0_m, frc::Rotation3d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose3d{1_m, 0_m, 0_m, wpi::math::Rotation3d{}}), estimator.SampleAt(0.5_s)); // Sampling after the newest value returns the newest value - EXPECT_EQ(std::optional(frc::Pose3d{2_m, 0_m, 0_m, frc::Rotation3d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose3d{2_m, 0_m, 0_m, wpi::math::Rotation3d{}}), estimator.SampleAt(2.5_s)); // Add a vision measurement after the odometry measurements (while keeping all // of the old odometry measurements) estimator.AddVisionMeasurement( - frc::Pose3d{2_m, 0_m, 0_m, frc::Rotation3d{0_rad, 0_rad, 1_rad}}, 2.2_s); + wpi::math::Pose3d{2_m, 0_m, 0_m, wpi::math::Rotation3d{0_rad, 0_rad, 1_rad}}, 2.2_s); // Make sure nothing changed (except the newest value) - EXPECT_EQ(std::optional(frc::Pose3d{1.02_m, 0_m, 0_m, frc::Rotation3d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose3d{1.02_m, 0_m, 0_m, wpi::math::Rotation3d{}}), estimator.SampleAt(1.02_s)); - EXPECT_EQ(std::optional(frc::Pose3d{1.01_m, 0_m, 0_m, frc::Rotation3d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose3d{1.01_m, 0_m, 0_m, wpi::math::Rotation3d{}}), estimator.SampleAt(1.01_s)); - EXPECT_EQ(std::optional(frc::Pose3d{1_m, 0_m, 0_m, frc::Rotation3d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose3d{1_m, 0_m, 0_m, wpi::math::Rotation3d{}}), estimator.SampleAt(0.5_s)); // Add a vision measurement before the odometry measurements that's still in // the buffer estimator.AddVisionMeasurement( - frc::Pose3d{1_m, 0.2_m, 0_m, frc::Rotation3d{}}, 0.9_s); + wpi::math::Pose3d{1_m, 0.2_m, 0_m, wpi::math::Rotation3d{}}, 0.9_s); // Everything should be the same except Y is 0.1 (halfway between 0 and 0.2) - EXPECT_EQ(std::optional(frc::Pose3d{1.02_m, 0.1_m, 0_m, frc::Rotation3d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose3d{1.02_m, 0.1_m, 0_m, wpi::math::Rotation3d{}}), estimator.SampleAt(1.02_s)); - EXPECT_EQ(std::optional(frc::Pose3d{1.01_m, 0.1_m, 0_m, frc::Rotation3d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose3d{1.01_m, 0.1_m, 0_m, wpi::math::Rotation3d{}}), estimator.SampleAt(1.01_s)); - EXPECT_EQ(std::optional(frc::Pose3d{1_m, 0.1_m, 0_m, frc::Rotation3d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose3d{1_m, 0.1_m, 0_m, wpi::math::Rotation3d{}}), estimator.SampleAt(0.5_s)); - EXPECT_EQ(std::optional(frc::Pose3d{2_m, 0.1_m, 0_m, frc::Rotation3d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose3d{2_m, 0.1_m, 0_m, wpi::math::Rotation3d{}}), estimator.SampleAt(2.5_s)); } TEST(SwerveDrivePoseEstimator3dTest, TestReset) { - frc::SwerveDriveKinematics<4> kinematics{ - frc::Translation2d{1_m, 1_m}, frc::Translation2d{1_m, -1_m}, - frc::Translation2d{-1_m, -1_m}, frc::Translation2d{-1_m, 1_m}}; - frc::SwerveDrivePoseEstimator3d estimator{ + wpi::math::SwerveDriveKinematics<4> kinematics{ + wpi::math::Translation2d{1_m, 1_m}, wpi::math::Translation2d{1_m, -1_m}, + wpi::math::Translation2d{-1_m, -1_m}, wpi::math::Translation2d{-1_m, 1_m}}; + wpi::math::SwerveDrivePoseEstimator3d estimator{ kinematics, - frc::Rotation3d{}, - {frc::SwerveModulePosition{}, frc::SwerveModulePosition{}, - frc::SwerveModulePosition{}, frc::SwerveModulePosition{}}, - frc::Pose3d{-1_m, -1_m, -1_m, frc::Rotation3d{0_rad, 0_rad, 1_rad}}, + wpi::math::Rotation3d{}, + {wpi::math::SwerveModulePosition{}, wpi::math::SwerveModulePosition{}, + wpi::math::SwerveModulePosition{}, wpi::math::SwerveModulePosition{}}, + wpi::math::Pose3d{-1_m, -1_m, -1_m, wpi::math::Rotation3d{0_rad, 0_rad, 1_rad}}, {1.0, 1.0, 1.0, 1.0}, {1.0, 1.0, 1.0, 1.0}}; @@ -425,11 +425,11 @@ TEST(SwerveDrivePoseEstimator3dTest, TestReset) { // Test reset position { - frc::SwerveModulePosition modulePosition{1_m, frc::Rotation2d{}}; + wpi::math::SwerveModulePosition modulePosition{1_m, wpi::math::Rotation2d{}}; estimator.ResetPosition( - frc::Rotation3d{}, + wpi::math::Rotation3d{}, {modulePosition, modulePosition, modulePosition, modulePosition}, - frc::Pose3d{1_m, 0_m, 0_m, frc::Rotation3d{}}); + wpi::math::Pose3d{1_m, 0_m, 0_m, wpi::math::Rotation3d{}}); } EXPECT_DOUBLE_EQ(1, estimator.GetEstimatedPosition().X().value()); @@ -441,8 +441,8 @@ TEST(SwerveDrivePoseEstimator3dTest, TestReset) { // Test orientation and wheel positions { - frc::SwerveModulePosition modulePosition{2_m, frc::Rotation2d{}}; - estimator.Update(frc::Rotation3d{}, {modulePosition, modulePosition, + wpi::math::SwerveModulePosition modulePosition{2_m, wpi::math::Rotation2d{}}; + estimator.Update(wpi::math::Rotation3d{}, {modulePosition, modulePosition, modulePosition, modulePosition}); } @@ -454,7 +454,7 @@ TEST(SwerveDrivePoseEstimator3dTest, TestReset) { EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Rotation().Z().value()); // Test reset rotation - estimator.ResetRotation(frc::Rotation3d{0_deg, 0_deg, 90_deg}); + estimator.ResetRotation(wpi::math::Rotation3d{0_deg, 0_deg, 90_deg}); EXPECT_DOUBLE_EQ(2, estimator.GetEstimatedPosition().X().value()); EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Y().value()); @@ -466,8 +466,8 @@ TEST(SwerveDrivePoseEstimator3dTest, TestReset) { // Test orientation { - frc::SwerveModulePosition modulePosition{3_m, frc::Rotation2d{}}; - estimator.Update(frc::Rotation3d{}, {modulePosition, modulePosition, + wpi::math::SwerveModulePosition modulePosition{3_m, wpi::math::Rotation2d{}}; + estimator.Update(wpi::math::Rotation3d{}, {modulePosition, modulePosition, modulePosition, modulePosition}); } @@ -480,7 +480,7 @@ TEST(SwerveDrivePoseEstimator3dTest, TestReset) { estimator.GetEstimatedPosition().Rotation().Z().value()); // Test reset translation - estimator.ResetTranslation(frc::Translation3d{-1_m, -1_m, -1_m}); + estimator.ResetTranslation(wpi::math::Translation3d{-1_m, -1_m, -1_m}); EXPECT_DOUBLE_EQ(-1, estimator.GetEstimatedPosition().X().value()); EXPECT_DOUBLE_EQ(-1, estimator.GetEstimatedPosition().Y().value()); @@ -491,7 +491,7 @@ TEST(SwerveDrivePoseEstimator3dTest, TestReset) { estimator.GetEstimatedPosition().Rotation().Z().value()); // Test reset pose - estimator.ResetPose(frc::Pose3d{}); + estimator.ResetPose(wpi::math::Pose3d{}); EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().X().value()); EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Y().value()); diff --git a/wpimath/src/test/native/cpp/estimator/SwerveDrivePoseEstimatorTest.cpp b/wpimath/src/test/native/cpp/estimator/SwerveDrivePoseEstimatorTest.cpp index 53d24a06fa..c6f0cbf56e 100644 --- a/wpimath/src/test/native/cpp/estimator/SwerveDrivePoseEstimatorTest.cpp +++ b/wpimath/src/test/native/cpp/estimator/SwerveDrivePoseEstimatorTest.cpp @@ -19,39 +19,39 @@ #include "wpi/util/timestamp.h" void testFollowTrajectory( - const frc::SwerveDriveKinematics<4>& kinematics, - frc::SwerveDrivePoseEstimator<4>& estimator, - const frc::Trajectory& trajectory, - std::function + const wpi::math::SwerveDriveKinematics<4>& kinematics, + wpi::math::SwerveDrivePoseEstimator<4>& estimator, + const wpi::math::Trajectory& trajectory, + std::function chassisSpeedsGenerator, - std::function + std::function visionMeasurementGenerator, - const frc::Pose2d& startingPose, const frc::Pose2d& endingPose, - const units::second_t dt, const units::second_t kVisionUpdateRate, - const units::second_t kVisionUpdateDelay, const bool checkError, + const wpi::math::Pose2d& startingPose, const wpi::math::Pose2d& endingPose, + const wpi::units::second_t dt, const wpi::units::second_t kVisionUpdateRate, + const wpi::units::second_t kVisionUpdateDelay, const bool checkError, const bool debug) { - wpi::array positions{wpi::empty_array}; + wpi::util::array positions{wpi::util::empty_array}; - estimator.ResetPosition(frc::Rotation2d{}, positions, startingPose); + estimator.ResetPosition(wpi::math::Rotation2d{}, positions, startingPose); std::default_random_engine generator; std::normal_distribution distribution(0.0, 1.0); - units::second_t t = 0_s; + wpi::units::second_t t = 0_s; - std::vector> visionPoses; - std::vector> + std::vector> visionPoses; + std::vector> visionLog; double maxError = -std::numeric_limits::max(); double errorSum = 0; if (debug) { - wpi::print("time, est_x, est_y, est_theta, true_x, true_y, true_theta\n"); + wpi::util::print("time, est_x, est_y, est_theta, true_x, true_y, true_theta\n"); } while (t < trajectory.TotalTime()) { - frc::Trajectory::State groundTruthState = trajectory.Sample(t); + wpi::math::Trajectory::State groundTruthState = trajectory.Sample(t); // We are due for a new vision measurement if it's been `visionUpdateRate` // seconds since the last vision measurement @@ -59,9 +59,9 @@ void testFollowTrajectory( visionPoses.back().first + kVisionUpdateRate < t) { auto visionPose = visionMeasurementGenerator(groundTruthState) + - frc::Transform2d{frc::Translation2d{distribution(generator) * 0.1_m, + wpi::math::Transform2d{wpi::math::Translation2d{distribution(generator) * 0.1_m, distribution(generator) * 0.1_m}, - frc::Rotation2d{distribution(generator) * 0.05_rad}}; + wpi::math::Rotation2d{distribution(generator) * 0.05_rad}}; visionPoses.push_back({t, visionPose}); } @@ -87,12 +87,12 @@ void testFollowTrajectory( auto xhat = estimator.UpdateWithTime( t, groundTruthState.pose.Rotation() + - frc::Rotation2d{distribution(generator) * 0.05_rad} - + wpi::math::Rotation2d{distribution(generator) * 0.05_rad} - trajectory.InitialPose().Rotation(), positions); if (debug) { - wpi::print("{}, {}, {}, {}, {}, {}, {}\n", t.value(), xhat.X().value(), + wpi::util::print("{}, {}, {}, {}, {}, {}, {}\n", t.value(), xhat.X().value(), xhat.Y().value(), xhat.Rotation().Radians().value(), groundTruthState.pose.X().value(), groundTruthState.pose.Y().value(), @@ -112,14 +112,14 @@ void testFollowTrajectory( } if (debug) { - wpi::print("apply_time, measured_time, vision_x, vision_y, vision_theta\n"); + wpi::util::print("apply_time, measured_time, vision_x, vision_y, vision_theta\n"); - units::second_t apply_time; - units::second_t measure_time; - frc::Pose2d vision_pose; + wpi::units::second_t apply_time; + wpi::units::second_t measure_time; + wpi::math::Pose2d vision_pose; for (auto record : visionLog) { std::tie(apply_time, measure_time, vision_pose) = record; - wpi::print("{}, {}, {}, {}, {}\n", apply_time.value(), + wpi::util::print("{}, {}, {}, {}, {}\n", apply_time.value(), measure_time.value(), vision_pose.X().value(), vision_pose.Y().value(), vision_pose.Rotation().Radians().value()); @@ -142,79 +142,79 @@ void testFollowTrajectory( } TEST(SwerveDrivePoseEstimatorTest, AccuracyFacingTrajectory) { - frc::SwerveDriveKinematics<4> kinematics{ - frc::Translation2d{1_m, 1_m}, frc::Translation2d{1_m, -1_m}, - frc::Translation2d{-1_m, -1_m}, frc::Translation2d{-1_m, 1_m}}; + wpi::math::SwerveDriveKinematics<4> kinematics{ + wpi::math::Translation2d{1_m, 1_m}, wpi::math::Translation2d{1_m, -1_m}, + wpi::math::Translation2d{-1_m, -1_m}, wpi::math::Translation2d{-1_m, 1_m}}; - frc::SwerveModulePosition fl; - frc::SwerveModulePosition fr; - frc::SwerveModulePosition bl; - frc::SwerveModulePosition br; + wpi::math::SwerveModulePosition fl; + wpi::math::SwerveModulePosition fr; + wpi::math::SwerveModulePosition bl; + wpi::math::SwerveModulePosition br; - frc::SwerveDrivePoseEstimator<4> estimator{ - kinematics, frc::Rotation2d{}, {fl, fr, bl, br}, - frc::Pose2d{}, {0.1, 0.1, 0.1}, {0.45, 0.45, 0.45}}; + wpi::math::SwerveDrivePoseEstimator<4> estimator{ + kinematics, wpi::math::Rotation2d{}, {fl, fr, bl, br}, + wpi::math::Pose2d{}, {0.1, 0.1, 0.1}, {0.45, 0.45, 0.45}}; - frc::Trajectory trajectory = frc::TrajectoryGenerator::GenerateTrajectory( - std::vector{frc::Pose2d{0_m, 0_m, 45_deg}, frc::Pose2d{3_m, 0_m, -90_deg}, - frc::Pose2d{0_m, 0_m, 135_deg}, - frc::Pose2d{-3_m, 0_m, -90_deg}, - frc::Pose2d{0_m, 0_m, 45_deg}}, - frc::TrajectoryConfig(2_mps, 2.0_mps_sq)); + wpi::math::Trajectory trajectory = wpi::math::TrajectoryGenerator::GenerateTrajectory( + std::vector{wpi::math::Pose2d{0_m, 0_m, 45_deg}, wpi::math::Pose2d{3_m, 0_m, -90_deg}, + wpi::math::Pose2d{0_m, 0_m, 135_deg}, + wpi::math::Pose2d{-3_m, 0_m, -90_deg}, + wpi::math::Pose2d{0_m, 0_m, 45_deg}}, + wpi::math::TrajectoryConfig(2_mps, 2.0_mps_sq)); testFollowTrajectory( kinematics, estimator, trajectory, - [&](frc::Trajectory::State& state) { - return frc::ChassisSpeeds{state.velocity, 0_mps, + [&](wpi::math::Trajectory::State& state) { + return wpi::math::ChassisSpeeds{state.velocity, 0_mps, state.velocity * state.curvature}; }, - [&](frc::Trajectory::State& state) { return state.pose; }, - {0_m, 0_m, frc::Rotation2d{45_deg}}, {0_m, 0_m, frc::Rotation2d{45_deg}}, + [&](wpi::math::Trajectory::State& state) { return state.pose; }, + {0_m, 0_m, wpi::math::Rotation2d{45_deg}}, {0_m, 0_m, wpi::math::Rotation2d{45_deg}}, 20_ms, 100_ms, 250_ms, true, false); } TEST(SwerveDrivePoseEstimatorTest, BadInitialPose) { - frc::SwerveDriveKinematics<4> kinematics{ - frc::Translation2d{1_m, 1_m}, frc::Translation2d{1_m, -1_m}, - frc::Translation2d{-1_m, -1_m}, frc::Translation2d{-1_m, 1_m}}; + wpi::math::SwerveDriveKinematics<4> kinematics{ + wpi::math::Translation2d{1_m, 1_m}, wpi::math::Translation2d{1_m, -1_m}, + wpi::math::Translation2d{-1_m, -1_m}, wpi::math::Translation2d{-1_m, 1_m}}; - frc::SwerveModulePosition fl; - frc::SwerveModulePosition fr; - frc::SwerveModulePosition bl; - frc::SwerveModulePosition br; + wpi::math::SwerveModulePosition fl; + wpi::math::SwerveModulePosition fr; + wpi::math::SwerveModulePosition bl; + wpi::math::SwerveModulePosition br; - frc::SwerveDrivePoseEstimator<4> estimator{ - kinematics, frc::Rotation2d{}, {fl, fr, bl, br}, - frc::Pose2d{}, {0.1, 0.1, 0.1}, {0.9, 0.9, 0.9}}; + wpi::math::SwerveDrivePoseEstimator<4> estimator{ + kinematics, wpi::math::Rotation2d{}, {fl, fr, bl, br}, + wpi::math::Pose2d{}, {0.1, 0.1, 0.1}, {0.9, 0.9, 0.9}}; - frc::Trajectory trajectory = frc::TrajectoryGenerator::GenerateTrajectory( - std::vector{frc::Pose2d{0_m, 0_m, 45_deg}, frc::Pose2d{3_m, 0_m, -90_deg}, - frc::Pose2d{0_m, 0_m, 135_deg}, - frc::Pose2d{-3_m, 0_m, -90_deg}, - frc::Pose2d{0_m, 0_m, 45_deg}}, - frc::TrajectoryConfig(2_mps, 2.0_mps_sq)); + wpi::math::Trajectory trajectory = wpi::math::TrajectoryGenerator::GenerateTrajectory( + std::vector{wpi::math::Pose2d{0_m, 0_m, 45_deg}, wpi::math::Pose2d{3_m, 0_m, -90_deg}, + wpi::math::Pose2d{0_m, 0_m, 135_deg}, + wpi::math::Pose2d{-3_m, 0_m, -90_deg}, + wpi::math::Pose2d{0_m, 0_m, 45_deg}}, + wpi::math::TrajectoryConfig(2_mps, 2.0_mps_sq)); - for (units::degree_t offset_direction_degs = 0_deg; + for (wpi::units::degree_t offset_direction_degs = 0_deg; offset_direction_degs < 360_deg; offset_direction_degs += 45_deg) { - for (units::degree_t offset_heading_degs = 0_deg; + for (wpi::units::degree_t offset_heading_degs = 0_deg; offset_heading_degs < 360_deg; offset_heading_degs += 45_deg) { - auto pose_offset = frc::Rotation2d{offset_direction_degs}; - auto heading_offset = frc::Rotation2d{offset_heading_degs}; + auto pose_offset = wpi::math::Rotation2d{offset_direction_degs}; + auto heading_offset = wpi::math::Rotation2d{offset_heading_degs}; auto initial_pose = trajectory.InitialPose() + - frc::Transform2d{frc::Translation2d{pose_offset.Cos() * 1_m, + wpi::math::Transform2d{wpi::math::Translation2d{pose_offset.Cos() * 1_m, pose_offset.Sin() * 1_m}, heading_offset}; testFollowTrajectory( kinematics, estimator, trajectory, - [&](frc::Trajectory::State& state) { - return frc::ChassisSpeeds{state.velocity, 0_mps, + [&](wpi::math::Trajectory::State& state) { + return wpi::math::ChassisSpeeds{state.velocity, 0_mps, state.velocity * state.curvature}; }, - [&](frc::Trajectory::State& state) { return state.pose; }, - initial_pose, {0_m, 0_m, frc::Rotation2d{45_deg}}, 20_ms, 100_ms, + [&](wpi::math::Trajectory::State& state) { return state.pose; }, + initial_pose, {0_m, 0_m, wpi::math::Rotation2d{45_deg}}, 20_ms, 100_ms, 250_ms, false, false); } } @@ -226,53 +226,53 @@ TEST(SwerveDrivePoseEstimatorTest, SimultaneousVisionMeasurements) { // The alternative result is that only one vision measurement affects the // outcome. If that were the case, after 1000 measurements, the estimated // pose would converge to that measurement. - frc::SwerveDriveKinematics<4> kinematics{ - frc::Translation2d{1_m, 1_m}, frc::Translation2d{1_m, -1_m}, - frc::Translation2d{-1_m, -1_m}, frc::Translation2d{-1_m, 1_m}}; + wpi::math::SwerveDriveKinematics<4> kinematics{ + wpi::math::Translation2d{1_m, 1_m}, wpi::math::Translation2d{1_m, -1_m}, + wpi::math::Translation2d{-1_m, -1_m}, wpi::math::Translation2d{-1_m, 1_m}}; - frc::SwerveModulePosition fl; - frc::SwerveModulePosition fr; - frc::SwerveModulePosition bl; - frc::SwerveModulePosition br; + wpi::math::SwerveModulePosition fl; + wpi::math::SwerveModulePosition fr; + wpi::math::SwerveModulePosition bl; + wpi::math::SwerveModulePosition br; - frc::SwerveDrivePoseEstimator<4> estimator{ - kinematics, frc::Rotation2d{}, - {fl, fr, bl, br}, frc::Pose2d{1_m, 2_m, frc::Rotation2d{270_deg}}, + wpi::math::SwerveDrivePoseEstimator<4> estimator{ + kinematics, wpi::math::Rotation2d{}, + {fl, fr, bl, br}, wpi::math::Pose2d{1_m, 2_m, wpi::math::Rotation2d{270_deg}}, {0.1, 0.1, 0.1}, {0.45, 0.45, 0.45}}; - estimator.UpdateWithTime(0_s, frc::Rotation2d{}, {fl, fr, bl, br}); + estimator.UpdateWithTime(0_s, wpi::math::Rotation2d{}, {fl, fr, bl, br}); for (int i = 0; i < 1000; i++) { estimator.AddVisionMeasurement( - frc::Pose2d{0_m, 0_m, frc::Rotation2d{0_deg}}, 0_s); + wpi::math::Pose2d{0_m, 0_m, wpi::math::Rotation2d{0_deg}}, 0_s); estimator.AddVisionMeasurement( - frc::Pose2d{3_m, 1_m, frc::Rotation2d{90_deg}}, 0_s); + wpi::math::Pose2d{3_m, 1_m, wpi::math::Rotation2d{90_deg}}, 0_s); estimator.AddVisionMeasurement( - frc::Pose2d{2_m, 4_m, frc::Rotation2d{180_deg}}, 0_s); + wpi::math::Pose2d{2_m, 4_m, wpi::math::Rotation2d{180_deg}}, 0_s); } { - auto dx = units::math::abs(estimator.GetEstimatedPosition().X() - 0_m); - auto dy = units::math::abs(estimator.GetEstimatedPosition().Y() - 0_m); - auto dtheta = units::math::abs( + auto dx = wpi::units::math::abs(estimator.GetEstimatedPosition().X() - 0_m); + auto dy = wpi::units::math::abs(estimator.GetEstimatedPosition().Y() - 0_m); + auto dtheta = wpi::units::math::abs( estimator.GetEstimatedPosition().Rotation().Radians() - 0_deg); EXPECT_TRUE(dx > 0.08_m || dy > 0.08_m || dtheta > 0.08_rad); } { - auto dx = units::math::abs(estimator.GetEstimatedPosition().X() - 3_m); - auto dy = units::math::abs(estimator.GetEstimatedPosition().Y() - 1_m); - auto dtheta = units::math::abs( + auto dx = wpi::units::math::abs(estimator.GetEstimatedPosition().X() - 3_m); + auto dy = wpi::units::math::abs(estimator.GetEstimatedPosition().Y() - 1_m); + auto dtheta = wpi::units::math::abs( estimator.GetEstimatedPosition().Rotation().Radians() - 90_deg); EXPECT_TRUE(dx > 0.08_m || dy > 0.08_m || dtheta > 0.08_rad); } { - auto dx = units::math::abs(estimator.GetEstimatedPosition().X() - 2_m); - auto dy = units::math::abs(estimator.GetEstimatedPosition().Y() - 4_m); - auto dtheta = units::math::abs( + auto dx = wpi::units::math::abs(estimator.GetEstimatedPosition().X() - 2_m); + auto dy = wpi::units::math::abs(estimator.GetEstimatedPosition().Y() - 4_m); + auto dtheta = wpi::units::math::abs( estimator.GetEstimatedPosition().Rotation().Radians() - 180_deg); EXPECT_TRUE(dx > 0.08_m || dy > 0.08_m || dtheta > 0.08_rad); @@ -280,29 +280,29 @@ TEST(SwerveDrivePoseEstimatorTest, SimultaneousVisionMeasurements) { } TEST(SwerveDrivePoseEstimatorTest, TestDiscardStaleVisionMeasurements) { - frc::SwerveDriveKinematics<4> kinematics{ - frc::Translation2d{1_m, 1_m}, frc::Translation2d{1_m, -1_m}, - frc::Translation2d{-1_m, -1_m}, frc::Translation2d{-1_m, 1_m}}; + wpi::math::SwerveDriveKinematics<4> kinematics{ + wpi::math::Translation2d{1_m, 1_m}, wpi::math::Translation2d{1_m, -1_m}, + wpi::math::Translation2d{-1_m, -1_m}, wpi::math::Translation2d{-1_m, 1_m}}; - frc::SwerveModulePosition fl; - frc::SwerveModulePosition fr; - frc::SwerveModulePosition bl; - frc::SwerveModulePosition br; + wpi::math::SwerveModulePosition fl; + wpi::math::SwerveModulePosition fr; + wpi::math::SwerveModulePosition bl; + wpi::math::SwerveModulePosition br; - frc::SwerveDrivePoseEstimator<4> estimator{ - kinematics, frc::Rotation2d{}, {fl, fr, bl, br}, - frc::Pose2d{}, {0.1, 0.1, 0.1}, {0.45, 0.45, 0.45}}; + wpi::math::SwerveDrivePoseEstimator<4> estimator{ + kinematics, wpi::math::Rotation2d{}, {fl, fr, bl, br}, + wpi::math::Pose2d{}, {0.1, 0.1, 0.1}, {0.45, 0.45, 0.45}}; // Add enough measurements to fill up the buffer for (auto time = 0_s; time < 4_s; time += 20_ms) { - estimator.UpdateWithTime(time, frc::Rotation2d{}, {fl, fr, bl, br}); + estimator.UpdateWithTime(time, wpi::math::Rotation2d{}, {fl, fr, bl, br}); } auto odometryPose = estimator.GetEstimatedPosition(); // Apply a vision measurement from 3 seconds ago estimator.AddVisionMeasurement( - frc::Pose2d{frc::Translation2d{10_m, 10_m}, frc::Rotation2d{0.1_rad}}, + wpi::math::Pose2d{wpi::math::Translation2d{10_m, 10_m}, wpi::math::Rotation2d{0.1_rad}}, 1_s, {0.1, 0.1, 0.1}); EXPECT_NEAR(odometryPose.X().value(), @@ -315,15 +315,15 @@ TEST(SwerveDrivePoseEstimatorTest, TestDiscardStaleVisionMeasurements) { } TEST(SwerveDrivePoseEstimatorTest, TestSampleAt) { - frc::SwerveDriveKinematics<4> kinematics{ - frc::Translation2d{1_m, 1_m}, frc::Translation2d{1_m, -1_m}, - frc::Translation2d{-1_m, -1_m}, frc::Translation2d{-1_m, 1_m}}; - frc::SwerveDrivePoseEstimator estimator{ + wpi::math::SwerveDriveKinematics<4> kinematics{ + wpi::math::Translation2d{1_m, 1_m}, wpi::math::Translation2d{1_m, -1_m}, + wpi::math::Translation2d{-1_m, -1_m}, wpi::math::Translation2d{-1_m, 1_m}}; + wpi::math::SwerveDrivePoseEstimator estimator{ kinematics, - frc::Rotation2d{}, - {frc::SwerveModulePosition{}, frc::SwerveModulePosition{}, - frc::SwerveModulePosition{}, frc::SwerveModulePosition{}}, - frc::Pose2d{}, + wpi::math::Rotation2d{}, + {wpi::math::SwerveModulePosition{}, wpi::math::SwerveModulePosition{}, + wpi::math::SwerveModulePosition{}, wpi::math::SwerveModulePosition{}}, + wpi::math::Pose2d{}, {1.0, 1.0, 1.0}, {1.0, 1.0, 1.0}}; @@ -334,67 +334,67 @@ TEST(SwerveDrivePoseEstimatorTest, TestSampleAt) { // Add a tiny tolerance for the upper bound because of floating point rounding // error for (double time = 1; time <= 2 + 1e-9; time += 0.02) { - wpi::array wheelPositions{ - {frc::SwerveModulePosition{units::meter_t{time}, frc::Rotation2d{}}, - frc::SwerveModulePosition{units::meter_t{time}, frc::Rotation2d{}}, - frc::SwerveModulePosition{units::meter_t{time}, frc::Rotation2d{}}, - frc::SwerveModulePosition{units::meter_t{time}, frc::Rotation2d{}}}}; - estimator.UpdateWithTime(units::second_t{time}, frc::Rotation2d{}, + wpi::util::array wheelPositions{ + {wpi::math::SwerveModulePosition{wpi::units::meter_t{time}, wpi::math::Rotation2d{}}, + wpi::math::SwerveModulePosition{wpi::units::meter_t{time}, wpi::math::Rotation2d{}}, + wpi::math::SwerveModulePosition{wpi::units::meter_t{time}, wpi::math::Rotation2d{}}, + wpi::math::SwerveModulePosition{wpi::units::meter_t{time}, wpi::math::Rotation2d{}}}}; + estimator.UpdateWithTime(wpi::units::second_t{time}, wpi::math::Rotation2d{}, wheelPositions); } // Sample at an added time - EXPECT_EQ(std::optional(frc::Pose2d{1.02_m, 0_m, frc::Rotation2d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose2d{1.02_m, 0_m, wpi::math::Rotation2d{}}), estimator.SampleAt(1.02_s)); // Sample between updates (test interpolation) - EXPECT_EQ(std::optional(frc::Pose2d{1.01_m, 0_m, frc::Rotation2d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose2d{1.01_m, 0_m, wpi::math::Rotation2d{}}), estimator.SampleAt(1.01_s)); // Sampling before the oldest value returns the oldest value - EXPECT_EQ(std::optional(frc::Pose2d{1_m, 0_m, frc::Rotation2d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose2d{1_m, 0_m, wpi::math::Rotation2d{}}), estimator.SampleAt(0.5_s)); // Sampling after the newest value returns the newest value - EXPECT_EQ(std::optional(frc::Pose2d{2_m, 0_m, frc::Rotation2d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose2d{2_m, 0_m, wpi::math::Rotation2d{}}), estimator.SampleAt(2.5_s)); // Add a vision measurement after the odometry measurements (while keeping all // of the old odometry measurements) - estimator.AddVisionMeasurement(frc::Pose2d{2_m, 0_m, frc::Rotation2d{1_rad}}, + estimator.AddVisionMeasurement(wpi::math::Pose2d{2_m, 0_m, wpi::math::Rotation2d{1_rad}}, 2.2_s); // Make sure nothing changed (except the newest value) - EXPECT_EQ(std::optional(frc::Pose2d{1.02_m, 0_m, frc::Rotation2d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose2d{1.02_m, 0_m, wpi::math::Rotation2d{}}), estimator.SampleAt(1.02_s)); - EXPECT_EQ(std::optional(frc::Pose2d{1.01_m, 0_m, frc::Rotation2d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose2d{1.01_m, 0_m, wpi::math::Rotation2d{}}), estimator.SampleAt(1.01_s)); - EXPECT_EQ(std::optional(frc::Pose2d{1_m, 0_m, frc::Rotation2d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose2d{1_m, 0_m, wpi::math::Rotation2d{}}), estimator.SampleAt(0.5_s)); // Add a vision measurement before the odometry measurements that's still in // the buffer - estimator.AddVisionMeasurement(frc::Pose2d{1_m, 0.2_m, frc::Rotation2d{}}, + estimator.AddVisionMeasurement(wpi::math::Pose2d{1_m, 0.2_m, wpi::math::Rotation2d{}}, 0.9_s); // Everything should be the same except Y is 0.1 (halfway between 0 and 0.2) - EXPECT_EQ(std::optional(frc::Pose2d{1.02_m, 0.1_m, frc::Rotation2d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose2d{1.02_m, 0.1_m, wpi::math::Rotation2d{}}), estimator.SampleAt(1.02_s)); - EXPECT_EQ(std::optional(frc::Pose2d{1.01_m, 0.1_m, frc::Rotation2d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose2d{1.01_m, 0.1_m, wpi::math::Rotation2d{}}), estimator.SampleAt(1.01_s)); - EXPECT_EQ(std::optional(frc::Pose2d{1_m, 0.1_m, frc::Rotation2d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose2d{1_m, 0.1_m, wpi::math::Rotation2d{}}), estimator.SampleAt(0.5_s)); - EXPECT_EQ(std::optional(frc::Pose2d{2_m, 0.1_m, frc::Rotation2d{}}), + EXPECT_EQ(std::optional(wpi::math::Pose2d{2_m, 0.1_m, wpi::math::Rotation2d{}}), estimator.SampleAt(2.5_s)); } TEST(SwerveDrivePoseEstimatorTest, TestReset) { - frc::SwerveDriveKinematics<4> kinematics{ - frc::Translation2d{1_m, 1_m}, frc::Translation2d{1_m, -1_m}, - frc::Translation2d{-1_m, -1_m}, frc::Translation2d{-1_m, 1_m}}; - frc::SwerveDrivePoseEstimator estimator{ + wpi::math::SwerveDriveKinematics<4> kinematics{ + wpi::math::Translation2d{1_m, 1_m}, wpi::math::Translation2d{1_m, -1_m}, + wpi::math::Translation2d{-1_m, -1_m}, wpi::math::Translation2d{-1_m, 1_m}}; + wpi::math::SwerveDrivePoseEstimator estimator{ kinematics, - frc::Rotation2d{}, - {frc::SwerveModulePosition{}, frc::SwerveModulePosition{}, - frc::SwerveModulePosition{}, frc::SwerveModulePosition{}}, - frc::Pose2d{-1_m, -1_m, frc::Rotation2d{1_rad}}, + wpi::math::Rotation2d{}, + {wpi::math::SwerveModulePosition{}, wpi::math::SwerveModulePosition{}, + wpi::math::SwerveModulePosition{}, wpi::math::SwerveModulePosition{}}, + wpi::math::Pose2d{-1_m, -1_m, wpi::math::Rotation2d{1_rad}}, {1.0, 1.0, 1.0}, {1.0, 1.0, 1.0}}; @@ -406,11 +406,11 @@ TEST(SwerveDrivePoseEstimatorTest, TestReset) { // Test reset position { - frc::SwerveModulePosition modulePosition{1_m, frc::Rotation2d{}}; + wpi::math::SwerveModulePosition modulePosition{1_m, wpi::math::Rotation2d{}}; estimator.ResetPosition( - frc::Rotation2d{}, + wpi::math::Rotation2d{}, {modulePosition, modulePosition, modulePosition, modulePosition}, - frc::Pose2d{1_m, 0_m, frc::Rotation2d{}}); + wpi::math::Pose2d{1_m, 0_m, wpi::math::Rotation2d{}}); } EXPECT_DOUBLE_EQ(1, estimator.GetEstimatedPosition().X().value()); @@ -420,8 +420,8 @@ TEST(SwerveDrivePoseEstimatorTest, TestReset) { // Test orientation and wheel positions { - frc::SwerveModulePosition modulePosition{2_m, frc::Rotation2d{}}; - estimator.Update(frc::Rotation2d{}, {modulePosition, modulePosition, + wpi::math::SwerveModulePosition modulePosition{2_m, wpi::math::Rotation2d{}}; + estimator.Update(wpi::math::Rotation2d{}, {modulePosition, modulePosition, modulePosition, modulePosition}); } @@ -431,7 +431,7 @@ TEST(SwerveDrivePoseEstimatorTest, TestReset) { 0, estimator.GetEstimatedPosition().Rotation().Radians().value()); // Test reset rotation - estimator.ResetRotation(frc::Rotation2d{90_deg}); + estimator.ResetRotation(wpi::math::Rotation2d{90_deg}); EXPECT_DOUBLE_EQ(2, estimator.GetEstimatedPosition().X().value()); EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Y().value()); @@ -441,8 +441,8 @@ TEST(SwerveDrivePoseEstimatorTest, TestReset) { // Test orientation { - frc::SwerveModulePosition modulePosition{3_m, frc::Rotation2d{}}; - estimator.Update(frc::Rotation2d{}, {modulePosition, modulePosition, + wpi::math::SwerveModulePosition modulePosition{3_m, wpi::math::Rotation2d{}}; + estimator.Update(wpi::math::Rotation2d{}, {modulePosition, modulePosition, modulePosition, modulePosition}); } @@ -453,7 +453,7 @@ TEST(SwerveDrivePoseEstimatorTest, TestReset) { estimator.GetEstimatedPosition().Rotation().Radians().value()); // Test reset translation - estimator.ResetTranslation(frc::Translation2d{-1_m, -1_m}); + estimator.ResetTranslation(wpi::math::Translation2d{-1_m, -1_m}); EXPECT_DOUBLE_EQ(-1, estimator.GetEstimatedPosition().X().value()); EXPECT_DOUBLE_EQ(-1, estimator.GetEstimatedPosition().Y().value()); @@ -462,7 +462,7 @@ TEST(SwerveDrivePoseEstimatorTest, TestReset) { estimator.GetEstimatedPosition().Rotation().Radians().value()); // Test reset pose - estimator.ResetPose(frc::Pose2d{}); + estimator.ResetPose(wpi::math::Pose2d{}); EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().X().value()); EXPECT_DOUBLE_EQ(0, estimator.GetEstimatedPosition().Y().value()); diff --git a/wpimath/src/test/native/cpp/filter/DebouncerTest.cpp b/wpimath/src/test/native/cpp/filter/DebouncerTest.cpp index fe6dbfdd85..29e5403b99 100644 --- a/wpimath/src/test/native/cpp/filter/DebouncerTest.cpp +++ b/wpimath/src/test/native/cpp/filter/DebouncerTest.cpp @@ -8,19 +8,19 @@ #include "wpi/units/time.hpp" #include "wpi/util/timestamp.h" -static units::second_t now = 0_s; +static wpi::units::second_t now = 0_s; class DebouncerTest : public ::testing::Test { protected: void SetUp() override { - WPI_SetNowImpl([] { return units::microsecond_t{now}.to(); }); + WPI_SetNowImpl([] { return wpi::units::microsecond_t{now}.to(); }); } void TearDown() override { WPI_SetNowImpl(nullptr); } }; TEST_F(DebouncerTest, DebounceRising) { - frc::Debouncer debouncer{20_ms}; + wpi::math::Debouncer debouncer{20_ms}; debouncer.Calculate(false); EXPECT_FALSE(debouncer.Calculate(true)); @@ -31,7 +31,7 @@ TEST_F(DebouncerTest, DebounceRising) { } TEST_F(DebouncerTest, DebounceFalling) { - frc::Debouncer debouncer{20_ms, frc::Debouncer::DebounceType::kFalling}; + wpi::math::Debouncer debouncer{20_ms, wpi::math::Debouncer::DebounceType::kFalling}; debouncer.Calculate(true); EXPECT_TRUE(debouncer.Calculate(false)); @@ -42,7 +42,7 @@ TEST_F(DebouncerTest, DebounceFalling) { } TEST_F(DebouncerTest, DebounceBoth) { - frc::Debouncer debouncer{20_ms, frc::Debouncer::DebounceType::kBoth}; + wpi::math::Debouncer debouncer{20_ms, wpi::math::Debouncer::DebounceType::kBoth}; debouncer.Calculate(false); EXPECT_FALSE(debouncer.Calculate(true)); @@ -58,20 +58,20 @@ TEST_F(DebouncerTest, DebounceBoth) { } TEST_F(DebouncerTest, DebounceParams) { - frc::Debouncer debouncer{20_ms, frc::Debouncer::DebounceType::kBoth}; + wpi::math::Debouncer debouncer{20_ms, wpi::math::Debouncer::DebounceType::kBoth}; EXPECT_TRUE(debouncer.GetDebounceTime() == 20_ms); EXPECT_TRUE(debouncer.GetDebounceType() == - frc::Debouncer::DebounceType::kBoth); + wpi::math::Debouncer::DebounceType::kBoth); debouncer.SetDebounceTime(100_ms); EXPECT_TRUE(debouncer.GetDebounceTime() == 100_ms); - debouncer.SetDebounceType(frc::Debouncer::DebounceType::kFalling); + debouncer.SetDebounceType(wpi::math::Debouncer::DebounceType::kFalling); EXPECT_TRUE(debouncer.GetDebounceType() == - frc::Debouncer::DebounceType::kFalling); + wpi::math::Debouncer::DebounceType::kFalling); EXPECT_TRUE(debouncer.Calculate(false)); } diff --git a/wpimath/src/test/native/cpp/filter/LinearFilterNoiseTest.cpp b/wpimath/src/test/native/cpp/filter/LinearFilterNoiseTest.cpp index aaf250edc0..192d62f01d 100644 --- a/wpimath/src/test/native/cpp/filter/LinearFilterNoiseTest.cpp +++ b/wpimath/src/test/native/cpp/filter/LinearFilterNoiseTest.cpp @@ -27,14 +27,14 @@ static double GetData(double t) { class LinearFilterNoiseTest : public testing::TestWithParam { protected: - frc::LinearFilter m_filter = [=] { + wpi::math::LinearFilter m_filter = [=] { switch (GetParam()) { case kTestSinglePoleIIR: - return frc::LinearFilter::SinglePoleIIR( + return wpi::math::LinearFilter::SinglePoleIIR( kSinglePoleIIRTimeConstant, kFilterStep); break; default: - return frc::LinearFilter::MovingAverage(kMovAvgTaps); + return wpi::math::LinearFilter::MovingAverage(kMovAvgTaps); break; } }(); diff --git a/wpimath/src/test/native/cpp/filter/LinearFilterOutputTest.cpp b/wpimath/src/test/native/cpp/filter/LinearFilterOutputTest.cpp index 13cd3890f2..32e0cc4f9f 100644 --- a/wpimath/src/test/native/cpp/filter/LinearFilterOutputTest.cpp +++ b/wpimath/src/test/native/cpp/filter/LinearFilterOutputTest.cpp @@ -51,21 +51,21 @@ static double GetPulseData(double t) { class LinearFilterOutputTest : public testing::TestWithParam { protected: - frc::LinearFilter m_filter = [=] { + wpi::math::LinearFilter m_filter = [=] { switch (GetParam()) { case kTestSinglePoleIIR: - return frc::LinearFilter::SinglePoleIIR( + return wpi::math::LinearFilter::SinglePoleIIR( kSinglePoleIIRTimeConstant, kFilterStep); break; case kTestHighPass: - return frc::LinearFilter::HighPass(kHighPassTimeConstant, + return wpi::math::LinearFilter::HighPass(kHighPassTimeConstant, kFilterStep); break; case kTestMovAvg: - return frc::LinearFilter::MovingAverage(kMovAvgTaps); + return wpi::math::LinearFilter::MovingAverage(kMovAvgTaps); break; default: - return frc::LinearFilter::MovingAverage(kMovAvgTaps); + return wpi::math::LinearFilter::MovingAverage(kMovAvgTaps); break; } }(); @@ -121,18 +121,18 @@ INSTANTIATE_TEST_SUITE_P(Tests, LinearFilterOutputTest, kTestMovAvg, kTestPulse)); template -void AssertCentralResults(F&& f, DfDx&& dfdx, units::second_t h, double min, +void AssertCentralResults(F&& f, DfDx&& dfdx, wpi::units::second_t h, double min, double max) { static_assert(Samples % 2 != 0, "Number of samples must be odd."); // Generate stencil points from -(samples - 1)/2 to (samples - 1)/2 - wpi::array stencil{wpi::empty_array}; + wpi::util::array stencil{wpi::util::empty_array}; for (int i = 0; i < Samples; ++i) { stencil[i] = -(Samples - 1) / 2 + i; } auto filter = - frc::LinearFilter::FiniteDifference(stencil, + wpi::math::LinearFilter::FiniteDifference(stencil, h); for (int i = min / h.value(); i < max / h.value(); ++i) { @@ -153,10 +153,10 @@ void AssertCentralResults(F&& f, DfDx&& dfdx, units::second_t h, double min, } template -void AssertBackwardResults(F&& f, DfDx&& dfdx, units::second_t h, double min, +void AssertBackwardResults(F&& f, DfDx&& dfdx, wpi::units::second_t h, double min, double max) { auto filter = - frc::LinearFilter::BackwardFiniteDifference( + wpi::math::LinearFilter::BackwardFiniteDifference( h); for (int i = min / h.value(); i < max / h.value(); ++i) { diff --git a/wpimath/src/test/native/cpp/filter/MedianFilterTest.cpp b/wpimath/src/test/native/cpp/filter/MedianFilterTest.cpp index c341d8b8b1..6718e76429 100644 --- a/wpimath/src/test/native/cpp/filter/MedianFilterTest.cpp +++ b/wpimath/src/test/native/cpp/filter/MedianFilterTest.cpp @@ -7,7 +7,7 @@ #include "wpi/math/filter/MedianFilter.hpp" TEST(MedianFilterTest, MedianFilterNotFullTestEven) { - frc::MedianFilter filter{10}; + wpi::math::MedianFilter filter{10}; filter.Calculate(3); filter.Calculate(0); @@ -17,7 +17,7 @@ TEST(MedianFilterTest, MedianFilterNotFullTestEven) { } TEST(MedianFilterTest, MedianFilterNotFullTestOdd) { - frc::MedianFilter filter{10}; + wpi::math::MedianFilter filter{10}; filter.Calculate(3); filter.Calculate(0); @@ -28,7 +28,7 @@ TEST(MedianFilterTest, MedianFilterNotFullTestOdd) { } TEST(MedianFilterTest, MedianFilterFullTestEven) { - frc::MedianFilter filter{6}; + wpi::math::MedianFilter filter{6}; filter.Calculate(3); filter.Calculate(0); @@ -41,7 +41,7 @@ TEST(MedianFilterTest, MedianFilterFullTestEven) { } TEST(MedianFilterTest, MedianFilterFullTestOdd) { - frc::MedianFilter filter{5}; + wpi::math::MedianFilter filter{5}; filter.Calculate(3); filter.Calculate(0); diff --git a/wpimath/src/test/native/cpp/filter/SlewRateLimiterTest.cpp b/wpimath/src/test/native/cpp/filter/SlewRateLimiterTest.cpp index 7220855f4f..9c94fbb720 100644 --- a/wpimath/src/test/native/cpp/filter/SlewRateLimiterTest.cpp +++ b/wpimath/src/test/native/cpp/filter/SlewRateLimiterTest.cpp @@ -10,21 +10,21 @@ #include "wpi/units/velocity.hpp" #include "wpi/util/timestamp.h" -static units::second_t now = 0_s; +static wpi::units::second_t now = 0_s; class SlewRateLimiterTest : public ::testing::Test { protected: void SetUp() override { - WPI_SetNowImpl([] { return units::microsecond_t{now}.to(); }); + WPI_SetNowImpl([] { return wpi::units::microsecond_t{now}.to(); }); } void TearDown() override { WPI_SetNowImpl(nullptr); } }; TEST_F(SlewRateLimiterTest, SlewRateLimit) { - WPI_SetNowImpl([] { return units::microsecond_t{now}.to(); }); + WPI_SetNowImpl([] { return wpi::units::microsecond_t{now}.to(); }); - frc::SlewRateLimiter limiter(1_mps); + wpi::math::SlewRateLimiter limiter(1_mps); now += 1_s; @@ -32,7 +32,7 @@ TEST_F(SlewRateLimiterTest, SlewRateLimit) { } TEST_F(SlewRateLimiterTest, SlewRateNoLimit) { - frc::SlewRateLimiter limiter(1_mps); + wpi::math::SlewRateLimiter limiter(1_mps); now += 1_s; @@ -40,7 +40,7 @@ TEST_F(SlewRateLimiterTest, SlewRateNoLimit) { } TEST_F(SlewRateLimiterTest, SlewRatePositiveNegativeLimit) { - frc::SlewRateLimiter limiter(1_mps, -0.5_mps); + wpi::math::SlewRateLimiter limiter(1_mps, -0.5_mps); now += 1_s; diff --git a/wpimath/src/test/native/cpp/geometry/CoordinateSystemTest.cpp b/wpimath/src/test/native/cpp/geometry/CoordinateSystemTest.cpp index e326f50de8..13aaf8a4e2 100644 --- a/wpimath/src/test/native/cpp/geometry/CoordinateSystemTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/CoordinateSystemTest.cpp @@ -8,7 +8,7 @@ #include "wpi/math/geometry/Pose3d.hpp" #include "wpi/math/geometry/Transform3d.hpp" -using namespace frc; +using namespace wpi::math; void CheckPose3dConvert(const Pose3d& poseFrom, const Pose3d& poseTo, const CoordinateSystem& coordFrom, diff --git a/wpimath/src/test/native/cpp/geometry/Ellipse2dTest.cpp b/wpimath/src/test/native/cpp/geometry/Ellipse2dTest.cpp index bda14d8623..57db84452f 100644 --- a/wpimath/src/test/native/cpp/geometry/Ellipse2dTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/Ellipse2dTest.cpp @@ -7,32 +7,32 @@ #include "wpi/math/geometry/Ellipse2d.hpp" TEST(Ellipse2dTest, FocalPoints) { - constexpr frc::Pose2d center{1_m, 2_m, 0_deg}; - constexpr frc::Ellipse2d ellipse{center, 5_m, 4_m}; + constexpr wpi::math::Pose2d center{1_m, 2_m, 0_deg}; + constexpr wpi::math::Ellipse2d ellipse{center, 5_m, 4_m}; const auto [a, b] = ellipse.FocalPoints(); - EXPECT_EQ(frc::Translation2d(-2_m, 2_m), a); - EXPECT_EQ(frc::Translation2d(4_m, 2_m), b); + EXPECT_EQ(wpi::math::Translation2d(-2_m, 2_m), a); + EXPECT_EQ(wpi::math::Translation2d(4_m, 2_m), b); } TEST(Ellipse2dTest, Intersects) { - constexpr frc::Pose2d center{1_m, 2_m, 0_deg}; - constexpr frc::Ellipse2d ellipse{center, 2_m, 1_m}; + constexpr wpi::math::Pose2d center{1_m, 2_m, 0_deg}; + constexpr wpi::math::Ellipse2d ellipse{center, 2_m, 1_m}; - constexpr frc::Translation2d pointA{1_m, 3_m}; - constexpr frc::Translation2d pointB{0_m, 3_m}; + constexpr wpi::math::Translation2d pointA{1_m, 3_m}; + constexpr wpi::math::Translation2d pointB{0_m, 3_m}; EXPECT_TRUE(ellipse.Intersects(pointA)); EXPECT_FALSE(ellipse.Intersects(pointB)); } TEST(Ellipse2dTest, Contains) { - constexpr frc::Pose2d center{-1_m, -2_m, 45_deg}; - constexpr frc::Ellipse2d ellipse{center, 2_m, 1_m}; + constexpr wpi::math::Pose2d center{-1_m, -2_m, 45_deg}; + constexpr wpi::math::Ellipse2d ellipse{center, 2_m, 1_m}; - constexpr frc::Translation2d pointA{0_m, -1_m}; - constexpr frc::Translation2d pointB{0.5_m, -2_m}; + constexpr wpi::math::Translation2d pointA{0_m, -1_m}; + constexpr wpi::math::Translation2d pointB{0.5_m, -2_m}; EXPECT_TRUE(ellipse.Contains(pointA)); EXPECT_FALSE(ellipse.Contains(pointB)); @@ -41,58 +41,58 @@ TEST(Ellipse2dTest, Contains) { TEST(Ellipse2dTest, Distance) { constexpr double kEpsilon = 1E-9; - constexpr frc::Pose2d center{1_m, 2_m, 270_deg}; - constexpr frc::Ellipse2d ellipse{center, 1_m, 2_m}; + constexpr wpi::math::Pose2d center{1_m, 2_m, 270_deg}; + constexpr wpi::math::Ellipse2d ellipse{center, 1_m, 2_m}; - constexpr frc::Translation2d point1{2.5_m, 2_m}; + constexpr wpi::math::Translation2d point1{2.5_m, 2_m}; EXPECT_NEAR(0, ellipse.Distance(point1).value(), kEpsilon); - constexpr frc::Translation2d point2{1_m, 2_m}; + constexpr wpi::math::Translation2d point2{1_m, 2_m}; EXPECT_NEAR(0, ellipse.Distance(point2).value(), kEpsilon); - constexpr frc::Translation2d point3{1_m, 1_m}; + constexpr wpi::math::Translation2d point3{1_m, 1_m}; EXPECT_NEAR(0, ellipse.Distance(point3).value(), kEpsilon); - constexpr frc::Translation2d point4{-1_m, 2.5_m}; + constexpr wpi::math::Translation2d point4{-1_m, 2.5_m}; EXPECT_NEAR(0.19210128384806818, ellipse.Distance(point4).value(), kEpsilon); } TEST(Ellipse2dTest, Nearest) { constexpr double kEpsilon = 1E-9; - constexpr frc::Pose2d center{1_m, 2_m, 270_deg}; - constexpr frc::Ellipse2d ellipse{center, 1_m, 2_m}; + constexpr wpi::math::Pose2d center{1_m, 2_m, 270_deg}; + constexpr wpi::math::Ellipse2d ellipse{center, 1_m, 2_m}; - constexpr frc::Translation2d point1{2.5_m, 2_m}; + constexpr wpi::math::Translation2d point1{2.5_m, 2_m}; auto nearestPoint1 = ellipse.Nearest(point1); EXPECT_NEAR(2.5, nearestPoint1.X().value(), kEpsilon); EXPECT_NEAR(2.0, nearestPoint1.Y().value(), kEpsilon); - constexpr frc::Translation2d point2{1_m, 2_m}; + constexpr wpi::math::Translation2d point2{1_m, 2_m}; auto nearestPoint2 = ellipse.Nearest(point2); EXPECT_NEAR(1.0, nearestPoint2.X().value(), kEpsilon); EXPECT_NEAR(2.0, nearestPoint2.Y().value(), kEpsilon); - constexpr frc::Translation2d point3{1_m, 1_m}; + constexpr wpi::math::Translation2d point3{1_m, 1_m}; auto nearestPoint3 = ellipse.Nearest(point3); EXPECT_NEAR(1.0, nearestPoint3.X().value(), kEpsilon); EXPECT_NEAR(1.0, nearestPoint3.Y().value(), kEpsilon); - constexpr frc::Translation2d point4{-1_m, 2.5_m}; + constexpr wpi::math::Translation2d point4{-1_m, 2.5_m}; auto nearestPoint4 = ellipse.Nearest(point4); EXPECT_NEAR(-0.8512799937611617, nearestPoint4.X().value(), kEpsilon); EXPECT_NEAR(2.378405333174535, nearestPoint4.Y().value(), kEpsilon); } TEST(Ellipse2dTest, Equals) { - constexpr frc::Pose2d center1{1_m, 2_m, 90_deg}; - constexpr frc::Ellipse2d ellipse1{center1, 2_m, 3_m}; + constexpr wpi::math::Pose2d center1{1_m, 2_m, 90_deg}; + constexpr wpi::math::Ellipse2d ellipse1{center1, 2_m, 3_m}; - constexpr frc::Pose2d center2{1_m, 2_m, 90_deg}; - constexpr frc::Ellipse2d ellipse2{center2, 2_m, 3_m}; + constexpr wpi::math::Pose2d center2{1_m, 2_m, 90_deg}; + constexpr wpi::math::Ellipse2d ellipse2{center2, 2_m, 3_m}; - constexpr frc::Pose2d center3{1_m, 2_m, 90_deg}; - constexpr frc::Ellipse2d ellipse3{center3, 3_m, 2_m}; + constexpr wpi::math::Pose2d center3{1_m, 2_m, 90_deg}; + constexpr wpi::math::Ellipse2d ellipse3{center3, 3_m, 2_m}; EXPECT_EQ(ellipse1, ellipse2); EXPECT_NE(ellipse1, ellipse3); diff --git a/wpimath/src/test/native/cpp/geometry/Pose2dTest.cpp b/wpimath/src/test/native/cpp/geometry/Pose2dTest.cpp index e7402d9c1e..da60baa3b0 100644 --- a/wpimath/src/test/native/cpp/geometry/Pose2dTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/Pose2dTest.cpp @@ -9,7 +9,7 @@ #include "wpi/math/geometry/Pose2d.hpp" -using namespace frc; +using namespace wpi::math; TEST(Pose2dTest, RotateBy) { constexpr auto x = 1_m; diff --git a/wpimath/src/test/native/cpp/geometry/Pose3dTest.cpp b/wpimath/src/test/native/cpp/geometry/Pose3dTest.cpp index 01ddbd456b..13bb08e3f9 100644 --- a/wpimath/src/test/native/cpp/geometry/Pose3dTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/Pose3dTest.cpp @@ -9,14 +9,14 @@ #include "wpi/math/geometry/Pose3d.hpp" #include "wpi/util/array.hpp" -using namespace frc; +using namespace wpi::math; TEST(Pose3dTest, RotateBy) { constexpr auto x = 1_m; constexpr auto y = 2_m; const Pose3d initial{x, y, 0_m, Rotation3d{0_deg, 0_deg, 45_deg}}; - constexpr units::radian_t yaw = 5_deg; + constexpr wpi::units::radian_t yaw = 5_deg; const Rotation3d rotation{0_deg, 0_deg, yaw}; const auto rotated = initial.RotateBy(rotation); @@ -67,7 +67,7 @@ TEST(Pose3dTest, TransformBy) { EXPECT_DOUBLE_EQ(1.0 + 5.0 / std::sqrt(2.0), transformed.X().value()); EXPECT_DOUBLE_EQ(2.0 + 5.0 / std::sqrt(2.0), transformed.Y().value()); EXPECT_DOUBLE_EQ(transformed.Rotation().Z().value(), - units::radian_t{50_deg}.value()); + wpi::units::radian_t{50_deg}.value()); } TEST(Pose3dTest, RelativeTo) { @@ -92,7 +92,7 @@ TEST(Pose3dTest, RotateAround) { EXPECT_NEAR(-5.0, rotated.X().value(), 1e-9); EXPECT_NEAR(0.0, rotated.Y().value(), 1e-9); - EXPECT_NEAR(units::radian_t{180_deg}.value(), rotated.Rotation().Z().value(), + EXPECT_NEAR(wpi::units::radian_t{180_deg}.value(), rotated.Rotation().Z().value(), 1e-9); } @@ -140,7 +140,7 @@ TEST(Pose3dTest, ToPose2d) { } TEST(Pose3dTest, ComplexTwists) { - wpi::array initial_poses{ + wpi::util::array initial_poses{ Pose3d{0.698303_m, -0.959096_m, 0.271076_m, Rotation3d{Quaternion{0.86403, -0.076866, 0.147234, 0.475254}}}, Pose3d{0.634892_m, -0.765209_m, 0.117543_m, @@ -153,7 +153,7 @@ TEST(Pose3dTest, ComplexTwists) { Rotation3d{Quaternion{0.807886, 0.029298, 0.257788, 0.529157}}}, }; - wpi::array final_poses{ + wpi::util::array final_poses{ Pose3d{-0.230448_m, -0.511957_m, 0.198406_m, Rotation3d{Quaternion{0.753984, 0.347016, 0.409105, 0.379106}}}, Pose3d{-0.088932_m, -0.343253_m, 0.095018_m, @@ -190,7 +190,7 @@ TEST(Pose3dTest, ComplexTwists) { } TEST(Pose3dTest, TwistNaN) { - wpi::array initial_poses{ + wpi::util::array initial_poses{ Pose3d{6.32_m, 4.12_m, 0.00_m, Rotation3d{Quaternion{-0.9999999999999999, 0.0, 0.0, 1.9208309264993548E-8}}}, @@ -199,7 +199,7 @@ TEST(Pose3dTest, TwistNaN) { 2.0352360299846772E-7}}}, }; - wpi::array final_poses{ + wpi::util::array final_poses{ Pose3d{6.33_m, 4.15_m, 0.00_m, Rotation3d{Quaternion{-0.9999999999999999, 0.0, 0.0, 2.416890209039172E-8}}}, diff --git a/wpimath/src/test/native/cpp/geometry/QuaternionTest.cpp b/wpimath/src/test/native/cpp/geometry/QuaternionTest.cpp index 0291407bf2..491b61758c 100644 --- a/wpimath/src/test/native/cpp/geometry/QuaternionTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/QuaternionTest.cpp @@ -10,7 +10,7 @@ #include "wpi/units/angle.hpp" #include "wpi/units/math.hpp" -using namespace frc; +using namespace wpi::math; TEST(QuaternionTest, Init) { // Identity @@ -94,8 +94,8 @@ TEST(QuaternionTest, ScalarDivision) { TEST(QuaternionTest, Multiply) { // 90° CCW rotations around each axis - double c = units::math::cos(90_deg / 2.0); - double s = units::math::sin(90_deg / 2.0); + double c = wpi::units::math::cos(90_deg / 2.0); + double s = wpi::units::math::sin(90_deg / 2.0); Quaternion xRot{c, s, 0.0, 0.0}; Quaternion yRot{c, 0.0, s, 0.0}; Quaternion zRot{c, 0.0, 0.0, s}; diff --git a/wpimath/src/test/native/cpp/geometry/Rectangle2dTest.cpp b/wpimath/src/test/native/cpp/geometry/Rectangle2dTest.cpp index af15a23f94..e74ce4fa48 100644 --- a/wpimath/src/test/native/cpp/geometry/Rectangle2dTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/Rectangle2dTest.cpp @@ -7,10 +7,10 @@ #include "wpi/math/geometry/Rectangle2d.hpp" TEST(Rectangle2dTest, NewWithCorners) { - constexpr frc::Translation2d cornerA{1_m, 2_m}; - constexpr frc::Translation2d cornerB{4_m, 6_m}; + constexpr wpi::math::Translation2d cornerA{1_m, 2_m}; + constexpr wpi::math::Translation2d cornerB{4_m, 6_m}; - frc::Rectangle2d rect{cornerA, cornerB}; + wpi::math::Rectangle2d rect{cornerA, cornerB}; EXPECT_EQ(3.0, rect.XWidth().value()); EXPECT_EQ(4.0, rect.YWidth().value()); @@ -19,69 +19,69 @@ TEST(Rectangle2dTest, NewWithCorners) { } TEST(Rectangle2dTest, Intersects) { - constexpr frc::Pose2d center{4_m, 3_m, 90_deg}; - constexpr frc::Rectangle2d rect{center, 2_m, 3_m}; + constexpr wpi::math::Pose2d center{4_m, 3_m, 90_deg}; + constexpr wpi::math::Rectangle2d rect{center, 2_m, 3_m}; - EXPECT_TRUE(rect.Intersects(frc::Translation2d{5.5_m, 4_m})); - EXPECT_TRUE(rect.Intersects(frc::Translation2d{3_m, 2_m})); - EXPECT_FALSE(rect.Intersects(frc::Translation2d{4_m, 1.5_m})); - EXPECT_FALSE(rect.Intersects(frc::Translation2d{4_m, 3.5_m})); + EXPECT_TRUE(rect.Intersects(wpi::math::Translation2d{5.5_m, 4_m})); + EXPECT_TRUE(rect.Intersects(wpi::math::Translation2d{3_m, 2_m})); + EXPECT_FALSE(rect.Intersects(wpi::math::Translation2d{4_m, 1.5_m})); + EXPECT_FALSE(rect.Intersects(wpi::math::Translation2d{4_m, 3.5_m})); } TEST(Rectangle2dTest, Contains) { - constexpr frc::Pose2d center{2_m, 3_m, 45_deg}; - constexpr frc::Rectangle2d rect{center, 3_m, 1_m}; + constexpr wpi::math::Pose2d center{2_m, 3_m, 45_deg}; + constexpr wpi::math::Rectangle2d rect{center, 3_m, 1_m}; - EXPECT_TRUE(rect.Contains(frc::Translation2d{2_m, 3_m})); - EXPECT_TRUE(rect.Contains(frc::Translation2d{3_m, 4_m})); - EXPECT_FALSE(rect.Contains(frc::Translation2d{3_m, 3_m})); + EXPECT_TRUE(rect.Contains(wpi::math::Translation2d{2_m, 3_m})); + EXPECT_TRUE(rect.Contains(wpi::math::Translation2d{3_m, 4_m})); + EXPECT_FALSE(rect.Contains(wpi::math::Translation2d{3_m, 3_m})); } TEST(Rectangle2dTest, Distance) { constexpr double kEpsilon = 1E-9; - constexpr frc::Pose2d center{1_m, 2_m, 270_deg}; - constexpr frc::Rectangle2d rect{center, 1_m, 2_m}; + constexpr wpi::math::Pose2d center{1_m, 2_m, 270_deg}; + constexpr wpi::math::Rectangle2d rect{center, 1_m, 2_m}; - constexpr frc::Translation2d point1{2.5_m, 2_m}; + constexpr wpi::math::Translation2d point1{2.5_m, 2_m}; EXPECT_NEAR(0.5, rect.Distance(point1).value(), kEpsilon); - constexpr frc::Translation2d point2{1_m, 2_m}; + constexpr wpi::math::Translation2d point2{1_m, 2_m}; EXPECT_NEAR(0, rect.Distance(point2).value(), kEpsilon); - constexpr frc::Translation2d point3{1_m, 1_m}; + constexpr wpi::math::Translation2d point3{1_m, 1_m}; EXPECT_NEAR(0.5, rect.Distance(point3).value(), kEpsilon); - constexpr frc::Translation2d point4{-1_m, 2.5_m}; + constexpr wpi::math::Translation2d point4{-1_m, 2.5_m}; EXPECT_NEAR(1, rect.Distance(point4).value(), kEpsilon); } TEST(Rectangle2dTest, Nearest) { constexpr double kEpsilon = 1E-9; - constexpr frc::Pose2d center{1_m, 1_m, 90_deg}; - constexpr frc::Rectangle2d rect{center, 3_m, 4_m}; + constexpr wpi::math::Pose2d center{1_m, 1_m, 90_deg}; + constexpr wpi::math::Rectangle2d rect{center, 3_m, 4_m}; - constexpr frc::Translation2d point1{1_m, 3_m}; + constexpr wpi::math::Translation2d point1{1_m, 3_m}; auto nearestPoint1 = rect.Nearest(point1); EXPECT_NEAR(1.0, nearestPoint1.X().value(), kEpsilon); EXPECT_NEAR(2.5, nearestPoint1.Y().value(), kEpsilon); - constexpr frc::Translation2d point2{0_m, 0_m}; + constexpr wpi::math::Translation2d point2{0_m, 0_m}; auto nearestPoint2 = rect.Nearest(point2); EXPECT_NEAR(0.0, nearestPoint2.X().value(), kEpsilon); EXPECT_NEAR(0.0, nearestPoint2.Y().value(), kEpsilon); } TEST(Rectangle2dTest, Equals) { - constexpr frc::Pose2d center1{2_m, 3_m, 0_deg}; - constexpr frc::Rectangle2d rect1{center1, 5_m, 3_m}; + constexpr wpi::math::Pose2d center1{2_m, 3_m, 0_deg}; + constexpr wpi::math::Rectangle2d rect1{center1, 5_m, 3_m}; - constexpr frc::Pose2d center2{2_m, 3_m, 0_deg}; - constexpr frc::Rectangle2d rect2{center2, 5_m, 3_m}; + constexpr wpi::math::Pose2d center2{2_m, 3_m, 0_deg}; + constexpr wpi::math::Rectangle2d rect2{center2, 5_m, 3_m}; - constexpr frc::Pose2d center3{2_m, 3_m, 0_deg}; - constexpr frc::Rectangle2d rect3{center3, 3_m, 3_m}; + constexpr wpi::math::Pose2d center3{2_m, 3_m, 0_deg}; + constexpr wpi::math::Rectangle2d rect3{center3, 3_m, 3_m}; EXPECT_EQ(rect1, rect2); EXPECT_NE(rect2, rect3); diff --git a/wpimath/src/test/native/cpp/geometry/Rotation2dTest.cpp b/wpimath/src/test/native/cpp/geometry/Rotation2dTest.cpp index a3c6bb5dfe..133f76ea41 100644 --- a/wpimath/src/test/native/cpp/geometry/Rotation2dTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/Rotation2dTest.cpp @@ -9,11 +9,11 @@ #include "wpi/math/geometry/Rotation2d.hpp" -using namespace frc; +using namespace wpi::math; TEST(Rotation2dTest, RadiansToDegrees) { - const Rotation2d rot1{units::radian_t{std::numbers::pi / 3.0}}; - const Rotation2d rot2{units::radian_t{std::numbers::pi / 4.0}}; + const Rotation2d rot1{wpi::units::radian_t{std::numbers::pi / 3.0}}; + const Rotation2d rot2{wpi::units::radian_t{std::numbers::pi / 4.0}}; EXPECT_DOUBLE_EQ(60.0, rot1.Degrees().value()); EXPECT_DOUBLE_EQ(45.0, rot2.Degrees().value()); diff --git a/wpimath/src/test/native/cpp/geometry/Rotation3dTest.cpp b/wpimath/src/test/native/cpp/geometry/Rotation3dTest.cpp index a8802b4794..d9b4551b1b 100644 --- a/wpimath/src/test/native/cpp/geometry/Rotation3dTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/Rotation3dTest.cpp @@ -11,38 +11,38 @@ #include "wpi/math/geometry/Rotation3d.hpp" #include "wpi/util/MathExtras.hpp" -using namespace frc; +using namespace wpi::math; TEST(Rotation3dTest, GimbalLockAccuracy) { - auto rot1 = Rotation3d{0_rad, 0_rad, units::radian_t{std::numbers::pi / 2}}; - auto rot2 = Rotation3d{units::radian_t{std::numbers::pi}, 0_rad, 0_rad}; - auto rot3 = Rotation3d{-units::radian_t{std::numbers::pi / 2}, 0_rad, 0_rad}; + auto rot1 = Rotation3d{0_rad, 0_rad, wpi::units::radian_t{std::numbers::pi / 2}}; + auto rot2 = Rotation3d{wpi::units::radian_t{std::numbers::pi}, 0_rad, 0_rad}; + auto rot3 = Rotation3d{-wpi::units::radian_t{std::numbers::pi / 2}, 0_rad, 0_rad}; const auto result1 = rot1 + rot2 + rot3; const auto expected1 = - Rotation3d{0_rad, -units::radian_t{std::numbers::pi / 2}, - units::radian_t{std::numbers::pi / 2}}; + Rotation3d{0_rad, -wpi::units::radian_t{std::numbers::pi / 2}, + wpi::units::radian_t{std::numbers::pi / 2}}; EXPECT_EQ(expected1, result1); EXPECT_DOUBLE_EQ(std::numbers::pi / 2, (result1.X() + result1.Z()).value()); EXPECT_NEAR(-std::numbers::pi / 2, result1.Y().value(), 1e-7); - rot1 = Rotation3d{0_rad, 0_rad, units::radian_t{std::numbers::pi / 2}}; - rot2 = Rotation3d{units::radian_t{-std::numbers::pi}, 0_rad, 0_rad}; - rot3 = Rotation3d{units::radian_t{std::numbers::pi / 2}, 0_rad, 0_rad}; + rot1 = Rotation3d{0_rad, 0_rad, wpi::units::radian_t{std::numbers::pi / 2}}; + rot2 = Rotation3d{wpi::units::radian_t{-std::numbers::pi}, 0_rad, 0_rad}; + rot3 = Rotation3d{wpi::units::radian_t{std::numbers::pi / 2}, 0_rad, 0_rad}; const auto result2 = rot1 + rot2 + rot3; const auto expected2 = - Rotation3d{0_rad, units::radian_t{std::numbers::pi / 2}, - units::radian_t{std::numbers::pi / 2}}; + Rotation3d{0_rad, wpi::units::radian_t{std::numbers::pi / 2}, + wpi::units::radian_t{std::numbers::pi / 2}}; EXPECT_EQ(expected2, result2); EXPECT_DOUBLE_EQ(std::numbers::pi / 2, (result2.Z() - result2.X()).value()); EXPECT_NEAR(std::numbers::pi / 2, result2.Y().value(), 1e-7); - rot1 = Rotation3d{0_rad, 0_rad, units::radian_t{std::numbers::pi / 2}}; - rot2 = Rotation3d{0_rad, units::radian_t{std::numbers::pi / 3}, 0_rad}; - rot3 = Rotation3d{-units::radian_t{std::numbers::pi / 2}, 0_rad, 0_rad}; + rot1 = Rotation3d{0_rad, 0_rad, wpi::units::radian_t{std::numbers::pi / 2}}; + rot2 = Rotation3d{0_rad, wpi::units::radian_t{std::numbers::pi / 3}, 0_rad}; + rot3 = Rotation3d{-wpi::units::radian_t{std::numbers::pi / 2}, 0_rad, 0_rad}; const auto result3 = rot1 + rot2 + rot3; const auto expected3 = - Rotation3d{0_rad, units::radian_t{std::numbers::pi / 2}, - units::radian_t{std::numbers::pi / 6}}; + Rotation3d{0_rad, wpi::units::radian_t{std::numbers::pi / 2}, + wpi::units::radian_t{std::numbers::pi / 6}}; EXPECT_EQ(expected3, result3); EXPECT_DOUBLE_EQ(std::numbers::pi / 6, (result3.Z() - result3.X()).value()); EXPECT_DOUBLE_EQ(std::numbers::pi / 2, result3.Y().value()); @@ -50,22 +50,22 @@ TEST(Rotation3dTest, GimbalLockAccuracy) { TEST(Rotation3dTest, InitAxisAngleAndRollPitchYaw) { const Eigen::Vector3d xAxis{1.0, 0.0, 0.0}; - const Rotation3d rot1{xAxis, units::radian_t{std::numbers::pi / 3}}; - const Rotation3d rot2{units::radian_t{std::numbers::pi / 3}, 0_rad, 0_rad}; + const Rotation3d rot1{xAxis, wpi::units::radian_t{std::numbers::pi / 3}}; + const Rotation3d rot2{wpi::units::radian_t{std::numbers::pi / 3}, 0_rad, 0_rad}; const Rotation3d rvec1{Eigen::Vector3d{xAxis * std::numbers::pi / 3}}; EXPECT_EQ(rot1, rot2); EXPECT_EQ(rot1, rvec1); const Eigen::Vector3d yAxis{0.0, 1.0, 0.0}; - const Rotation3d rot3{yAxis, units::radian_t{std::numbers::pi / 3}}; - const Rotation3d rot4{0_rad, units::radian_t{std::numbers::pi / 3}, 0_rad}; + const Rotation3d rot3{yAxis, wpi::units::radian_t{std::numbers::pi / 3}}; + const Rotation3d rot4{0_rad, wpi::units::radian_t{std::numbers::pi / 3}, 0_rad}; const Rotation3d rvec2{Eigen::Vector3d{yAxis * std::numbers::pi / 3}}; EXPECT_EQ(rot3, rot4); EXPECT_EQ(rot3, rvec2); const Eigen::Vector3d zAxis{0.0, 0.0, 1.0}; - const Rotation3d rot5{zAxis, units::radian_t{std::numbers::pi / 3}}; - const Rotation3d rot6{0_rad, 0_rad, units::radian_t{std::numbers::pi / 3}}; + const Rotation3d rot5{zAxis, wpi::units::radian_t{std::numbers::pi / 3}}; + const Rotation3d rot6{0_rad, 0_rad, wpi::units::radian_t{std::numbers::pi / 3}}; const Rotation3d rvec3{Eigen::Vector3d{zAxis * std::numbers::pi / 3}}; EXPECT_EQ(rot5, rot6); EXPECT_EQ(rot5, rvec3); @@ -102,12 +102,12 @@ TEST(Rotation3dTest, InitTwoVector) { // 90 degree CW rotation around y-axis const Rotation3d rot1{xAxis, zAxis}; - const Rotation3d expected1{yAxis, units::radian_t{-std::numbers::pi / 2.0}}; + const Rotation3d expected1{yAxis, wpi::units::radian_t{-std::numbers::pi / 2.0}}; EXPECT_EQ(expected1, rot1); // 45 degree CCW rotation around z-axis const Rotation3d rot2{xAxis, Eigen::Vector3d{1.0, 1.0, 0.0}}; - const Rotation3d expected2{zAxis, units::radian_t{std::numbers::pi / 4.0}}; + const Rotation3d expected2{zAxis, wpi::units::radian_t{std::numbers::pi / 4.0}}; EXPECT_EQ(expected2, rot2); // 0 degree rotation of x-axes @@ -148,15 +148,15 @@ TEST(Rotation3dTest, InitTwoVector) { TEST(Rotation3dTest, RadiansToDegrees) { const Eigen::Vector3d zAxis{0.0, 0.0, 1.0}; - const Rotation3d rot1{zAxis, units::radian_t{std::numbers::pi / 3}}; + const Rotation3d rot1{zAxis, wpi::units::radian_t{std::numbers::pi / 3}}; EXPECT_DOUBLE_EQ(0.0, rot1.X().value()); EXPECT_DOUBLE_EQ(0.0, rot1.Y().value()); - EXPECT_DOUBLE_EQ(units::radian_t{60_deg}.value(), rot1.Z().value()); + EXPECT_DOUBLE_EQ(wpi::units::radian_t{60_deg}.value(), rot1.Z().value()); - const Rotation3d rot2{zAxis, units::radian_t{std::numbers::pi / 4}}; + const Rotation3d rot2{zAxis, wpi::units::radian_t{std::numbers::pi / 4}}; EXPECT_DOUBLE_EQ(0.0, rot2.X().value()); EXPECT_DOUBLE_EQ(0.0, rot2.Y().value()); - EXPECT_DOUBLE_EQ(units::radian_t{45_deg}.value(), rot2.Z().value()); + EXPECT_DOUBLE_EQ(wpi::units::radian_t{45_deg}.value(), rot2.Z().value()); } TEST(Rotation3dTest, DegreesToRadians) { @@ -259,7 +259,7 @@ TEST(Rotation3dTest, Minus) { const auto rot1 = Rotation3d{zAxis, 70_deg}; const auto rot2 = Rotation3d{zAxis, 30_deg}; - EXPECT_DOUBLE_EQ(40.0, units::degree_t{(rot1 - rot2).Z()}.value()); + EXPECT_DOUBLE_EQ(40.0, wpi::units::degree_t{(rot1 - rot2).Z()}.value()); } TEST(Rotation3dTest, AxisAngle) { @@ -327,48 +327,48 @@ TEST(Rotation3dTest, Interpolate) { // 50 + (70 - 50) * 0.5 = 60 auto rot1 = Rotation3d{xAxis, 50_deg}; auto rot2 = Rotation3d{xAxis, 70_deg}; - auto interpolated = wpi::Lerp(rot1, rot2, 0.5); - EXPECT_DOUBLE_EQ(60.0, units::degree_t{interpolated.X()}.value()); - EXPECT_DOUBLE_EQ(0.0, units::degree_t{interpolated.Y()}.value()); - EXPECT_DOUBLE_EQ(0.0, units::degree_t{interpolated.Z()}.value()); + auto interpolated = wpi::util::Lerp(rot1, rot2, 0.5); + EXPECT_DOUBLE_EQ(60.0, wpi::units::degree_t{interpolated.X()}.value()); + EXPECT_DOUBLE_EQ(0.0, wpi::units::degree_t{interpolated.Y()}.value()); + EXPECT_DOUBLE_EQ(0.0, wpi::units::degree_t{interpolated.Z()}.value()); // -160 minus half distance between 170 and -160 (15) = -175 rot1 = Rotation3d{xAxis, 170_deg}; rot2 = Rotation3d{xAxis, -160_deg}; - interpolated = wpi::Lerp(rot1, rot2, 0.5); - EXPECT_DOUBLE_EQ(-175.0, units::degree_t{interpolated.X()}.value()); - EXPECT_DOUBLE_EQ(0.0, units::degree_t{interpolated.Y()}.value()); - EXPECT_DOUBLE_EQ(0.0, units::degree_t{interpolated.Z()}.value()); + interpolated = wpi::util::Lerp(rot1, rot2, 0.5); + EXPECT_DOUBLE_EQ(-175.0, wpi::units::degree_t{interpolated.X()}.value()); + EXPECT_DOUBLE_EQ(0.0, wpi::units::degree_t{interpolated.Y()}.value()); + EXPECT_DOUBLE_EQ(0.0, wpi::units::degree_t{interpolated.Z()}.value()); // 50 + (70 - 50) * 0.5 = 60 rot1 = Rotation3d{yAxis, 50_deg}; rot2 = Rotation3d{yAxis, 70_deg}; - interpolated = wpi::Lerp(rot1, rot2, 0.5); - EXPECT_DOUBLE_EQ(0.0, units::degree_t{interpolated.X()}.value()); - EXPECT_DOUBLE_EQ(60.0, units::degree_t{interpolated.Y()}.value()); - EXPECT_DOUBLE_EQ(0.0, units::degree_t{interpolated.Z()}.value()); + interpolated = wpi::util::Lerp(rot1, rot2, 0.5); + EXPECT_DOUBLE_EQ(0.0, wpi::units::degree_t{interpolated.X()}.value()); + EXPECT_DOUBLE_EQ(60.0, wpi::units::degree_t{interpolated.Y()}.value()); + EXPECT_DOUBLE_EQ(0.0, wpi::units::degree_t{interpolated.Z()}.value()); // -160 plus half distance between 170 and -160 (165) = 5 rot1 = Rotation3d{yAxis, 170_deg}; rot2 = Rotation3d{yAxis, -160_deg}; - interpolated = wpi::Lerp(rot1, rot2, 0.5); - EXPECT_DOUBLE_EQ(180.0, units::degree_t{interpolated.X()}.value()); - EXPECT_DOUBLE_EQ(-5.0, units::degree_t{interpolated.Y()}.value()); - EXPECT_DOUBLE_EQ(180.0, units::degree_t{interpolated.Z()}.value()); + interpolated = wpi::util::Lerp(rot1, rot2, 0.5); + EXPECT_DOUBLE_EQ(180.0, wpi::units::degree_t{interpolated.X()}.value()); + EXPECT_DOUBLE_EQ(-5.0, wpi::units::degree_t{interpolated.Y()}.value()); + EXPECT_DOUBLE_EQ(180.0, wpi::units::degree_t{interpolated.Z()}.value()); // 50 + (70 - 50) * 0.5 = 60 rot1 = Rotation3d{zAxis, 50_deg}; rot2 = Rotation3d{zAxis, 70_deg}; - interpolated = wpi::Lerp(rot1, rot2, 0.5); - EXPECT_DOUBLE_EQ(0.0, units::degree_t{interpolated.X()}.value()); - EXPECT_DOUBLE_EQ(0.0, units::degree_t{interpolated.Y()}.value()); - EXPECT_DOUBLE_EQ(60.0, units::degree_t{interpolated.Z()}.value()); + interpolated = wpi::util::Lerp(rot1, rot2, 0.5); + EXPECT_DOUBLE_EQ(0.0, wpi::units::degree_t{interpolated.X()}.value()); + EXPECT_DOUBLE_EQ(0.0, wpi::units::degree_t{interpolated.Y()}.value()); + EXPECT_DOUBLE_EQ(60.0, wpi::units::degree_t{interpolated.Z()}.value()); // -160 minus half distance between 170 and -160 (15) = -175 rot1 = Rotation3d{zAxis, 170_deg}; rot2 = Rotation3d{zAxis, -160_deg}; - interpolated = wpi::Lerp(rot1, rot2, 0.5); - EXPECT_DOUBLE_EQ(0.0, units::degree_t{interpolated.X()}.value()); - EXPECT_DOUBLE_EQ(0.0, units::degree_t{interpolated.Y()}.value()); - EXPECT_DOUBLE_EQ(-175.0, units::degree_t{interpolated.Z()}.value()); + interpolated = wpi::util::Lerp(rot1, rot2, 0.5); + EXPECT_DOUBLE_EQ(0.0, wpi::units::degree_t{interpolated.X()}.value()); + EXPECT_DOUBLE_EQ(0.0, wpi::units::degree_t{interpolated.Y()}.value()); + EXPECT_DOUBLE_EQ(-175.0, wpi::units::degree_t{interpolated.Z()}.value()); } diff --git a/wpimath/src/test/native/cpp/geometry/Transform2dTest.cpp b/wpimath/src/test/native/cpp/geometry/Transform2dTest.cpp index fb7efd1665..2c2e79a311 100644 --- a/wpimath/src/test/native/cpp/geometry/Transform2dTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/Transform2dTest.cpp @@ -11,7 +11,7 @@ #include "wpi/math/geometry/Transform2d.hpp" #include "wpi/math/geometry/Translation2d.hpp" -using namespace frc; +using namespace wpi::math; TEST(Transform2dTest, ToMatrix) { Transform2d before{1_m, 2_m, 20_deg}; diff --git a/wpimath/src/test/native/cpp/geometry/Transform3dTest.cpp b/wpimath/src/test/native/cpp/geometry/Transform3dTest.cpp index 94c9ce9936..ce6e0d66c4 100644 --- a/wpimath/src/test/native/cpp/geometry/Transform3dTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/Transform3dTest.cpp @@ -11,7 +11,7 @@ #include "wpi/math/geometry/Transform3d.hpp" #include "wpi/math/geometry/Translation3d.hpp" -using namespace frc; +using namespace wpi::math; TEST(Transform3dTest, ToMatrix) { Transform3d before{1_m, 2_m, 3_m, Rotation3d{10_deg, 20_deg, 30_deg}}; diff --git a/wpimath/src/test/native/cpp/geometry/Translation2dTest.cpp b/wpimath/src/test/native/cpp/geometry/Translation2dTest.cpp index f946168364..60814600c6 100644 --- a/wpimath/src/test/native/cpp/geometry/Translation2dTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/Translation2dTest.cpp @@ -8,7 +8,7 @@ #include "wpi/math/geometry/Translation2d.hpp" -using namespace frc; +using namespace wpi::math; TEST(Translation2dTest, Sum) { const Translation2d one{1_m, 3_m}; diff --git a/wpimath/src/test/native/cpp/geometry/Translation3dTest.cpp b/wpimath/src/test/native/cpp/geometry/Translation3dTest.cpp index b7e0a93a6e..76913ac2a1 100644 --- a/wpimath/src/test/native/cpp/geometry/Translation3dTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/Translation3dTest.cpp @@ -8,7 +8,7 @@ #include "wpi/math/geometry/Translation3d.hpp" -using namespace frc; +using namespace wpi::math; static constexpr double kEpsilon = 1E-9; diff --git a/wpimath/src/test/native/cpp/geometry/Twist2dTest.cpp b/wpimath/src/test/native/cpp/geometry/Twist2dTest.cpp index 8068f2a8da..80bc855b95 100644 --- a/wpimath/src/test/native/cpp/geometry/Twist2dTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/Twist2dTest.cpp @@ -9,7 +9,7 @@ #include "wpi/math/geometry/Pose2d.hpp" -using namespace frc; +using namespace wpi::math; TEST(Twist2dTest, Straight) { const Twist2d straight{5_m, 0_m, 0_rad}; @@ -22,7 +22,7 @@ TEST(Twist2dTest, Straight) { TEST(Twist2dTest, QuarterCircle) { const Twist2d quarterCircle{5_m / 2.0 * std::numbers::pi, 0_m, - units::radian_t{std::numbers::pi / 2.0}}; + wpi::units::radian_t{std::numbers::pi / 2.0}}; const auto quarterCirclePose = quarterCircle.Exp(); EXPECT_DOUBLE_EQ(5.0, quarterCirclePose.X().value()); @@ -57,8 +57,8 @@ TEST(Twist2dTest, Pose2dLog) { const auto twist = (end - start).Log(); - Twist2d expected{units::meter_t{5.0 / 2.0 * std::numbers::pi}, 0_m, - units::radian_t{std::numbers::pi / 2.0}}; + Twist2d expected{wpi::units::meter_t{5.0 / 2.0 * std::numbers::pi}, 0_m, + wpi::units::radian_t{std::numbers::pi / 2.0}}; EXPECT_EQ(expected, twist); // Make sure computed twist gives back original end pose diff --git a/wpimath/src/test/native/cpp/geometry/Twist3dTest.cpp b/wpimath/src/test/native/cpp/geometry/Twist3dTest.cpp index d890287552..f67a3ba80e 100644 --- a/wpimath/src/test/native/cpp/geometry/Twist3dTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/Twist3dTest.cpp @@ -9,7 +9,7 @@ #include "wpi/math/geometry/Pose3d.hpp" -using namespace frc; +using namespace wpi::math; TEST(Twist3dTest, StraightX) { const Twist3d straight{5_m, 0_m, 0_m, 0_rad, 0_rad, 0_rad}; @@ -40,7 +40,7 @@ TEST(Twist3dTest, QuarterCircle) { const Twist3d quarterCircle{ 5_m / 2.0 * std::numbers::pi, 0_m, 0_m, 0_rad, 0_rad, - units::radian_t{std::numbers::pi / 2.0}}; + wpi::units::radian_t{std::numbers::pi / 2.0}}; const auto quarterCirclePose = quarterCircle.Exp(); Transform3d expected{5_m, 5_m, 0_m, Rotation3d{zAxis, 90_deg}}; @@ -73,7 +73,7 @@ TEST(Twist3dTest, Pose3dLogX) { const auto twist = (end - start).Log(); - Twist3d expected{0_m, units::meter_t{5.0 / 2.0 * std::numbers::pi}, + Twist3d expected{0_m, wpi::units::meter_t{5.0 / 2.0 * std::numbers::pi}, 0_m, 90_deg, 0_deg, 0_deg}; EXPECT_EQ(expected, twist); @@ -89,7 +89,7 @@ TEST(Twist3dTest, Pose3dLogY) { const auto twist = (end - start).Log(); - Twist3d expected{0_m, 0_m, units::meter_t{5.0 / 2.0 * std::numbers::pi}, + Twist3d expected{0_m, 0_m, wpi::units::meter_t{5.0 / 2.0 * std::numbers::pi}, 0_deg, 90_deg, 0_deg}; EXPECT_EQ(expected, twist); @@ -104,7 +104,7 @@ TEST(Twist3dTest, Pose3dLogZ) { const auto twist = (end - start).Log(); - Twist3d expected{units::meter_t{5.0 / 2.0 * std::numbers::pi}, + Twist3d expected{wpi::units::meter_t{5.0 / 2.0 * std::numbers::pi}, 0_m, 0_m, 0_deg, diff --git a/wpimath/src/test/native/cpp/geometry/proto/Ellipse2dProtoTest.cpp b/wpimath/src/test/native/cpp/geometry/proto/Ellipse2dProtoTest.cpp index 81f16779da..6416474871 100644 --- a/wpimath/src/test/native/cpp/geometry/proto/Ellipse2dProtoTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/proto/Ellipse2dProtoTest.cpp @@ -7,7 +7,7 @@ #include "wpi/math/geometry/Ellipse2d.hpp" #include "wpi/util/SmallVector.hpp" -using namespace frc; +using namespace wpi::math; namespace { @@ -16,8 +16,8 @@ const Ellipse2d kExpectedData{ } // namespace TEST(Ellipse2dProtoTest, Roundtrip) { - wpi::ProtobufMessage message; - wpi::SmallVector buf; + wpi::util::ProtobufMessage message; + wpi::util::SmallVector buf; ASSERT_TRUE(message.Pack(buf, kExpectedData)); auto unpacked_data = message.Unpack(buf); diff --git a/wpimath/src/test/native/cpp/geometry/proto/Pose2dProtoTest.cpp b/wpimath/src/test/native/cpp/geometry/proto/Pose2dProtoTest.cpp index f99a6b3bf3..17239259c0 100644 --- a/wpimath/src/test/native/cpp/geometry/proto/Pose2dProtoTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/proto/Pose2dProtoTest.cpp @@ -7,7 +7,7 @@ #include "wpi/math/geometry/Pose2d.hpp" #include "wpi/util/SmallVector.hpp" -using namespace frc; +using namespace wpi::math; namespace { @@ -16,8 +16,8 @@ const Pose2d kExpectedData = } // namespace TEST(Pose2dProtoTest, Roundtrip) { - wpi::ProtobufMessage message; - wpi::SmallVector buf; + wpi::util::ProtobufMessage message; + wpi::util::SmallVector buf; ASSERT_TRUE(message.Pack(buf, kExpectedData)); auto unpacked_data = message.Unpack(buf); diff --git a/wpimath/src/test/native/cpp/geometry/proto/Pose3dProtoTest.cpp b/wpimath/src/test/native/cpp/geometry/proto/Pose3dProtoTest.cpp index 2c7a0d94a6..96cd69cbe6 100644 --- a/wpimath/src/test/native/cpp/geometry/proto/Pose3dProtoTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/proto/Pose3dProtoTest.cpp @@ -7,7 +7,7 @@ #include "wpi/math/geometry/Pose3d.hpp" #include "wpi/util/SmallVector.hpp" -using namespace frc; +using namespace wpi::math; namespace { @@ -17,8 +17,8 @@ const Pose3d kExpectedData = } // namespace TEST(Pose3dProtoTest, Roundtrip) { - wpi::ProtobufMessage message; - wpi::SmallVector buf; + wpi::util::ProtobufMessage message; + wpi::util::SmallVector buf; ASSERT_TRUE(message.Pack(buf, kExpectedData)); auto unpacked_data = message.Unpack(buf); diff --git a/wpimath/src/test/native/cpp/geometry/proto/QuaternionProtoTest.cpp b/wpimath/src/test/native/cpp/geometry/proto/QuaternionProtoTest.cpp index fc0b972e05..11a802f1f7 100644 --- a/wpimath/src/test/native/cpp/geometry/proto/QuaternionProtoTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/proto/QuaternionProtoTest.cpp @@ -7,7 +7,7 @@ #include "wpi/math/geometry/Quaternion.hpp" #include "wpi/util/SmallVector.hpp" -using namespace frc; +using namespace wpi::math; namespace { @@ -15,8 +15,8 @@ const Quaternion kExpectedData = Quaternion{1.1, 0.191, 35.04, 19.1}; } // namespace TEST(QuaternionProtoTest, Roundtrip) { - wpi::ProtobufMessage message; - wpi::SmallVector buf; + wpi::util::ProtobufMessage message; + wpi::util::SmallVector buf; ASSERT_TRUE(message.Pack(buf, kExpectedData)); auto unpacked_data = message.Unpack(buf); diff --git a/wpimath/src/test/native/cpp/geometry/proto/Rectangle2dProtoTest.cpp b/wpimath/src/test/native/cpp/geometry/proto/Rectangle2dProtoTest.cpp index 45e111dadc..c8062ca043 100644 --- a/wpimath/src/test/native/cpp/geometry/proto/Rectangle2dProtoTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/proto/Rectangle2dProtoTest.cpp @@ -7,7 +7,7 @@ #include "wpi/math/geometry/Rectangle2d.hpp" #include "wpi/util/SmallVector.hpp" -using namespace frc; +using namespace wpi::math; namespace { @@ -16,8 +16,8 @@ const Rectangle2d kExpectedData{ } // namespace TEST(Rectangle2dProtoTest, Roundtrip) { - wpi::ProtobufMessage message; - wpi::SmallVector buf; + wpi::util::ProtobufMessage message; + wpi::util::SmallVector buf; ASSERT_TRUE(message.Pack(buf, kExpectedData)); auto unpacked_data = message.Unpack(buf); diff --git a/wpimath/src/test/native/cpp/geometry/proto/Rotation2dProtoTest.cpp b/wpimath/src/test/native/cpp/geometry/proto/Rotation2dProtoTest.cpp index 5cfb826238..7853936b0d 100644 --- a/wpimath/src/test/native/cpp/geometry/proto/Rotation2dProtoTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/proto/Rotation2dProtoTest.cpp @@ -7,7 +7,7 @@ #include "wpi/math/geometry/Rotation2d.hpp" #include "wpi/util/SmallVector.hpp" -using namespace frc; +using namespace wpi::math; namespace { @@ -15,8 +15,8 @@ const Rotation2d kExpectedData = Rotation2d{1.91_rad}; } // namespace TEST(Rotation2dProtoTest, Roundtrip) { - wpi::ProtobufMessage message; - wpi::SmallVector buf; + wpi::util::ProtobufMessage message; + wpi::util::SmallVector buf; ASSERT_TRUE(message.Pack(buf, kExpectedData)); auto unpacked_data = message.Unpack(buf); diff --git a/wpimath/src/test/native/cpp/geometry/proto/Rotation3dProtoTest.cpp b/wpimath/src/test/native/cpp/geometry/proto/Rotation3dProtoTest.cpp index 3ad8ab0d2a..cc47ee3b09 100644 --- a/wpimath/src/test/native/cpp/geometry/proto/Rotation3dProtoTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/proto/Rotation3dProtoTest.cpp @@ -7,7 +7,7 @@ #include "wpi/math/geometry/Rotation3d.hpp" #include "wpi/util/SmallVector.hpp" -using namespace frc; +using namespace wpi::math; namespace { @@ -16,8 +16,8 @@ const Rotation3d kExpectedData = } // namespace TEST(Rotation3dProtoTest, Roundtrip) { - wpi::ProtobufMessage message; - wpi::SmallVector buf; + wpi::util::ProtobufMessage message; + wpi::util::SmallVector buf; ASSERT_TRUE(message.Pack(buf, kExpectedData)); auto unpacked_data = message.Unpack(buf); diff --git a/wpimath/src/test/native/cpp/geometry/proto/Transform2dProtoTest.cpp b/wpimath/src/test/native/cpp/geometry/proto/Transform2dProtoTest.cpp index c6bedb2d7f..de2fa5d96e 100644 --- a/wpimath/src/test/native/cpp/geometry/proto/Transform2dProtoTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/proto/Transform2dProtoTest.cpp @@ -7,7 +7,7 @@ #include "wpi/math/geometry/Transform2d.hpp" #include "wpi/util/SmallVector.hpp" -using namespace frc; +using namespace wpi::math; namespace { @@ -16,8 +16,8 @@ const Transform2d kExpectedData = } // namespace TEST(Transform2dProtoTest, Roundtrip) { - wpi::ProtobufMessage message; - wpi::SmallVector buf; + wpi::util::ProtobufMessage message; + wpi::util::SmallVector buf; ASSERT_TRUE(message.Pack(buf, kExpectedData)); auto unpacked_data = message.Unpack(buf); diff --git a/wpimath/src/test/native/cpp/geometry/proto/Transform3dProtoTest.cpp b/wpimath/src/test/native/cpp/geometry/proto/Transform3dProtoTest.cpp index 56af438c87..e21a9f8e03 100644 --- a/wpimath/src/test/native/cpp/geometry/proto/Transform3dProtoTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/proto/Transform3dProtoTest.cpp @@ -7,7 +7,7 @@ #include "wpi/math/geometry/Transform3d.hpp" #include "wpi/util/SmallVector.hpp" -using namespace frc; +using namespace wpi::math; namespace { @@ -17,8 +17,8 @@ const Transform3d kExpectedData = } // namespace TEST(Transform3dProtoTest, Roundtrip) { - wpi::ProtobufMessage message; - wpi::SmallVector buf; + wpi::util::ProtobufMessage message; + wpi::util::SmallVector buf; ASSERT_TRUE(message.Pack(buf, kExpectedData)); auto unpacked_data = message.Unpack(buf); diff --git a/wpimath/src/test/native/cpp/geometry/proto/Translation2dProtoTest.cpp b/wpimath/src/test/native/cpp/geometry/proto/Translation2dProtoTest.cpp index b53076b605..8d8bba431b 100644 --- a/wpimath/src/test/native/cpp/geometry/proto/Translation2dProtoTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/proto/Translation2dProtoTest.cpp @@ -7,7 +7,7 @@ #include "wpi/math/geometry/Translation2d.hpp" #include "wpi/util/SmallVector.hpp" -using namespace frc; +using namespace wpi::math; namespace { @@ -15,8 +15,8 @@ const Translation2d kExpectedData = Translation2d{3.504_m, 22.9_m}; } // namespace TEST(Translation2dProtoTest, Roundtrip) { - wpi::ProtobufMessage message; - wpi::SmallVector buf; + wpi::util::ProtobufMessage message; + wpi::util::SmallVector buf; ASSERT_TRUE(message.Pack(buf, kExpectedData)); auto unpacked_data = message.Unpack(buf); diff --git a/wpimath/src/test/native/cpp/geometry/proto/Translation3dProtoTest.cpp b/wpimath/src/test/native/cpp/geometry/proto/Translation3dProtoTest.cpp index 12b5d54517..95b3611318 100644 --- a/wpimath/src/test/native/cpp/geometry/proto/Translation3dProtoTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/proto/Translation3dProtoTest.cpp @@ -7,7 +7,7 @@ #include "wpi/math/geometry/Translation3d.hpp" #include "wpi/util/SmallVector.hpp" -using namespace frc; +using namespace wpi::math; namespace { @@ -15,8 +15,8 @@ const Translation3d kExpectedData = Translation3d{35.04_m, 22.9_m, 3.504_m}; } // namespace TEST(Translation3dProtoTest, Roundtrip) { - wpi::ProtobufMessage message; - wpi::SmallVector buf; + wpi::util::ProtobufMessage message; + wpi::util::SmallVector buf; ASSERT_TRUE(message.Pack(buf, kExpectedData)); auto unpacked_data = message.Unpack(buf); diff --git a/wpimath/src/test/native/cpp/geometry/proto/Twist2dProtoTest.cpp b/wpimath/src/test/native/cpp/geometry/proto/Twist2dProtoTest.cpp index 04bda40d36..ef8130d11d 100644 --- a/wpimath/src/test/native/cpp/geometry/proto/Twist2dProtoTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/proto/Twist2dProtoTest.cpp @@ -7,7 +7,7 @@ #include "wpi/math/geometry/Twist2d.hpp" #include "wpi/util/SmallVector.hpp" -using namespace frc; +using namespace wpi::math; namespace { @@ -15,8 +15,8 @@ const Twist2d kExpectedData = Twist2d{2.29_m, 35.04_m, 35.04_rad}; } // namespace TEST(Twist2dProtoTest, Roundtrip) { - wpi::ProtobufMessage message; - wpi::SmallVector buf; + wpi::util::ProtobufMessage message; + wpi::util::SmallVector buf; ASSERT_TRUE(message.Pack(buf, kExpectedData)); auto unpacked_data = message.Unpack(buf); diff --git a/wpimath/src/test/native/cpp/geometry/proto/Twist3dProtoTest.cpp b/wpimath/src/test/native/cpp/geometry/proto/Twist3dProtoTest.cpp index c1db34038a..eb22e2f5db 100644 --- a/wpimath/src/test/native/cpp/geometry/proto/Twist3dProtoTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/proto/Twist3dProtoTest.cpp @@ -7,7 +7,7 @@ #include "wpi/math/geometry/Twist3d.hpp" #include "wpi/util/SmallVector.hpp" -using namespace frc; +using namespace wpi::math; namespace { @@ -16,8 +16,8 @@ const Twist3d kExpectedData = } // namespace TEST(Twist3dProtoTest, Roundtrip) { - wpi::ProtobufMessage message; - wpi::SmallVector buf; + wpi::util::ProtobufMessage message; + wpi::util::SmallVector buf; ASSERT_TRUE(message.Pack(buf, kExpectedData)); auto unpacked_data = message.Unpack(buf); diff --git a/wpimath/src/test/native/cpp/geometry/struct/Ellipse2dStructTest.cpp b/wpimath/src/test/native/cpp/geometry/struct/Ellipse2dStructTest.cpp index 831e5c5c0e..bdd9a170d6 100644 --- a/wpimath/src/test/native/cpp/geometry/struct/Ellipse2dStructTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/struct/Ellipse2dStructTest.cpp @@ -6,11 +6,11 @@ #include "wpi/math/geometry/Ellipse2d.hpp" -using namespace frc; +using namespace wpi::math; namespace { -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; const Ellipse2d kExpectedData{ Pose2d{Translation2d{0.191_m, 2.2_m}, Rotation2d{22.9_rad}}, 1.2_m, 2.3_m}; } // namespace diff --git a/wpimath/src/test/native/cpp/geometry/struct/Pose2dStructTest.cpp b/wpimath/src/test/native/cpp/geometry/struct/Pose2dStructTest.cpp index f01d4aa3b9..e8828fe9cf 100644 --- a/wpimath/src/test/native/cpp/geometry/struct/Pose2dStructTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/struct/Pose2dStructTest.cpp @@ -6,11 +6,11 @@ #include "wpi/math/geometry/Pose2d.hpp" -using namespace frc; +using namespace wpi::math; namespace { -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; const Pose2d kExpectedData{ Pose2d{Translation2d{0.191_m, 2.2_m}, Rotation2d{22.9_rad}}}; } // namespace diff --git a/wpimath/src/test/native/cpp/geometry/struct/Pose3dStructTest.cpp b/wpimath/src/test/native/cpp/geometry/struct/Pose3dStructTest.cpp index 268a13f92a..7a5e2cea2f 100644 --- a/wpimath/src/test/native/cpp/geometry/struct/Pose3dStructTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/struct/Pose3dStructTest.cpp @@ -6,11 +6,11 @@ #include "wpi/math/geometry/Pose3d.hpp" -using namespace frc; +using namespace wpi::math; namespace { -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; const Pose3d kExpectedData{ Pose3d{Translation3d{1.1_m, 2.2_m, 1.1_m}, Rotation3d{Quaternion{1.91, 0.3504, 3.3, 1.74}}}}; diff --git a/wpimath/src/test/native/cpp/geometry/struct/QuaternionStructTest.cpp b/wpimath/src/test/native/cpp/geometry/struct/QuaternionStructTest.cpp index 1264dfecee..3c8a4dbf9c 100644 --- a/wpimath/src/test/native/cpp/geometry/struct/QuaternionStructTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/struct/QuaternionStructTest.cpp @@ -6,11 +6,11 @@ #include "wpi/math/geometry/Quaternion.hpp" -using namespace frc; +using namespace wpi::math; namespace { -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; const Quaternion kExpectedData{Quaternion{1.1, 0.191, 35.04, 19.1}}; } // namespace diff --git a/wpimath/src/test/native/cpp/geometry/struct/Rectangle2dStructTest.cpp b/wpimath/src/test/native/cpp/geometry/struct/Rectangle2dStructTest.cpp index 3605ebac34..32ac737717 100644 --- a/wpimath/src/test/native/cpp/geometry/struct/Rectangle2dStructTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/struct/Rectangle2dStructTest.cpp @@ -6,11 +6,11 @@ #include "wpi/math/geometry/Rectangle2d.hpp" -using namespace frc; +using namespace wpi::math; namespace { -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; const Rectangle2d kExpectedData{ Pose2d{Translation2d{0.191_m, 2.2_m}, Rotation2d{22.9_rad}}, 1.2_m, 2.3_m}; } // namespace diff --git a/wpimath/src/test/native/cpp/geometry/struct/Rotation2dStructTest.cpp b/wpimath/src/test/native/cpp/geometry/struct/Rotation2dStructTest.cpp index 672fdf5b9c..0b8642578a 100644 --- a/wpimath/src/test/native/cpp/geometry/struct/Rotation2dStructTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/struct/Rotation2dStructTest.cpp @@ -6,11 +6,11 @@ #include "wpi/math/geometry/Rotation2d.hpp" -using namespace frc; +using namespace wpi::math; namespace { -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; const Rotation2d kExpectedData{Rotation2d{1.91_rad}}; } // namespace diff --git a/wpimath/src/test/native/cpp/geometry/struct/Rotation3dStructTest.cpp b/wpimath/src/test/native/cpp/geometry/struct/Rotation3dStructTest.cpp index fd1bc84208..bf6c42957d 100644 --- a/wpimath/src/test/native/cpp/geometry/struct/Rotation3dStructTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/struct/Rotation3dStructTest.cpp @@ -6,11 +6,11 @@ #include "wpi/math/geometry/Rotation3d.hpp" -using namespace frc; +using namespace wpi::math; namespace { -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; const Rotation3d kExpectedData{ Rotation3d{Quaternion{2.29, 0.191, 0.191, 17.4}}}; } // namespace diff --git a/wpimath/src/test/native/cpp/geometry/struct/Transform2dStructTest.cpp b/wpimath/src/test/native/cpp/geometry/struct/Transform2dStructTest.cpp index e820d6e252..ef3c919381 100644 --- a/wpimath/src/test/native/cpp/geometry/struct/Transform2dStructTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/struct/Transform2dStructTest.cpp @@ -6,11 +6,11 @@ #include "wpi/math/geometry/Transform2d.hpp" -using namespace frc; +using namespace wpi::math; namespace { -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; const Transform2d kExpectedData{ Transform2d{Translation2d{0.191_m, 2.2_m}, Rotation2d{4.4_rad}}}; } // namespace diff --git a/wpimath/src/test/native/cpp/geometry/struct/Transform3dStructTest.cpp b/wpimath/src/test/native/cpp/geometry/struct/Transform3dStructTest.cpp index 328d8d8bd2..22eb6544aa 100644 --- a/wpimath/src/test/native/cpp/geometry/struct/Transform3dStructTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/struct/Transform3dStructTest.cpp @@ -6,11 +6,11 @@ #include "wpi/math/geometry/Transform3d.hpp" -using namespace frc; +using namespace wpi::math; namespace { -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; const Transform3d kExpectedData{ Transform3d{Translation3d{0.3504_m, 22.9_m, 3.504_m}, Rotation3d{Quaternion{0.3504, 35.04, 2.29, 0.3504}}}}; diff --git a/wpimath/src/test/native/cpp/geometry/struct/Translation2dStructTest.cpp b/wpimath/src/test/native/cpp/geometry/struct/Translation2dStructTest.cpp index c75c28cb7e..2d02864795 100644 --- a/wpimath/src/test/native/cpp/geometry/struct/Translation2dStructTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/struct/Translation2dStructTest.cpp @@ -6,11 +6,11 @@ #include "wpi/math/geometry/Translation2d.hpp" -using namespace frc; +using namespace wpi::math; namespace { -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; const Translation2d kExpectedData{Translation2d{3.504_m, 22.9_m}}; } // namespace diff --git a/wpimath/src/test/native/cpp/geometry/struct/Translation3dStructTest.cpp b/wpimath/src/test/native/cpp/geometry/struct/Translation3dStructTest.cpp index e4f68c9cf2..a160775d77 100644 --- a/wpimath/src/test/native/cpp/geometry/struct/Translation3dStructTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/struct/Translation3dStructTest.cpp @@ -6,11 +6,11 @@ #include "wpi/math/geometry/Translation3d.hpp" -using namespace frc; +using namespace wpi::math; namespace { -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; const Translation3d kExpectedData{Translation3d{35.04_m, 22.9_m, 3.504_m}}; } // namespace diff --git a/wpimath/src/test/native/cpp/geometry/struct/Twist2dStructTest.cpp b/wpimath/src/test/native/cpp/geometry/struct/Twist2dStructTest.cpp index dd1a082fdf..0f34f6b4f2 100644 --- a/wpimath/src/test/native/cpp/geometry/struct/Twist2dStructTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/struct/Twist2dStructTest.cpp @@ -6,11 +6,11 @@ #include "wpi/math/geometry/Twist2d.hpp" -using namespace frc; +using namespace wpi::math; namespace { -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; const Twist2d kExpectedData{Twist2d{2.29_m, 35.04_m, 35.04_rad}}; } // namespace diff --git a/wpimath/src/test/native/cpp/geometry/struct/Twist3dStructTest.cpp b/wpimath/src/test/native/cpp/geometry/struct/Twist3dStructTest.cpp index 4b5aac4ff6..cc8291919b 100644 --- a/wpimath/src/test/native/cpp/geometry/struct/Twist3dStructTest.cpp +++ b/wpimath/src/test/native/cpp/geometry/struct/Twist3dStructTest.cpp @@ -6,11 +6,11 @@ #include "wpi/math/geometry/Twist3d.hpp" -using namespace frc; +using namespace wpi::math; namespace { -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; const Twist3d kExpectedData{ Twist3d{1.1_m, 2.29_m, 35.04_m, 0.174_rad, 19.1_rad, 4.4_rad}}; } // namespace diff --git a/wpimath/src/test/native/cpp/interpolation/TimeInterpolatableBufferTest.cpp b/wpimath/src/test/native/cpp/interpolation/TimeInterpolatableBufferTest.cpp index 6c3550e209..0419229c9e 100644 --- a/wpimath/src/test/native/cpp/interpolation/TimeInterpolatableBufferTest.cpp +++ b/wpimath/src/test/native/cpp/interpolation/TimeInterpolatableBufferTest.cpp @@ -12,7 +12,7 @@ #include "wpi/units/time.hpp" TEST(TimeInterpolatableBufferTest, AddSample) { - frc::TimeInterpolatableBuffer buffer{10_s}; + wpi::math::TimeInterpolatableBuffer buffer{10_s}; // No entries buffer.AddSample(1_s, 0_rad); @@ -32,7 +32,7 @@ TEST(TimeInterpolatableBufferTest, AddSample) { } TEST(TimeInterpolatableBufferTest, Interpolation) { - frc::TimeInterpolatableBuffer buffer{10_s}; + wpi::math::TimeInterpolatableBuffer buffer{10_s}; buffer.AddSample(0_s, 0_rad); EXPECT_TRUE(buffer.Sample(0_s).value() == 0_rad); @@ -47,12 +47,12 @@ TEST(TimeInterpolatableBufferTest, Interpolation) { } TEST(TimeInterpolatableBufferTest, Pose2d) { - frc::TimeInterpolatableBuffer buffer{10_s}; + wpi::math::TimeInterpolatableBuffer buffer{10_s}; // We expect to be at (1 - 1/std::sqrt(2), 1/std::sqrt(2), 45deg) at t=0.5 - buffer.AddSample(0_s, frc::Pose2d{0_m, 0_m, 90_deg}); - buffer.AddSample(1_s, frc::Pose2d{1_m, 1_m, 0_deg}); - frc::Pose2d sample = buffer.Sample(0.5_s).value(); + buffer.AddSample(0_s, wpi::math::Pose2d{0_m, 0_m, 90_deg}); + buffer.AddSample(1_s, wpi::math::Pose2d{1_m, 1_m, 0_deg}); + wpi::math::Pose2d sample = buffer.Sample(0.5_s).value(); EXPECT_TRUE(std::abs(sample.X().value() - (1.0 - 1.0 / std::sqrt(2.0))) < 0.01); diff --git a/wpimath/src/test/native/cpp/kinematics/ChassisSpeedsTest.cpp b/wpimath/src/test/native/cpp/kinematics/ChassisSpeedsTest.cpp index e07018d559..ae4ebf0d54 100644 --- a/wpimath/src/test/native/cpp/kinematics/ChassisSpeedsTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/ChassisSpeedsTest.cpp @@ -11,15 +11,15 @@ static constexpr double kEpsilon = 1E-9; TEST(ChassisSpeedsTest, Discretize) { - constexpr frc::ChassisSpeeds target{1_mps, 0_mps, 0.5_rad_per_s}; - constexpr units::second_t duration = 1_s; - constexpr units::second_t dt = 10_ms; + constexpr wpi::math::ChassisSpeeds target{1_mps, 0_mps, 0.5_rad_per_s}; + constexpr wpi::units::second_t duration = 1_s; + constexpr wpi::units::second_t dt = 10_ms; const auto speeds = target.Discretize(duration); - const frc::Twist2d twist{speeds.vx * dt, speeds.vy * dt, speeds.omega * dt}; + const wpi::math::Twist2d twist{speeds.vx * dt, speeds.vy * dt, speeds.omega * dt}; - frc::Pose2d pose; - for (units::second_t time = 0_s; time < duration; time += dt) { + wpi::math::Pose2d pose; + for (wpi::units::second_t time = 0_s; time < duration; time += dt) { pose = pose + twist.Exp(); } @@ -31,7 +31,7 @@ TEST(ChassisSpeedsTest, Discretize) { TEST(ChassisSpeedsTest, ToRobotRelative) { const auto chassisSpeeds = - frc::ChassisSpeeds{1_mps, 0_mps, 0.5_rad_per_s}.ToRobotRelative( + wpi::math::ChassisSpeeds{1_mps, 0_mps, 0.5_rad_per_s}.ToRobotRelative( -90.0_deg); EXPECT_NEAR(0.0, chassisSpeeds.vx.value(), kEpsilon); @@ -41,7 +41,7 @@ TEST(ChassisSpeedsTest, ToRobotRelative) { TEST(ChassisSpeedsTest, ToFieldRelative) { const auto chassisSpeeds = - frc::ChassisSpeeds{1_mps, 0_mps, 0.5_rad_per_s}.ToFieldRelative(45.0_deg); + wpi::math::ChassisSpeeds{1_mps, 0_mps, 0.5_rad_per_s}.ToFieldRelative(45.0_deg); EXPECT_NEAR(1.0 / std::sqrt(2.0), chassisSpeeds.vx.value(), kEpsilon); EXPECT_NEAR(1.0 / std::sqrt(2.0), chassisSpeeds.vy.value(), kEpsilon); @@ -49,10 +49,10 @@ TEST(ChassisSpeedsTest, ToFieldRelative) { } TEST(ChassisSpeedsTest, Plus) { - const frc::ChassisSpeeds left{1.0_mps, 0.5_mps, 0.75_rad_per_s}; - const frc::ChassisSpeeds right{2.0_mps, 1.5_mps, 0.25_rad_per_s}; + const wpi::math::ChassisSpeeds left{1.0_mps, 0.5_mps, 0.75_rad_per_s}; + const wpi::math::ChassisSpeeds right{2.0_mps, 1.5_mps, 0.25_rad_per_s}; - const frc::ChassisSpeeds result = left + right; + const wpi::math::ChassisSpeeds result = left + right; EXPECT_NEAR(3.0, result.vx.value(), kEpsilon); EXPECT_NEAR(2.0, result.vy.value(), kEpsilon); @@ -60,10 +60,10 @@ TEST(ChassisSpeedsTest, Plus) { } TEST(ChassisSpeedsTest, Minus) { - const frc::ChassisSpeeds left{1.0_mps, 0.5_mps, 0.75_rad_per_s}; - const frc::ChassisSpeeds right{2.0_mps, 0.5_mps, 0.25_rad_per_s}; + const wpi::math::ChassisSpeeds left{1.0_mps, 0.5_mps, 0.75_rad_per_s}; + const wpi::math::ChassisSpeeds right{2.0_mps, 0.5_mps, 0.25_rad_per_s}; - const frc::ChassisSpeeds result = left - right; + const wpi::math::ChassisSpeeds result = left - right; EXPECT_NEAR(-1.0, result.vx.value(), kEpsilon); EXPECT_NEAR(0, result.vy.value(), kEpsilon); @@ -71,9 +71,9 @@ TEST(ChassisSpeedsTest, Minus) { } TEST(ChassisSpeedsTest, UnaryMinus) { - const frc::ChassisSpeeds speeds{1.0_mps, 0.5_mps, 0.75_rad_per_s}; + const wpi::math::ChassisSpeeds speeds{1.0_mps, 0.5_mps, 0.75_rad_per_s}; - const frc::ChassisSpeeds result = -speeds; + const wpi::math::ChassisSpeeds result = -speeds; EXPECT_NEAR(-1.0, result.vx.value(), kEpsilon); EXPECT_NEAR(-0.5, result.vy.value(), kEpsilon); @@ -81,9 +81,9 @@ TEST(ChassisSpeedsTest, UnaryMinus) { } TEST(ChassisSpeedsTest, Multiplication) { - const frc::ChassisSpeeds speeds{1.0_mps, 0.5_mps, 0.75_rad_per_s}; + const wpi::math::ChassisSpeeds speeds{1.0_mps, 0.5_mps, 0.75_rad_per_s}; - const frc::ChassisSpeeds result = speeds * 2; + const wpi::math::ChassisSpeeds result = speeds * 2; EXPECT_NEAR(2.0, result.vx.value(), kEpsilon); EXPECT_NEAR(1.0, result.vy.value(), kEpsilon); @@ -91,9 +91,9 @@ TEST(ChassisSpeedsTest, Multiplication) { } TEST(ChassisSpeedsTest, Division) { - const frc::ChassisSpeeds speeds{1.0_mps, 0.5_mps, 0.75_rad_per_s}; + const wpi::math::ChassisSpeeds speeds{1.0_mps, 0.5_mps, 0.75_rad_per_s}; - const frc::ChassisSpeeds result = speeds / 2; + const wpi::math::ChassisSpeeds result = speeds / 2; EXPECT_NEAR(0.5, result.vx.value(), kEpsilon); EXPECT_NEAR(0.25, result.vy.value(), kEpsilon); diff --git a/wpimath/src/test/native/cpp/kinematics/DifferentialDriveKinematicsTest.cpp b/wpimath/src/test/native/cpp/kinematics/DifferentialDriveKinematicsTest.cpp index 7e5e9897fe..a945fefe99 100644 --- a/wpimath/src/test/native/cpp/kinematics/DifferentialDriveKinematicsTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/DifferentialDriveKinematicsTest.cpp @@ -12,7 +12,7 @@ #include "wpi/units/length.hpp" #include "wpi/units/velocity.hpp" -using namespace frc; +using namespace wpi::math; static constexpr double kEpsilon = 1E-9; @@ -57,7 +57,7 @@ TEST(DifferentialDriveKinematicsTest, ForwardKinematicsForStraightLine) { TEST(DifferentialDriveKinematicsTest, InverseKinematicsForRotateInPlace) { const DifferentialDriveKinematics kinematics{0.381_m * 2}; const ChassisSpeeds chassisSpeeds{ - 0.0_mps, 0.0_mps, units::radians_per_second_t{std::numbers::pi}}; + 0.0_mps, 0.0_mps, wpi::units::radians_per_second_t{std::numbers::pi}}; const auto wheelSpeeds = kinematics.ToWheelSpeeds(chassisSpeeds); EXPECT_NEAR(wheelSpeeds.left.value(), -0.381 * std::numbers::pi, kEpsilon); @@ -67,8 +67,8 @@ TEST(DifferentialDriveKinematicsTest, InverseKinematicsForRotateInPlace) { TEST(DifferentialDriveKinematicsTest, ForwardKinematicsForRotateInPlace) { const DifferentialDriveKinematics kinematics{0.381_m * 2}; const DifferentialDriveWheelSpeeds wheelSpeeds{ - units::meters_per_second_t{+0.381 * std::numbers::pi}, - units::meters_per_second_t{-0.381 * std::numbers::pi}}; + wpi::units::meters_per_second_t{+0.381 * std::numbers::pi}, + wpi::units::meters_per_second_t{-0.381 * std::numbers::pi}}; const auto chassisSpeeds = kinematics.ToChassisSpeeds(wheelSpeeds); EXPECT_NEAR(chassisSpeeds.vx.value(), 0, kEpsilon); diff --git a/wpimath/src/test/native/cpp/kinematics/DifferentialDriveOdometry3dTest.cpp b/wpimath/src/test/native/cpp/kinematics/DifferentialDriveOdometry3dTest.cpp index e5f8fd3ab1..299bebb02f 100644 --- a/wpimath/src/test/native/cpp/kinematics/DifferentialDriveOdometry3dTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/DifferentialDriveOdometry3dTest.cpp @@ -11,14 +11,14 @@ static constexpr double kEpsilon = 1E-9; -using namespace frc; +using namespace wpi::math; TEST(DifferentialDriveOdometry3dTest, Initialize) { DifferentialDriveOdometry3d odometry{ - frc::Rotation3d{0_deg, 0_deg, 90_deg}, 0_m, 0_m, - frc::Pose3d{1_m, 2_m, 0_m, frc::Rotation3d{0_deg, 0_deg, 45_deg}}}; + wpi::math::Rotation3d{0_deg, 0_deg, 90_deg}, 0_m, 0_m, + wpi::math::Pose3d{1_m, 2_m, 0_m, wpi::math::Rotation3d{0_deg, 0_deg, 45_deg}}}; - const frc::Pose3d& pose = odometry.GetPose(); + const wpi::math::Pose3d& pose = odometry.GetPose(); EXPECT_NEAR(pose.X().value(), 1, kEpsilon); EXPECT_NEAR(pose.Y().value(), 2, kEpsilon); @@ -27,11 +27,11 @@ TEST(DifferentialDriveOdometry3dTest, Initialize) { } TEST(DifferentialDriveOdometry3dTest, EncoderDistances) { - DifferentialDriveOdometry3d odometry{frc::Rotation3d{0_deg, 0_deg, 45_deg}, + DifferentialDriveOdometry3d odometry{wpi::math::Rotation3d{0_deg, 0_deg, 45_deg}, 0_m, 0_m}; - const auto& pose = odometry.Update(frc::Rotation3d{0_deg, 0_deg, 135_deg}, - 0_m, units::meter_t{5 * std::numbers::pi}); + const auto& pose = odometry.Update(wpi::math::Rotation3d{0_deg, 0_deg, 135_deg}, + 0_m, wpi::units::meter_t{5 * std::numbers::pi}); EXPECT_NEAR(pose.X().value(), 5.0, kEpsilon); EXPECT_NEAR(pose.Y().value(), 5.0, kEpsilon); diff --git a/wpimath/src/test/native/cpp/kinematics/DifferentialDriveOdometryTest.cpp b/wpimath/src/test/native/cpp/kinematics/DifferentialDriveOdometryTest.cpp index a9289d53f9..cb9f3cd434 100644 --- a/wpimath/src/test/native/cpp/kinematics/DifferentialDriveOdometryTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/DifferentialDriveOdometryTest.cpp @@ -11,13 +11,13 @@ static constexpr double kEpsilon = 1E-9; -using namespace frc; +using namespace wpi::math; TEST(DifferentialDriveOdometryTest, EncoderDistances) { DifferentialDriveOdometry odometry{45_deg, 0_m, 0_m}; const auto& pose = - odometry.Update(135_deg, 0_m, units::meter_t{5 * std::numbers::pi}); + odometry.Update(135_deg, 0_m, wpi::units::meter_t{5 * std::numbers::pi}); EXPECT_NEAR(pose.X().value(), 5.0, kEpsilon); EXPECT_NEAR(pose.Y().value(), 5.0, kEpsilon); diff --git a/wpimath/src/test/native/cpp/kinematics/DifferentialDriveWheelSpeedsTest.cpp b/wpimath/src/test/native/cpp/kinematics/DifferentialDriveWheelSpeedsTest.cpp index dcf68acff7..76aaaf70ed 100644 --- a/wpimath/src/test/native/cpp/kinematics/DifferentialDriveWheelSpeedsTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/DifferentialDriveWheelSpeedsTest.cpp @@ -7,47 +7,47 @@ #include "wpi/math/kinematics/DifferentialDriveWheelSpeeds.hpp" TEST(DifferentialDriveWheelSpeedsTest, Plus) { - const frc::DifferentialDriveWheelSpeeds left{1.0_mps, 0.5_mps}; - const frc::DifferentialDriveWheelSpeeds right{2.0_mps, 1.5_mps}; + const wpi::math::DifferentialDriveWheelSpeeds left{1.0_mps, 0.5_mps}; + const wpi::math::DifferentialDriveWheelSpeeds right{2.0_mps, 1.5_mps}; - const frc::DifferentialDriveWheelSpeeds result = left + right; + const wpi::math::DifferentialDriveWheelSpeeds result = left + right; EXPECT_EQ(3.0, result.left.value()); EXPECT_EQ(2.0, result.right.value()); } TEST(DifferentialDriveWheelSpeedsTest, Minus) { - const frc::DifferentialDriveWheelSpeeds left{1.0_mps, 0.5_mps}; - const frc::DifferentialDriveWheelSpeeds right{2.0_mps, 0.5_mps}; + const wpi::math::DifferentialDriveWheelSpeeds left{1.0_mps, 0.5_mps}; + const wpi::math::DifferentialDriveWheelSpeeds right{2.0_mps, 0.5_mps}; - const frc::DifferentialDriveWheelSpeeds result = left - right; + const wpi::math::DifferentialDriveWheelSpeeds result = left - right; EXPECT_EQ(-1.0, result.left.value()); EXPECT_EQ(0, result.right.value()); } TEST(DifferentialDriveWheelSpeedsTest, UnaryMinus) { - const frc::DifferentialDriveWheelSpeeds speeds{1.0_mps, 0.5_mps}; + const wpi::math::DifferentialDriveWheelSpeeds speeds{1.0_mps, 0.5_mps}; - const frc::DifferentialDriveWheelSpeeds result = -speeds; + const wpi::math::DifferentialDriveWheelSpeeds result = -speeds; EXPECT_EQ(-1.0, result.left.value()); EXPECT_EQ(-0.5, result.right.value()); } TEST(DifferentialDriveWheelSpeedsTest, Multiplication) { - const frc::DifferentialDriveWheelSpeeds speeds{1.0_mps, 0.5_mps}; + const wpi::math::DifferentialDriveWheelSpeeds speeds{1.0_mps, 0.5_mps}; - const frc::DifferentialDriveWheelSpeeds result = speeds * 2; + const wpi::math::DifferentialDriveWheelSpeeds result = speeds * 2; EXPECT_EQ(2.0, result.left.value()); EXPECT_EQ(1.0, result.right.value()); } TEST(DifferentialDriveWheelSpeedsTest, Division) { - const frc::DifferentialDriveWheelSpeeds speeds{1.0_mps, 0.5_mps}; + const wpi::math::DifferentialDriveWheelSpeeds speeds{1.0_mps, 0.5_mps}; - const frc::DifferentialDriveWheelSpeeds result = speeds / 2; + const wpi::math::DifferentialDriveWheelSpeeds result = speeds / 2; EXPECT_EQ(0.5, result.left.value()); EXPECT_EQ(0.25, result.right.value()); diff --git a/wpimath/src/test/native/cpp/kinematics/MecanumDriveKinematicsTest.cpp b/wpimath/src/test/native/cpp/kinematics/MecanumDriveKinematicsTest.cpp index 7587986bb3..93fd2d2925 100644 --- a/wpimath/src/test/native/cpp/kinematics/MecanumDriveKinematicsTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/MecanumDriveKinematicsTest.cpp @@ -10,7 +10,7 @@ #include "wpi/math/kinematics/MecanumDriveKinematics.hpp" #include "wpi/units/angular_velocity.hpp" -using namespace frc; +using namespace wpi::math; class MecanumDriveKinematicsTest : public ::testing::Test { protected: @@ -80,7 +80,7 @@ TEST_F(MecanumDriveKinematicsTest, StrafeForwardKinematicsWithDeltas) { TEST_F(MecanumDriveKinematicsTest, RotationInverseKinematics) { ChassisSpeeds speeds{0_mps, 0_mps, - units::radians_per_second_t{2 * std::numbers::pi}}; + wpi::units::radians_per_second_t{2 * std::numbers::pi}}; auto moduleStates = kinematics.ToWheelSpeeds(speeds); EXPECT_NEAR(-150.79644737, moduleStates.frontLeft.value(), 0.1); diff --git a/wpimath/src/test/native/cpp/kinematics/MecanumDriveOdometry3dTest.cpp b/wpimath/src/test/native/cpp/kinematics/MecanumDriveOdometry3dTest.cpp index 5f0785112a..82924a8e3f 100644 --- a/wpimath/src/test/native/cpp/kinematics/MecanumDriveOdometry3dTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/MecanumDriveOdometry3dTest.cpp @@ -10,7 +10,7 @@ #include "wpi/math/kinematics/MecanumDriveOdometry3d.hpp" #include "wpi/math/trajectory/TrajectoryGenerator.hpp" -using namespace frc; +using namespace wpi::math; class MecanumDriveOdometry3dTest : public ::testing::Test { protected: @@ -22,15 +22,15 @@ class MecanumDriveOdometry3dTest : public ::testing::Test { MecanumDriveWheelPositions zero; MecanumDriveKinematics kinematics{m_fl, m_fr, m_bl, m_br}; - MecanumDriveOdometry3d odometry{kinematics, frc::Rotation3d{}, zero}; + MecanumDriveOdometry3d odometry{kinematics, wpi::math::Rotation3d{}, zero}; }; TEST_F(MecanumDriveOdometry3dTest, Initialize) { MecanumDriveOdometry3d odometry{ - kinematics, frc::Rotation3d{}, zero, - frc::Pose3d{1_m, 2_m, 0_m, frc::Rotation3d{0_deg, 0_deg, 45_deg}}}; + kinematics, wpi::math::Rotation3d{}, zero, + wpi::math::Pose3d{1_m, 2_m, 0_m, wpi::math::Rotation3d{0_deg, 0_deg, 45_deg}}}; - const frc::Pose3d& pose = odometry.GetPose(); + const wpi::math::Pose3d& pose = odometry.GetPose(); EXPECT_NEAR(pose.X().value(), 1, 1e-9); EXPECT_NEAR(pose.Y().value(), 2, 1e-9); @@ -41,10 +41,10 @@ TEST_F(MecanumDriveOdometry3dTest, Initialize) { TEST_F(MecanumDriveOdometry3dTest, MultipleConsecutiveUpdates) { MecanumDriveWheelPositions wheelDeltas{3.536_m, 3.536_m, 3.536_m, 3.536_m}; - odometry.ResetPosition(frc::Rotation3d{}, wheelDeltas, Pose3d{}); + odometry.ResetPosition(wpi::math::Rotation3d{}, wheelDeltas, Pose3d{}); - odometry.Update(frc::Rotation3d{}, wheelDeltas); - auto secondPose = odometry.Update(frc::Rotation3d{}, wheelDeltas); + odometry.Update(wpi::math::Rotation3d{}, wheelDeltas); + auto secondPose = odometry.Update(wpi::math::Rotation3d{}, wheelDeltas); EXPECT_NEAR(secondPose.X().value(), 0.0, 0.01); EXPECT_NEAR(secondPose.Y().value(), 0.0, 0.01); @@ -54,12 +54,12 @@ TEST_F(MecanumDriveOdometry3dTest, MultipleConsecutiveUpdates) { } TEST_F(MecanumDriveOdometry3dTest, TwoIterations) { - odometry.ResetPosition(frc::Rotation3d{}, zero, Pose3d{}); + odometry.ResetPosition(wpi::math::Rotation3d{}, zero, Pose3d{}); MecanumDriveWheelPositions wheelDeltas{0.3536_m, 0.3536_m, 0.3536_m, 0.3536_m}; - odometry.Update(frc::Rotation3d{}, MecanumDriveWheelPositions{}); - auto pose = odometry.Update(frc::Rotation3d{}, wheelDeltas); + odometry.Update(wpi::math::Rotation3d{}, MecanumDriveWheelPositions{}); + auto pose = odometry.Update(wpi::math::Rotation3d{}, wheelDeltas); EXPECT_NEAR(pose.X().value(), 0.3536, 0.01); EXPECT_NEAR(pose.Y().value(), 0.0, 0.01); @@ -68,12 +68,12 @@ TEST_F(MecanumDriveOdometry3dTest, TwoIterations) { } TEST_F(MecanumDriveOdometry3dTest, 90DegreeTurn) { - odometry.ResetPosition(frc::Rotation3d{}, zero, Pose3d{}); + odometry.ResetPosition(wpi::math::Rotation3d{}, zero, Pose3d{}); MecanumDriveWheelPositions wheelDeltas{-13.328_m, 39.986_m, -13.329_m, 39.986_m}; - odometry.Update(frc::Rotation3d{}, MecanumDriveWheelPositions{}); + odometry.Update(wpi::math::Rotation3d{}, MecanumDriveWheelPositions{}); auto pose = - odometry.Update(frc::Rotation3d{0_deg, 0_deg, 90_deg}, wheelDeltas); + odometry.Update(wpi::math::Rotation3d{0_deg, 0_deg, 90_deg}, wheelDeltas); EXPECT_NEAR(pose.X().value(), 8.4855, 0.01); EXPECT_NEAR(pose.Y().value(), 8.4855, 0.01); @@ -82,13 +82,13 @@ TEST_F(MecanumDriveOdometry3dTest, 90DegreeTurn) { } TEST_F(MecanumDriveOdometry3dTest, GyroAngleReset) { - odometry.ResetPosition(frc::Rotation3d{0_deg, 0_deg, 90_deg}, zero, Pose3d{}); + odometry.ResetPosition(wpi::math::Rotation3d{0_deg, 0_deg, 90_deg}, zero, Pose3d{}); MecanumDriveWheelPositions wheelDeltas{0.3536_m, 0.3536_m, 0.3536_m, 0.3536_m}; auto pose = - odometry.Update(frc::Rotation3d{0_deg, 0_deg, 90_deg}, wheelDeltas); + odometry.Update(wpi::math::Rotation3d{0_deg, 0_deg, 90_deg}, wheelDeltas); EXPECT_NEAR(pose.X().value(), 0.3536, 0.01); EXPECT_NEAR(pose.Y().value(), 0.0, 0.01); @@ -97,33 +97,33 @@ TEST_F(MecanumDriveOdometry3dTest, GyroAngleReset) { } TEST_F(MecanumDriveOdometry3dTest, AccuracyFacingTrajectory) { - frc::MecanumDriveKinematics kinematics{ - frc::Translation2d{1_m, 1_m}, frc::Translation2d{1_m, -1_m}, - frc::Translation2d{-1_m, -1_m}, frc::Translation2d{-1_m, 1_m}}; + wpi::math::MecanumDriveKinematics kinematics{ + wpi::math::Translation2d{1_m, 1_m}, wpi::math::Translation2d{1_m, -1_m}, + wpi::math::Translation2d{-1_m, -1_m}, wpi::math::Translation2d{-1_m, 1_m}}; - frc::MecanumDriveWheelPositions wheelPositions; + wpi::math::MecanumDriveWheelPositions wheelPositions; - frc::MecanumDriveOdometry3d odometry{kinematics, frc::Rotation3d{}, + wpi::math::MecanumDriveOdometry3d odometry{kinematics, wpi::math::Rotation3d{}, wheelPositions}; - frc::Trajectory trajectory = frc::TrajectoryGenerator::GenerateTrajectory( - std::vector{frc::Pose2d{0_m, 0_m, 45_deg}, frc::Pose2d{3_m, 0_m, -90_deg}, - frc::Pose2d{0_m, 0_m, 135_deg}, - frc::Pose2d{-3_m, 0_m, -90_deg}, - frc::Pose2d{0_m, 0_m, 45_deg}}, - frc::TrajectoryConfig(5.0_mps, 2.0_mps_sq)); + wpi::math::Trajectory trajectory = wpi::math::TrajectoryGenerator::GenerateTrajectory( + std::vector{wpi::math::Pose2d{0_m, 0_m, 45_deg}, wpi::math::Pose2d{3_m, 0_m, -90_deg}, + wpi::math::Pose2d{0_m, 0_m, 135_deg}, + wpi::math::Pose2d{-3_m, 0_m, -90_deg}, + wpi::math::Pose2d{0_m, 0_m, 45_deg}}, + wpi::math::TrajectoryConfig(5.0_mps, 2.0_mps_sq)); std::default_random_engine generator; std::normal_distribution distribution(0.0, 1.0); - units::second_t dt = 20_ms; - units::second_t t = 0_s; + wpi::units::second_t dt = 20_ms; + wpi::units::second_t t = 0_s; double maxError = -std::numeric_limits::max(); double errorSum = 0; while (t < trajectory.TotalTime()) { - frc::Trajectory::State groundTruthState = trajectory.Sample(t); + wpi::math::Trajectory::State groundTruthState = trajectory.Sample(t); auto wheelSpeeds = kinematics.ToWheelSpeeds( {groundTruthState.velocity, 0_mps, @@ -140,8 +140,8 @@ TEST_F(MecanumDriveOdometry3dTest, AccuracyFacingTrajectory) { wheelPositions.rearRight += wheelSpeeds.rearRight * dt; auto xhat = odometry.Update( - frc::Rotation3d{groundTruthState.pose.Rotation() + - frc::Rotation2d{distribution(generator) * 0.05_rad}}, + wpi::math::Rotation3d{groundTruthState.pose.Rotation() + + wpi::math::Rotation2d{distribution(generator) * 0.05_rad}}, wheelPositions); double error = groundTruthState.pose.Translation() .Distance(xhat.Translation().ToTranslation2d()) @@ -160,33 +160,33 @@ TEST_F(MecanumDriveOdometry3dTest, AccuracyFacingTrajectory) { } TEST_F(MecanumDriveOdometry3dTest, AccuracyFacingXAxis) { - frc::MecanumDriveKinematics kinematics{ - frc::Translation2d{1_m, 1_m}, frc::Translation2d{1_m, -1_m}, - frc::Translation2d{-1_m, -1_m}, frc::Translation2d{-1_m, 1_m}}; + wpi::math::MecanumDriveKinematics kinematics{ + wpi::math::Translation2d{1_m, 1_m}, wpi::math::Translation2d{1_m, -1_m}, + wpi::math::Translation2d{-1_m, -1_m}, wpi::math::Translation2d{-1_m, 1_m}}; - frc::MecanumDriveWheelPositions wheelPositions; + wpi::math::MecanumDriveWheelPositions wheelPositions; - frc::MecanumDriveOdometry3d odometry{kinematics, frc::Rotation3d{}, + wpi::math::MecanumDriveOdometry3d odometry{kinematics, wpi::math::Rotation3d{}, wheelPositions}; - frc::Trajectory trajectory = frc::TrajectoryGenerator::GenerateTrajectory( - std::vector{frc::Pose2d{0_m, 0_m, 45_deg}, frc::Pose2d{3_m, 0_m, -90_deg}, - frc::Pose2d{0_m, 0_m, 135_deg}, - frc::Pose2d{-3_m, 0_m, -90_deg}, - frc::Pose2d{0_m, 0_m, 45_deg}}, - frc::TrajectoryConfig(5.0_mps, 2.0_mps_sq)); + wpi::math::Trajectory trajectory = wpi::math::TrajectoryGenerator::GenerateTrajectory( + std::vector{wpi::math::Pose2d{0_m, 0_m, 45_deg}, wpi::math::Pose2d{3_m, 0_m, -90_deg}, + wpi::math::Pose2d{0_m, 0_m, 135_deg}, + wpi::math::Pose2d{-3_m, 0_m, -90_deg}, + wpi::math::Pose2d{0_m, 0_m, 45_deg}}, + wpi::math::TrajectoryConfig(5.0_mps, 2.0_mps_sq)); std::default_random_engine generator; std::normal_distribution distribution(0.0, 1.0); - units::second_t dt = 20_ms; - units::second_t t = 0_s; + wpi::units::second_t dt = 20_ms; + wpi::units::second_t t = 0_s; double maxError = -std::numeric_limits::max(); double errorSum = 0; while (t < trajectory.TotalTime()) { - frc::Trajectory::State groundTruthState = trajectory.Sample(t); + wpi::math::Trajectory::State groundTruthState = trajectory.Sample(t); auto wheelSpeeds = kinematics.ToWheelSpeeds( {groundTruthState.velocity * groundTruthState.pose.Rotation().Cos(), @@ -204,7 +204,7 @@ TEST_F(MecanumDriveOdometry3dTest, AccuracyFacingXAxis) { wheelPositions.rearRight += wheelSpeeds.rearRight * dt; auto xhat = odometry.Update( - frc::Rotation3d{0_rad, 0_rad, distribution(generator) * 0.05_rad}, + wpi::math::Rotation3d{0_rad, 0_rad, distribution(generator) * 0.05_rad}, wheelPositions); double error = groundTruthState.pose.Translation() .Distance(xhat.Translation().ToTranslation2d()) diff --git a/wpimath/src/test/native/cpp/kinematics/MecanumDriveOdometryTest.cpp b/wpimath/src/test/native/cpp/kinematics/MecanumDriveOdometryTest.cpp index 3b796c0888..b4b68a98cf 100644 --- a/wpimath/src/test/native/cpp/kinematics/MecanumDriveOdometryTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/MecanumDriveOdometryTest.cpp @@ -10,7 +10,7 @@ #include "wpi/math/kinematics/MecanumDriveOdometry.hpp" #include "wpi/math/trajectory/TrajectoryGenerator.hpp" -using namespace frc; +using namespace wpi::math; class MecanumDriveOdometryTest : public ::testing::Test { protected: @@ -78,33 +78,33 @@ TEST_F(MecanumDriveOdometryTest, GyroAngleReset) { } TEST_F(MecanumDriveOdometryTest, AccuracyFacingTrajectory) { - frc::MecanumDriveKinematics kinematics{ - frc::Translation2d{1_m, 1_m}, frc::Translation2d{1_m, -1_m}, - frc::Translation2d{-1_m, -1_m}, frc::Translation2d{-1_m, 1_m}}; + wpi::math::MecanumDriveKinematics kinematics{ + wpi::math::Translation2d{1_m, 1_m}, wpi::math::Translation2d{1_m, -1_m}, + wpi::math::Translation2d{-1_m, -1_m}, wpi::math::Translation2d{-1_m, 1_m}}; - frc::MecanumDriveWheelPositions wheelPositions; + wpi::math::MecanumDriveWheelPositions wheelPositions; - frc::MecanumDriveOdometry odometry{kinematics, frc::Rotation2d{}, + wpi::math::MecanumDriveOdometry odometry{kinematics, wpi::math::Rotation2d{}, wheelPositions}; - frc::Trajectory trajectory = frc::TrajectoryGenerator::GenerateTrajectory( - std::vector{frc::Pose2d{0_m, 0_m, 45_deg}, frc::Pose2d{3_m, 0_m, -90_deg}, - frc::Pose2d{0_m, 0_m, 135_deg}, - frc::Pose2d{-3_m, 0_m, -90_deg}, - frc::Pose2d{0_m, 0_m, 45_deg}}, - frc::TrajectoryConfig(5.0_mps, 2.0_mps_sq)); + wpi::math::Trajectory trajectory = wpi::math::TrajectoryGenerator::GenerateTrajectory( + std::vector{wpi::math::Pose2d{0_m, 0_m, 45_deg}, wpi::math::Pose2d{3_m, 0_m, -90_deg}, + wpi::math::Pose2d{0_m, 0_m, 135_deg}, + wpi::math::Pose2d{-3_m, 0_m, -90_deg}, + wpi::math::Pose2d{0_m, 0_m, 45_deg}}, + wpi::math::TrajectoryConfig(5.0_mps, 2.0_mps_sq)); std::default_random_engine generator; std::normal_distribution distribution(0.0, 1.0); - units::second_t dt = 20_ms; - units::second_t t = 0_s; + wpi::units::second_t dt = 20_ms; + wpi::units::second_t t = 0_s; double maxError = -std::numeric_limits::max(); double errorSum = 0; while (t < trajectory.TotalTime()) { - frc::Trajectory::State groundTruthState = trajectory.Sample(t); + wpi::math::Trajectory::State groundTruthState = trajectory.Sample(t); auto wheelSpeeds = kinematics.ToWheelSpeeds( {groundTruthState.velocity, 0_mps, @@ -122,7 +122,7 @@ TEST_F(MecanumDriveOdometryTest, AccuracyFacingTrajectory) { auto xhat = odometry.Update(groundTruthState.pose.Rotation() + - frc::Rotation2d{distribution(generator) * 0.05_rad}, + wpi::math::Rotation2d{distribution(generator) * 0.05_rad}, wheelPositions); double error = groundTruthState.pose.Translation() .Distance(xhat.Translation()) @@ -141,33 +141,33 @@ TEST_F(MecanumDriveOdometryTest, AccuracyFacingTrajectory) { } TEST_F(MecanumDriveOdometryTest, AccuracyFacingXAxis) { - frc::MecanumDriveKinematics kinematics{ - frc::Translation2d{1_m, 1_m}, frc::Translation2d{1_m, -1_m}, - frc::Translation2d{-1_m, -1_m}, frc::Translation2d{-1_m, 1_m}}; + wpi::math::MecanumDriveKinematics kinematics{ + wpi::math::Translation2d{1_m, 1_m}, wpi::math::Translation2d{1_m, -1_m}, + wpi::math::Translation2d{-1_m, -1_m}, wpi::math::Translation2d{-1_m, 1_m}}; - frc::MecanumDriveWheelPositions wheelPositions; + wpi::math::MecanumDriveWheelPositions wheelPositions; - frc::MecanumDriveOdometry odometry{kinematics, frc::Rotation2d{}, + wpi::math::MecanumDriveOdometry odometry{kinematics, wpi::math::Rotation2d{}, wheelPositions}; - frc::Trajectory trajectory = frc::TrajectoryGenerator::GenerateTrajectory( - std::vector{frc::Pose2d{0_m, 0_m, 45_deg}, frc::Pose2d{3_m, 0_m, -90_deg}, - frc::Pose2d{0_m, 0_m, 135_deg}, - frc::Pose2d{-3_m, 0_m, -90_deg}, - frc::Pose2d{0_m, 0_m, 45_deg}}, - frc::TrajectoryConfig(5.0_mps, 2.0_mps_sq)); + wpi::math::Trajectory trajectory = wpi::math::TrajectoryGenerator::GenerateTrajectory( + std::vector{wpi::math::Pose2d{0_m, 0_m, 45_deg}, wpi::math::Pose2d{3_m, 0_m, -90_deg}, + wpi::math::Pose2d{0_m, 0_m, 135_deg}, + wpi::math::Pose2d{-3_m, 0_m, -90_deg}, + wpi::math::Pose2d{0_m, 0_m, 45_deg}}, + wpi::math::TrajectoryConfig(5.0_mps, 2.0_mps_sq)); std::default_random_engine generator; std::normal_distribution distribution(0.0, 1.0); - units::second_t dt = 20_ms; - units::second_t t = 0_s; + wpi::units::second_t dt = 20_ms; + wpi::units::second_t t = 0_s; double maxError = -std::numeric_limits::max(); double errorSum = 0; while (t < trajectory.TotalTime()) { - frc::Trajectory::State groundTruthState = trajectory.Sample(t); + wpi::math::Trajectory::State groundTruthState = trajectory.Sample(t); auto wheelSpeeds = kinematics.ToWheelSpeeds( {groundTruthState.velocity * groundTruthState.pose.Rotation().Cos(), @@ -185,7 +185,7 @@ TEST_F(MecanumDriveOdometryTest, AccuracyFacingXAxis) { wheelPositions.rearRight += wheelSpeeds.rearRight * dt; auto xhat = odometry.Update( - frc::Rotation2d{distribution(generator) * 0.05_rad}, wheelPositions); + wpi::math::Rotation2d{distribution(generator) * 0.05_rad}, wheelPositions); double error = groundTruthState.pose.Translation() .Distance(xhat.Translation()) .value(); diff --git a/wpimath/src/test/native/cpp/kinematics/MecanumDriveWheelSpeedsTest.cpp b/wpimath/src/test/native/cpp/kinematics/MecanumDriveWheelSpeedsTest.cpp index 70ff02a545..30a81dd65b 100644 --- a/wpimath/src/test/native/cpp/kinematics/MecanumDriveWheelSpeedsTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/MecanumDriveWheelSpeedsTest.cpp @@ -7,10 +7,10 @@ #include "wpi/math/kinematics/MecanumDriveWheelSpeeds.hpp" TEST(MecanumDriveWheelSpeedsTest, Plus) { - const frc::MecanumDriveWheelSpeeds left{1.0_mps, 0.5_mps, 2.0_mps, 1.5_mps}; - const frc::MecanumDriveWheelSpeeds right{2.0_mps, 1.5_mps, 0.5_mps, 1.0_mps}; + const wpi::math::MecanumDriveWheelSpeeds left{1.0_mps, 0.5_mps, 2.0_mps, 1.5_mps}; + const wpi::math::MecanumDriveWheelSpeeds right{2.0_mps, 1.5_mps, 0.5_mps, 1.0_mps}; - const frc::MecanumDriveWheelSpeeds result = left + right; + const wpi::math::MecanumDriveWheelSpeeds result = left + right; EXPECT_EQ(3.0, result.frontLeft.value()); EXPECT_EQ(2.0, result.frontRight.value()); @@ -19,10 +19,10 @@ TEST(MecanumDriveWheelSpeedsTest, Plus) { } TEST(MecanumDriveWheelSpeedsTest, Minus) { - const frc::MecanumDriveWheelSpeeds left{1.0_mps, 0.5_mps, 2.0_mps, 1.5_mps}; - const frc::MecanumDriveWheelSpeeds right{2.0_mps, 1.5_mps, 0.5_mps, 1.0_mps}; + const wpi::math::MecanumDriveWheelSpeeds left{1.0_mps, 0.5_mps, 2.0_mps, 1.5_mps}; + const wpi::math::MecanumDriveWheelSpeeds right{2.0_mps, 1.5_mps, 0.5_mps, 1.0_mps}; - const frc::MecanumDriveWheelSpeeds result = left - right; + const wpi::math::MecanumDriveWheelSpeeds result = left - right; EXPECT_EQ(-1.0, result.frontLeft.value()); EXPECT_EQ(-1.0, result.frontRight.value()); @@ -31,9 +31,9 @@ TEST(MecanumDriveWheelSpeedsTest, Minus) { } TEST(MecanumDriveWheelSpeedsTest, UnaryMinus) { - const frc::MecanumDriveWheelSpeeds speeds{1.0_mps, 0.5_mps, 2.0_mps, 1.5_mps}; + const wpi::math::MecanumDriveWheelSpeeds speeds{1.0_mps, 0.5_mps, 2.0_mps, 1.5_mps}; - const frc::MecanumDriveWheelSpeeds result = -speeds; + const wpi::math::MecanumDriveWheelSpeeds result = -speeds; EXPECT_EQ(-1.0, result.frontLeft.value()); EXPECT_EQ(-0.5, result.frontRight.value()); @@ -42,9 +42,9 @@ TEST(MecanumDriveWheelSpeedsTest, UnaryMinus) { } TEST(MecanumDriveWheelSpeedsTest, Multiplication) { - const frc::MecanumDriveWheelSpeeds speeds{1.0_mps, 0.5_mps, 2.0_mps, 1.5_mps}; + const wpi::math::MecanumDriveWheelSpeeds speeds{1.0_mps, 0.5_mps, 2.0_mps, 1.5_mps}; - const frc::MecanumDriveWheelSpeeds result = speeds * 2; + const wpi::math::MecanumDriveWheelSpeeds result = speeds * 2; EXPECT_EQ(2.0, result.frontLeft.value()); EXPECT_EQ(1.0, result.frontRight.value()); @@ -53,9 +53,9 @@ TEST(MecanumDriveWheelSpeedsTest, Multiplication) { } TEST(MecanumDriveWheelSpeedsTest, Division) { - const frc::MecanumDriveWheelSpeeds speeds{1.0_mps, 0.5_mps, 2.0_mps, 1.5_mps}; + const wpi::math::MecanumDriveWheelSpeeds speeds{1.0_mps, 0.5_mps, 2.0_mps, 1.5_mps}; - const frc::MecanumDriveWheelSpeeds result = speeds / 2; + const wpi::math::MecanumDriveWheelSpeeds result = speeds / 2; EXPECT_EQ(0.5, result.frontLeft.value()); EXPECT_EQ(0.25, result.frontRight.value()); diff --git a/wpimath/src/test/native/cpp/kinematics/SwerveDriveKinematicsTest.cpp b/wpimath/src/test/native/cpp/kinematics/SwerveDriveKinematicsTest.cpp index 647754b8b6..713fbdb855 100644 --- a/wpimath/src/test/native/cpp/kinematics/SwerveDriveKinematicsTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/SwerveDriveKinematicsTest.cpp @@ -10,7 +10,7 @@ #include "wpi/math/kinematics/SwerveDriveKinematics.hpp" #include "wpi/units/angular_velocity.hpp" -using namespace frc; +using namespace wpi::math; static constexpr double kEpsilon = 0.1; @@ -96,7 +96,7 @@ TEST_F(SwerveDriveKinematicsTest, StraightStrafeForwardKinematicsWithDeltas) { TEST_F(SwerveDriveKinematicsTest, TurnInPlaceInverseKinematics) { ChassisSpeeds speeds{0_mps, 0_mps, - units::radians_per_second_t{2 * std::numbers::pi}}; + wpi::units::radians_per_second_t{2 * std::numbers::pi}}; auto [fl, fr, bl, br] = m_kinematics.ToSwerveModuleStates(speeds); EXPECT_NEAR(fl.speed.value(), 106.63, kEpsilon); @@ -112,7 +112,7 @@ TEST_F(SwerveDriveKinematicsTest, TurnInPlaceInverseKinematics) { TEST_F(SwerveDriveKinematicsTest, ConserveWheelAngle) { ChassisSpeeds speeds{0_mps, 0_mps, - units::radians_per_second_t{2 * std::numbers::pi}}; + wpi::units::radians_per_second_t{2 * std::numbers::pi}}; m_kinematics.ToSwerveModuleStates(speeds); auto [fl, fr, bl, br] = m_kinematics.ToSwerveModuleStates(ChassisSpeeds{}); @@ -174,7 +174,7 @@ TEST_F(SwerveDriveKinematicsTest, TurnInPlaceForwardKinematicsWithDeltas) { TEST_F(SwerveDriveKinematicsTest, OffCenterCORRotationInverseKinematics) { ChassisSpeeds speeds{0_mps, 0_mps, - units::radians_per_second_t{2 * std::numbers::pi}}; + wpi::units::radians_per_second_t{2 * std::numbers::pi}}; auto [fl, fr, bl, br] = m_kinematics.ToSwerveModuleStates(speeds, m_fl); EXPECT_NEAR(fl.speed.value(), 0.0, kEpsilon); @@ -266,7 +266,7 @@ TEST_F(SwerveDriveKinematicsTest, Desaturate) { SwerveModuleState state3{4.0_mps, 0_deg}; SwerveModuleState state4{7.0_mps, 0_deg}; - wpi::array arr{state1, state2, state3, state4}; + wpi::util::array arr{state1, state2, state3, state4}; SwerveDriveKinematics<4>::DesaturateWheelSpeeds(&arr, 5.5_mps); double kFactor = 5.5 / 7.0; @@ -283,7 +283,7 @@ TEST_F(SwerveDriveKinematicsTest, DesaturateSmooth) { SwerveModuleState state3{4.0_mps, 0_deg}; SwerveModuleState state4{7.0_mps, 0_deg}; - wpi::array arr{state1, state2, state3, state4}; + wpi::util::array arr{state1, state2, state3, state4}; SwerveDriveKinematics<4>::DesaturateWheelSpeeds( &arr, m_kinematics.ToChassisSpeeds(arr), 5.5_mps, 5.5_mps, 3.5_rad_per_s); @@ -301,7 +301,7 @@ TEST_F(SwerveDriveKinematicsTest, DesaturateNegativeSpeed) { SwerveModuleState state3{-2.0_mps, 0_deg}; SwerveModuleState state4{-2.0_mps, 0_deg}; - wpi::array arr{state1, state2, state3, state4}; + wpi::util::array arr{state1, state2, state3, state4}; SwerveDriveKinematics<4>::DesaturateWheelSpeeds(&arr, 1.0_mps); EXPECT_NEAR(arr[0].speed.value(), 0.5, kEpsilon); diff --git a/wpimath/src/test/native/cpp/kinematics/SwerveDriveOdometry3dTest.cpp b/wpimath/src/test/native/cpp/kinematics/SwerveDriveOdometry3dTest.cpp index 6f61d74890..844f4434a5 100644 --- a/wpimath/src/test/native/cpp/kinematics/SwerveDriveOdometry3dTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/SwerveDriveOdometry3dTest.cpp @@ -13,7 +13,7 @@ #include "wpi/math/trajectory/TrajectoryConfig.hpp" #include "wpi/math/trajectory/TrajectoryGenerator.hpp" -using namespace frc; +using namespace wpi::math; static constexpr double kEpsilon = 0.01; @@ -27,17 +27,17 @@ class SwerveDriveOdometry3dTest : public ::testing::Test { SwerveDriveKinematics<4> m_kinematics{m_fl, m_fr, m_bl, m_br}; SwerveModulePosition zero; SwerveDriveOdometry3d<4> m_odometry{ - m_kinematics, frc::Rotation3d{}, {zero, zero, zero, zero}}; + m_kinematics, wpi::math::Rotation3d{}, {zero, zero, zero, zero}}; }; TEST_F(SwerveDriveOdometry3dTest, Initialize) { SwerveDriveOdometry3d odometry{ m_kinematics, - frc::Rotation3d{}, + wpi::math::Rotation3d{}, {zero, zero, zero, zero}, - frc::Pose3d{1_m, 2_m, 0_m, frc::Rotation3d{0_deg, 0_deg, 45_deg}}}; + wpi::math::Pose3d{1_m, 2_m, 0_m, wpi::math::Rotation3d{0_deg, 0_deg, 45_deg}}}; - const frc::Pose3d& pose = odometry.GetPose(); + const wpi::math::Pose3d& pose = odometry.GetPose(); EXPECT_NEAR(pose.X().value(), 1, kEpsilon); EXPECT_NEAR(pose.Y().value(), 2, kEpsilon); @@ -48,12 +48,12 @@ TEST_F(SwerveDriveOdometry3dTest, Initialize) { TEST_F(SwerveDriveOdometry3dTest, TwoIterations) { SwerveModulePosition position{0.5_m, 0_deg}; - m_odometry.ResetPosition(frc::Rotation3d{}, {zero, zero, zero, zero}, + m_odometry.ResetPosition(wpi::math::Rotation3d{}, {zero, zero, zero, zero}, Pose3d{}); - m_odometry.Update(frc::Rotation3d{}, {zero, zero, zero, zero}); + m_odometry.Update(wpi::math::Rotation3d{}, {zero, zero, zero, zero}); - auto pose = m_odometry.Update(frc::Rotation3d{}, + auto pose = m_odometry.Update(wpi::math::Rotation3d{}, {position, position, position, position}); EXPECT_NEAR(0.5, pose.X().value(), kEpsilon); @@ -68,9 +68,9 @@ TEST_F(SwerveDriveOdometry3dTest, 90DegreeTurn) { SwerveModulePosition bl{18.85_m, -90_deg}; SwerveModulePosition br{42.15_m, -26.565_deg}; - m_odometry.ResetPosition(frc::Rotation3d{}, {zero, zero, zero, zero}, + m_odometry.ResetPosition(wpi::math::Rotation3d{}, {zero, zero, zero, zero}, Pose3d{}); - auto pose = m_odometry.Update(frc::Rotation3d{0_deg, 0_deg, 90_deg}, + auto pose = m_odometry.Update(wpi::math::Rotation3d{0_deg, 0_deg, 90_deg}, {fl, fr, bl, br}); EXPECT_NEAR(12.0, pose.X().value(), kEpsilon); @@ -80,12 +80,12 @@ TEST_F(SwerveDriveOdometry3dTest, 90DegreeTurn) { } TEST_F(SwerveDriveOdometry3dTest, GyroAngleReset) { - m_odometry.ResetPosition(frc::Rotation3d{0_deg, 0_deg, 90_deg}, + m_odometry.ResetPosition(wpi::math::Rotation3d{0_deg, 0_deg, 90_deg}, {zero, zero, zero, zero}, Pose3d{}); SwerveModulePosition position{0.5_m, 0_deg}; - auto pose = m_odometry.Update(frc::Rotation3d{0_deg, 0_deg, 90_deg}, + auto pose = m_odometry.Update(wpi::math::Rotation3d{0_deg, 0_deg, 90_deg}, {position, position, position, position}); EXPECT_NEAR(0.5, pose.X().value(), kEpsilon); @@ -100,7 +100,7 @@ TEST_F(SwerveDriveOdometry3dTest, AccuracyFacingTrajectory) { Translation2d{-1_m, -1_m}, Translation2d{-1_m, 1_m}}; SwerveDriveOdometry3d<4> odometry{ - kinematics, frc::Rotation3d{}, {zero, zero, zero, zero}}; + kinematics, wpi::math::Rotation3d{}, {zero, zero, zero, zero}}; SwerveModulePosition fl; SwerveModulePosition fr; @@ -116,8 +116,8 @@ TEST_F(SwerveDriveOdometry3dTest, AccuracyFacingTrajectory) { std::default_random_engine generator; std::normal_distribution distribution(0.0, 1.0); - units::second_t dt = 20_ms; - units::second_t t = 0_s; + wpi::units::second_t dt = 20_ms; + wpi::units::second_t t = 0_s; double maxError = -std::numeric_limits::max(); double errorSum = 0; @@ -140,8 +140,8 @@ TEST_F(SwerveDriveOdometry3dTest, AccuracyFacingTrajectory) { br.angle = moduleStates[3].angle; auto xhat = odometry.Update( - frc::Rotation3d{groundTruthState.pose.Rotation() + - frc::Rotation2d{distribution(generator) * 0.05_rad}}, + wpi::math::Rotation3d{groundTruthState.pose.Rotation() + + wpi::math::Rotation2d{distribution(generator) * 0.05_rad}}, {fl, fr, bl, br}); double error = groundTruthState.pose.Translation() .Distance(xhat.Translation().ToTranslation2d()) @@ -165,7 +165,7 @@ TEST_F(SwerveDriveOdometry3dTest, AccuracyFacingXAxis) { Translation2d{-1_m, -1_m}, Translation2d{-1_m, 1_m}}; SwerveDriveOdometry3d<4> odometry{ - kinematics, frc::Rotation3d{}, {zero, zero, zero, zero}}; + kinematics, wpi::math::Rotation3d{}, {zero, zero, zero, zero}}; SwerveModulePosition fl; SwerveModulePosition fr; @@ -181,8 +181,8 @@ TEST_F(SwerveDriveOdometry3dTest, AccuracyFacingXAxis) { std::default_random_engine generator; std::normal_distribution distribution(0.0, 1.0); - units::second_t dt = 20_ms; - units::second_t t = 0_s; + wpi::units::second_t dt = 20_ms; + wpi::units::second_t t = 0_s; double maxError = -std::numeric_limits::max(); double errorSum = 0; @@ -205,7 +205,7 @@ TEST_F(SwerveDriveOdometry3dTest, AccuracyFacingXAxis) { br.angle = groundTruthState.pose.Rotation(); auto xhat = odometry.Update( - frc::Rotation3d{0_rad, 0_rad, distribution(generator) * 0.05_rad}, + wpi::math::Rotation3d{0_rad, 0_rad, distribution(generator) * 0.05_rad}, {fl, fr, bl, br}); double error = groundTruthState.pose.Translation() .Distance(xhat.Translation().ToTranslation2d()) diff --git a/wpimath/src/test/native/cpp/kinematics/SwerveDriveOdometryTest.cpp b/wpimath/src/test/native/cpp/kinematics/SwerveDriveOdometryTest.cpp index 8e88f22b9d..d5a16720fd 100644 --- a/wpimath/src/test/native/cpp/kinematics/SwerveDriveOdometryTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/SwerveDriveOdometryTest.cpp @@ -13,7 +13,7 @@ #include "wpi/math/trajectory/TrajectoryConfig.hpp" #include "wpi/math/trajectory/TrajectoryGenerator.hpp" -using namespace frc; +using namespace wpi::math; static constexpr double kEpsilon = 0.01; @@ -78,7 +78,7 @@ TEST_F(SwerveDriveOdometryTest, AccuracyFacingTrajectory) { Translation2d{-1_m, -1_m}, Translation2d{-1_m, 1_m}}; SwerveDriveOdometry<4> odometry{ - kinematics, frc::Rotation2d{}, {zero, zero, zero, zero}}; + kinematics, wpi::math::Rotation2d{}, {zero, zero, zero, zero}}; SwerveModulePosition fl; SwerveModulePosition fr; @@ -94,8 +94,8 @@ TEST_F(SwerveDriveOdometryTest, AccuracyFacingTrajectory) { std::default_random_engine generator; std::normal_distribution distribution(0.0, 1.0); - units::second_t dt = 20_ms; - units::second_t t = 0_s; + wpi::units::second_t dt = 20_ms; + wpi::units::second_t t = 0_s; double maxError = -std::numeric_limits::max(); double errorSum = 0; @@ -119,7 +119,7 @@ TEST_F(SwerveDriveOdometryTest, AccuracyFacingTrajectory) { auto xhat = odometry.Update(groundTruthState.pose.Rotation() + - frc::Rotation2d{distribution(generator) * 0.05_rad}, + wpi::math::Rotation2d{distribution(generator) * 0.05_rad}, {fl, fr, bl, br}); double error = groundTruthState.pose.Translation() .Distance(xhat.Translation()) @@ -143,7 +143,7 @@ TEST_F(SwerveDriveOdometryTest, AccuracyFacingXAxis) { Translation2d{-1_m, -1_m}, Translation2d{-1_m, 1_m}}; SwerveDriveOdometry<4> odometry{ - kinematics, frc::Rotation2d{}, {zero, zero, zero, zero}}; + kinematics, wpi::math::Rotation2d{}, {zero, zero, zero, zero}}; SwerveModulePosition fl; SwerveModulePosition fr; @@ -159,8 +159,8 @@ TEST_F(SwerveDriveOdometryTest, AccuracyFacingXAxis) { std::default_random_engine generator; std::normal_distribution distribution(0.0, 1.0); - units::second_t dt = 20_ms; - units::second_t t = 0_s; + wpi::units::second_t dt = 20_ms; + wpi::units::second_t t = 0_s; double maxError = -std::numeric_limits::max(); double errorSum = 0; @@ -183,7 +183,7 @@ TEST_F(SwerveDriveOdometryTest, AccuracyFacingXAxis) { br.angle = groundTruthState.pose.Rotation(); auto xhat = odometry.Update( - frc::Rotation2d{distribution(generator) * 0.05_rad}, {fl, fr, bl, br}); + wpi::math::Rotation2d{distribution(generator) * 0.05_rad}, {fl, fr, bl, br}); double error = groundTruthState.pose.Translation() .Distance(xhat.Translation()) .value(); diff --git a/wpimath/src/test/native/cpp/kinematics/SwerveModulePositionTest.cpp b/wpimath/src/test/native/cpp/kinematics/SwerveModulePositionTest.cpp index 9baf909d38..58c5783c35 100644 --- a/wpimath/src/test/native/cpp/kinematics/SwerveModulePositionTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/SwerveModulePositionTest.cpp @@ -8,16 +8,16 @@ #include "wpi/math/kinematics/SwerveModulePosition.hpp" TEST(SwerveModulePositionTest, Equality) { - frc::SwerveModulePosition position1{2_m, 90_deg}; - frc::SwerveModulePosition position2{2_m, 90_deg}; + wpi::math::SwerveModulePosition position1{2_m, 90_deg}; + wpi::math::SwerveModulePosition position2{2_m, 90_deg}; EXPECT_EQ(position1, position2); } TEST(SwerveModulePositionTest, Inequality) { - frc::SwerveModulePosition position1{1_m, 90_deg}; - frc::SwerveModulePosition position2{2_m, 90_deg}; - frc::SwerveModulePosition position3{1_m, 89_deg}; + wpi::math::SwerveModulePosition position1{1_m, 90_deg}; + wpi::math::SwerveModulePosition position2{2_m, 90_deg}; + wpi::math::SwerveModulePosition position3{1_m, 89_deg}; EXPECT_NE(position1, position2); EXPECT_NE(position1, position3); diff --git a/wpimath/src/test/native/cpp/kinematics/SwerveModuleStateTest.cpp b/wpimath/src/test/native/cpp/kinematics/SwerveModuleStateTest.cpp index 63a8f03ab7..c1ebe1dd47 100644 --- a/wpimath/src/test/native/cpp/kinematics/SwerveModuleStateTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/SwerveModuleStateTest.cpp @@ -10,15 +10,15 @@ static constexpr double kEpsilon = 1E-9; TEST(SwerveModuleStateTest, Optimize) { - frc::Rotation2d angleA{45_deg}; - frc::SwerveModuleState refA{-2_mps, 180_deg}; + wpi::math::Rotation2d angleA{45_deg}; + wpi::math::SwerveModuleState refA{-2_mps, 180_deg}; refA.Optimize(angleA); EXPECT_NEAR(refA.speed.value(), 2.0, kEpsilon); EXPECT_NEAR(refA.angle.Degrees().value(), 0.0, kEpsilon); - frc::Rotation2d angleB{-50_deg}; - frc::SwerveModuleState refB{4.7_mps, 41_deg}; + wpi::math::Rotation2d angleB{-50_deg}; + wpi::math::SwerveModuleState refB{4.7_mps, 41_deg}; refB.Optimize(angleB); EXPECT_NEAR(refB.speed.value(), -4.7, kEpsilon); @@ -26,15 +26,15 @@ TEST(SwerveModuleStateTest, Optimize) { } TEST(SwerveModuleStateTest, NoOptimize) { - frc::Rotation2d angleA{0_deg}; - frc::SwerveModuleState refA{2_mps, 89_deg}; + wpi::math::Rotation2d angleA{0_deg}; + wpi::math::SwerveModuleState refA{2_mps, 89_deg}; refA.Optimize(angleA); EXPECT_NEAR(refA.speed.value(), 2.0, kEpsilon); EXPECT_NEAR(refA.angle.Degrees().value(), 89.0, kEpsilon); - frc::Rotation2d angleB{0_deg}; - frc::SwerveModuleState refB{-2_mps, -2_deg}; + wpi::math::Rotation2d angleB{0_deg}; + wpi::math::SwerveModuleState refB{-2_mps, -2_deg}; refB.Optimize(angleB); EXPECT_NEAR(refB.speed.value(), -2.0, kEpsilon); @@ -42,85 +42,85 @@ TEST(SwerveModuleStateTest, NoOptimize) { } TEST(SwerveModuleStateTest, CosineScaling) { - frc::Rotation2d angleA{0_deg}; - frc::SwerveModuleState refA{2_mps, 45_deg}; + wpi::math::Rotation2d angleA{0_deg}; + wpi::math::SwerveModuleState refA{2_mps, 45_deg}; refA.CosineScale(angleA); EXPECT_NEAR(refA.speed.value(), std::sqrt(2.0), kEpsilon); EXPECT_NEAR(refA.angle.Degrees().value(), 45.0, kEpsilon); - frc::Rotation2d angleB{45_deg}; - frc::SwerveModuleState refB{2_mps, 45_deg}; + wpi::math::Rotation2d angleB{45_deg}; + wpi::math::SwerveModuleState refB{2_mps, 45_deg}; refB.CosineScale(angleB); EXPECT_NEAR(refB.speed.value(), 2.0, kEpsilon); EXPECT_NEAR(refB.angle.Degrees().value(), 45.0, kEpsilon); - frc::Rotation2d angleC{-45_deg}; - frc::SwerveModuleState refC{2_mps, 45_deg}; + wpi::math::Rotation2d angleC{-45_deg}; + wpi::math::SwerveModuleState refC{2_mps, 45_deg}; refC.CosineScale(angleC); EXPECT_NEAR(refC.speed.value(), 0.0, kEpsilon); EXPECT_NEAR(refC.angle.Degrees().value(), 45.0, kEpsilon); - frc::Rotation2d angleD{135_deg}; - frc::SwerveModuleState refD{2_mps, 45_deg}; + wpi::math::Rotation2d angleD{135_deg}; + wpi::math::SwerveModuleState refD{2_mps, 45_deg}; refD.CosineScale(angleD); EXPECT_NEAR(refD.speed.value(), 0.0, kEpsilon); EXPECT_NEAR(refD.angle.Degrees().value(), 45.0, kEpsilon); - frc::Rotation2d angleE{-135_deg}; - frc::SwerveModuleState refE{2_mps, 45_deg}; + wpi::math::Rotation2d angleE{-135_deg}; + wpi::math::SwerveModuleState refE{2_mps, 45_deg}; refE.CosineScale(angleE); EXPECT_NEAR(refE.speed.value(), -2.0, kEpsilon); EXPECT_NEAR(refE.angle.Degrees().value(), 45.0, kEpsilon); - frc::Rotation2d angleF{180_deg}; - frc::SwerveModuleState refF{2_mps, 45_deg}; + wpi::math::Rotation2d angleF{180_deg}; + wpi::math::SwerveModuleState refF{2_mps, 45_deg}; refF.CosineScale(angleF); EXPECT_NEAR(refF.speed.value(), -std::sqrt(2.0), kEpsilon); EXPECT_NEAR(refF.angle.Degrees().value(), 45.0, kEpsilon); - frc::Rotation2d angleG{0_deg}; - frc::SwerveModuleState refG{-2_mps, 45_deg}; + wpi::math::Rotation2d angleG{0_deg}; + wpi::math::SwerveModuleState refG{-2_mps, 45_deg}; refG.CosineScale(angleG); EXPECT_NEAR(refG.speed.value(), -std::sqrt(2.0), kEpsilon); EXPECT_NEAR(refG.angle.Degrees().value(), 45.0, kEpsilon); - frc::Rotation2d angleH{45_deg}; - frc::SwerveModuleState refH{-2_mps, 45_deg}; + wpi::math::Rotation2d angleH{45_deg}; + wpi::math::SwerveModuleState refH{-2_mps, 45_deg}; refH.CosineScale(angleH); EXPECT_NEAR(refH.speed.value(), -2.0, kEpsilon); EXPECT_NEAR(refH.angle.Degrees().value(), 45.0, kEpsilon); - frc::Rotation2d angleI{-45_deg}; - frc::SwerveModuleState refI{-2_mps, 45_deg}; + wpi::math::Rotation2d angleI{-45_deg}; + wpi::math::SwerveModuleState refI{-2_mps, 45_deg}; refI.CosineScale(angleI); EXPECT_NEAR(refI.speed.value(), 0.0, kEpsilon); EXPECT_NEAR(refI.angle.Degrees().value(), 45.0, kEpsilon); - frc::Rotation2d angleJ{135_deg}; - frc::SwerveModuleState refJ{-2_mps, 45_deg}; + wpi::math::Rotation2d angleJ{135_deg}; + wpi::math::SwerveModuleState refJ{-2_mps, 45_deg}; refJ.CosineScale(angleJ); EXPECT_NEAR(refJ.speed.value(), 0.0, kEpsilon); EXPECT_NEAR(refJ.angle.Degrees().value(), 45.0, kEpsilon); - frc::Rotation2d angleK{-135_deg}; - frc::SwerveModuleState refK{-2_mps, 45_deg}; + wpi::math::Rotation2d angleK{-135_deg}; + wpi::math::SwerveModuleState refK{-2_mps, 45_deg}; refK.CosineScale(angleK); EXPECT_NEAR(refK.speed.value(), 2.0, kEpsilon); EXPECT_NEAR(refK.angle.Degrees().value(), 45.0, kEpsilon); - frc::Rotation2d angleL{180_deg}; - frc::SwerveModuleState refL{-2_mps, 45_deg}; + wpi::math::Rotation2d angleL{180_deg}; + wpi::math::SwerveModuleState refL{-2_mps, 45_deg}; refL.CosineScale(angleL); EXPECT_NEAR(refL.speed.value(), std::sqrt(2.0), kEpsilon); @@ -128,16 +128,16 @@ TEST(SwerveModuleStateTest, CosineScaling) { } TEST(SwerveModuleStateTest, Equality) { - frc::SwerveModuleState state1{2_mps, 90_deg}; - frc::SwerveModuleState state2{2_mps, 90_deg}; + wpi::math::SwerveModuleState state1{2_mps, 90_deg}; + wpi::math::SwerveModuleState state2{2_mps, 90_deg}; EXPECT_EQ(state1, state2); } TEST(SwerveModuleStateTest, Inequality) { - frc::SwerveModuleState state1{1_mps, 90_deg}; - frc::SwerveModuleState state2{2_mps, 90_deg}; - frc::SwerveModuleState state3{1_mps, 89_deg}; + wpi::math::SwerveModuleState state1{1_mps, 90_deg}; + wpi::math::SwerveModuleState state2{2_mps, 90_deg}; + wpi::math::SwerveModuleState state3{1_mps, 89_deg}; EXPECT_NE(state1, state2); EXPECT_NE(state1, state3); diff --git a/wpimath/src/test/native/cpp/kinematics/proto/ChassisSpeedsProtoTest.cpp b/wpimath/src/test/native/cpp/kinematics/proto/ChassisSpeedsProtoTest.cpp index 682d197915..245ec01e60 100644 --- a/wpimath/src/test/native/cpp/kinematics/proto/ChassisSpeedsProtoTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/proto/ChassisSpeedsProtoTest.cpp @@ -7,7 +7,7 @@ #include "wpi/math/kinematics/ChassisSpeeds.hpp" #include "wpi/util/SmallVector.hpp" -using namespace frc; +using namespace wpi::math; namespace { @@ -16,8 +16,8 @@ const ChassisSpeeds kExpectedData = } // namespace TEST(ChassisSpeedsProtoTest, Roundtrip) { - wpi::ProtobufMessage message; - wpi::SmallVector buf; + wpi::util::ProtobufMessage message; + wpi::util::SmallVector buf; ASSERT_TRUE(message.Pack(buf, kExpectedData)); auto unpacked_data = message.Unpack(buf); diff --git a/wpimath/src/test/native/cpp/kinematics/proto/DifferentialDriveKinematicsProtoTest.cpp b/wpimath/src/test/native/cpp/kinematics/proto/DifferentialDriveKinematicsProtoTest.cpp index 7e74b05484..17b0e5a252 100644 --- a/wpimath/src/test/native/cpp/kinematics/proto/DifferentialDriveKinematicsProtoTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/proto/DifferentialDriveKinematicsProtoTest.cpp @@ -7,7 +7,7 @@ #include "wpi/math/kinematics/DifferentialDriveKinematics.hpp" #include "wpi/util/SmallVector.hpp" -using namespace frc; +using namespace wpi::math; namespace { @@ -16,8 +16,8 @@ const DifferentialDriveKinematics kExpectedData = } // namespace TEST(DifferentialDriveKinematicsProtoTest, Roundtrip) { - wpi::ProtobufMessage message; - wpi::SmallVector buf; + wpi::util::ProtobufMessage message; + wpi::util::SmallVector buf; ASSERT_TRUE(message.Pack(buf, kExpectedData)); auto unpacked_data = message.Unpack(buf); diff --git a/wpimath/src/test/native/cpp/kinematics/proto/DifferentialDriveWheelSpeedsProtoTest.cpp b/wpimath/src/test/native/cpp/kinematics/proto/DifferentialDriveWheelSpeedsProtoTest.cpp index 21d3ad6b3e..9406369c32 100644 --- a/wpimath/src/test/native/cpp/kinematics/proto/DifferentialDriveWheelSpeedsProtoTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/proto/DifferentialDriveWheelSpeedsProtoTest.cpp @@ -7,7 +7,7 @@ #include "wpi/math/kinematics/DifferentialDriveWheelSpeeds.hpp" #include "wpi/util/SmallVector.hpp" -using namespace frc; +using namespace wpi::math; namespace { @@ -16,8 +16,8 @@ const DifferentialDriveWheelSpeeds kExpectedData = } // namespace TEST(DifferentialDriveWheelSpeedsProtoTest, Roundtrip) { - wpi::ProtobufMessage message; - wpi::SmallVector buf; + wpi::util::ProtobufMessage message; + wpi::util::SmallVector buf; ASSERT_TRUE(message.Pack(buf, kExpectedData)); auto unpacked_data = message.Unpack(buf); diff --git a/wpimath/src/test/native/cpp/kinematics/proto/MecanumDriveKinematicsProtoTest.cpp b/wpimath/src/test/native/cpp/kinematics/proto/MecanumDriveKinematicsProtoTest.cpp index 03ac227596..49fe8daeed 100644 --- a/wpimath/src/test/native/cpp/kinematics/proto/MecanumDriveKinematicsProtoTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/proto/MecanumDriveKinematicsProtoTest.cpp @@ -7,7 +7,7 @@ #include "wpi/math/kinematics/MecanumDriveKinematics.hpp" #include "wpi/util/SmallVector.hpp" -using namespace frc; +using namespace wpi::math; namespace { @@ -17,8 +17,8 @@ const MecanumDriveKinematics kExpectedData = MecanumDriveKinematics{ } // namespace TEST(MecanumDriveKinematicsProtoTest, Roundtrip) { - wpi::ProtobufMessage message; - wpi::SmallVector buf; + wpi::util::ProtobufMessage message; + wpi::util::SmallVector buf; ASSERT_TRUE(message.Pack(buf, kExpectedData)); auto unpacked_data = message.Unpack(buf); diff --git a/wpimath/src/test/native/cpp/kinematics/proto/MecanumDriveWheelPositionsProtoTest.cpp b/wpimath/src/test/native/cpp/kinematics/proto/MecanumDriveWheelPositionsProtoTest.cpp index 82ca0605ff..4fe5547a52 100644 --- a/wpimath/src/test/native/cpp/kinematics/proto/MecanumDriveWheelPositionsProtoTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/proto/MecanumDriveWheelPositionsProtoTest.cpp @@ -7,7 +7,7 @@ #include "wpi/math/kinematics/MecanumDriveWheelPositions.hpp" #include "wpi/util/SmallVector.hpp" -using namespace frc; +using namespace wpi::math; namespace { @@ -16,8 +16,8 @@ const MecanumDriveWheelPositions kExpectedData = } // namespace TEST(MecanumDriveWheelPositionsProtoTest, Roundtrip) { - wpi::ProtobufMessage message; - wpi::SmallVector buf; + wpi::util::ProtobufMessage message; + wpi::util::SmallVector buf; ASSERT_TRUE(message.Pack(buf, kExpectedData)); auto unpacked_data = message.Unpack(buf); diff --git a/wpimath/src/test/native/cpp/kinematics/proto/MecanumDriveWheelSpeedsProtoTest.cpp b/wpimath/src/test/native/cpp/kinematics/proto/MecanumDriveWheelSpeedsProtoTest.cpp index 9981b67e4e..711140f524 100644 --- a/wpimath/src/test/native/cpp/kinematics/proto/MecanumDriveWheelSpeedsProtoTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/proto/MecanumDriveWheelSpeedsProtoTest.cpp @@ -7,7 +7,7 @@ #include "wpi/math/kinematics/MecanumDriveWheelSpeeds.hpp" #include "wpi/util/SmallVector.hpp" -using namespace frc; +using namespace wpi::math; namespace { @@ -16,8 +16,8 @@ const MecanumDriveWheelSpeeds kExpectedData = } // namespace TEST(MecanumDriveWheelSpeedsProtoTest, Roundtrip) { - wpi::ProtobufMessage message; - wpi::SmallVector buf; + wpi::util::ProtobufMessage message; + wpi::util::SmallVector buf; ASSERT_TRUE(message.Pack(buf, kExpectedData)); auto unpacked_data = message.Unpack(buf); diff --git a/wpimath/src/test/native/cpp/kinematics/proto/SwerveDriveKinematicsProtoTest.cpp b/wpimath/src/test/native/cpp/kinematics/proto/SwerveDriveKinematicsProtoTest.cpp index bc6de1a0df..b8475b1bf0 100644 --- a/wpimath/src/test/native/cpp/kinematics/proto/SwerveDriveKinematicsProtoTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/proto/SwerveDriveKinematicsProtoTest.cpp @@ -8,14 +8,14 @@ #include "wpi/math/kinematics/SwerveDriveKinematics.hpp" #include "wpi/math/kinematics/proto/SwerveDriveKinematicsProto.hpp" -using namespace frc; +using namespace wpi::math; struct SwerveDriveKinematicsProtoTestData { using Type = SwerveDriveKinematics<4>; inline static const Type kTestData{ - frc::Translation2d{1.0_m, 0.9_m}, frc::Translation2d{1.1_m, -0.8_m}, - frc::Translation2d{-1.2_m, 0.7_m}, frc::Translation2d{-1.3_m, -0.6_m}}; + wpi::math::Translation2d{1.0_m, 0.9_m}, wpi::math::Translation2d{1.1_m, -0.8_m}, + wpi::math::Translation2d{-1.2_m, 0.7_m}, wpi::math::Translation2d{-1.3_m, -0.6_m}}; static void CheckEq(const Type& testData, const Type& data) { EXPECT_EQ(testData.GetModules(), data.GetModules()); diff --git a/wpimath/src/test/native/cpp/kinematics/proto/SwerveModulePositionProtoTest.cpp b/wpimath/src/test/native/cpp/kinematics/proto/SwerveModulePositionProtoTest.cpp index c3d7d480df..095810f03e 100644 --- a/wpimath/src/test/native/cpp/kinematics/proto/SwerveModulePositionProtoTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/proto/SwerveModulePositionProtoTest.cpp @@ -7,7 +7,7 @@ #include "wpi/math/kinematics/SwerveModulePosition.hpp" #include "wpi/util/SmallVector.hpp" -using namespace frc; +using namespace wpi::math; namespace { @@ -16,8 +16,8 @@ const SwerveModulePosition kExpectedData = } // namespace TEST(SwerveModulePositionProtoTest, Roundtrip) { - wpi::ProtobufMessage message; - wpi::SmallVector buf; + wpi::util::ProtobufMessage message; + wpi::util::SmallVector buf; ASSERT_TRUE(message.Pack(buf, kExpectedData)); auto unpacked_data = message.Unpack(buf); diff --git a/wpimath/src/test/native/cpp/kinematics/proto/SwerveModuleStateProtoTest.cpp b/wpimath/src/test/native/cpp/kinematics/proto/SwerveModuleStateProtoTest.cpp index 670ff10584..b0b871b82e 100644 --- a/wpimath/src/test/native/cpp/kinematics/proto/SwerveModuleStateProtoTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/proto/SwerveModuleStateProtoTest.cpp @@ -7,7 +7,7 @@ #include "wpi/math/kinematics/SwerveModuleState.hpp" #include "wpi/util/SmallVector.hpp" -using namespace frc; +using namespace wpi::math; namespace { @@ -16,8 +16,8 @@ const SwerveModuleState kExpectedData = } // namespace TEST(SwerveModuleStateProtoTest, Roundtrip) { - wpi::ProtobufMessage message; - wpi::SmallVector buf; + wpi::util::ProtobufMessage message; + wpi::util::SmallVector buf; ASSERT_TRUE(message.Pack(buf, kExpectedData)); auto unpacked_data = message.Unpack(buf); diff --git a/wpimath/src/test/native/cpp/kinematics/struct/ChassisSpeedsStructTest.cpp b/wpimath/src/test/native/cpp/kinematics/struct/ChassisSpeedsStructTest.cpp index a22de755e6..6a31491b75 100644 --- a/wpimath/src/test/native/cpp/kinematics/struct/ChassisSpeedsStructTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/struct/ChassisSpeedsStructTest.cpp @@ -6,11 +6,11 @@ #include "wpi/math/kinematics/ChassisSpeeds.hpp" -using namespace frc; +using namespace wpi::math; namespace { -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; const ChassisSpeeds kExpectedData{ ChassisSpeeds{2.29_mps, 2.2_mps, 0.3504_rad_per_s}}; } // namespace diff --git a/wpimath/src/test/native/cpp/kinematics/struct/DifferentialDriveKinematicsStructTest.cpp b/wpimath/src/test/native/cpp/kinematics/struct/DifferentialDriveKinematicsStructTest.cpp index a0e6cf693f..b74dfb27de 100644 --- a/wpimath/src/test/native/cpp/kinematics/struct/DifferentialDriveKinematicsStructTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/struct/DifferentialDriveKinematicsStructTest.cpp @@ -6,11 +6,11 @@ #include "wpi/math/kinematics/DifferentialDriveKinematics.hpp" -using namespace frc; +using namespace wpi::math; namespace { -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; const DifferentialDriveKinematics kExpectedData{ DifferentialDriveKinematics{1.74_m}}; } // namespace diff --git a/wpimath/src/test/native/cpp/kinematics/struct/DifferentialDriveWheelPositionsStructTest.cpp b/wpimath/src/test/native/cpp/kinematics/struct/DifferentialDriveWheelPositionsStructTest.cpp index 75b83e4f59..7aa770a8e4 100644 --- a/wpimath/src/test/native/cpp/kinematics/struct/DifferentialDriveWheelPositionsStructTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/struct/DifferentialDriveWheelPositionsStructTest.cpp @@ -6,11 +6,11 @@ #include "wpi/math/kinematics/DifferentialDriveWheelPositions.hpp" -using namespace frc; +using namespace wpi::math; namespace { -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; const DifferentialDriveWheelPositions kExpectedData{ DifferentialDriveWheelPositions{1.74_m, 35.04_m}}; } // namespace diff --git a/wpimath/src/test/native/cpp/kinematics/struct/DifferentialDriveWheelSpeedsStructTest.cpp b/wpimath/src/test/native/cpp/kinematics/struct/DifferentialDriveWheelSpeedsStructTest.cpp index 9d68fc9e7a..c35a55c3a5 100644 --- a/wpimath/src/test/native/cpp/kinematics/struct/DifferentialDriveWheelSpeedsStructTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/struct/DifferentialDriveWheelSpeedsStructTest.cpp @@ -6,11 +6,11 @@ #include "wpi/math/kinematics/DifferentialDriveWheelSpeeds.hpp" -using namespace frc; +using namespace wpi::math; namespace { -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; const DifferentialDriveWheelSpeeds kExpectedData{ DifferentialDriveWheelSpeeds{1.74_mps, 35.04_mps}}; } // namespace diff --git a/wpimath/src/test/native/cpp/kinematics/struct/MecanumDriveKinematicsStructTest.cpp b/wpimath/src/test/native/cpp/kinematics/struct/MecanumDriveKinematicsStructTest.cpp index 492ba94fae..82ed1ddc63 100644 --- a/wpimath/src/test/native/cpp/kinematics/struct/MecanumDriveKinematicsStructTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/struct/MecanumDriveKinematicsStructTest.cpp @@ -6,11 +6,11 @@ #include "wpi/math/kinematics/MecanumDriveKinematics.hpp" -using namespace frc; +using namespace wpi::math; namespace { -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; const MecanumDriveKinematics kExpectedData{MecanumDriveKinematics{ Translation2d{19.1_m, 2.2_m}, Translation2d{35.04_m, 1.91_m}, Translation2d{1.74_m, 3.504_m}, Translation2d{3.504_m, 1.91_m}}}; diff --git a/wpimath/src/test/native/cpp/kinematics/struct/MecanumDriveWheelPositionsStructTest.cpp b/wpimath/src/test/native/cpp/kinematics/struct/MecanumDriveWheelPositionsStructTest.cpp index c9ba803810..d39f515eff 100644 --- a/wpimath/src/test/native/cpp/kinematics/struct/MecanumDriveWheelPositionsStructTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/struct/MecanumDriveWheelPositionsStructTest.cpp @@ -6,11 +6,11 @@ #include "wpi/math/kinematics/MecanumDriveWheelPositions.hpp" -using namespace frc; +using namespace wpi::math; namespace { -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; const MecanumDriveWheelPositions kExpectedData{ MecanumDriveWheelPositions{17.4_m, 2.29_m, 22.9_m, 1.74_m}}; } // namespace diff --git a/wpimath/src/test/native/cpp/kinematics/struct/MecanumDriveWheelSpeedsStructTest.cpp b/wpimath/src/test/native/cpp/kinematics/struct/MecanumDriveWheelSpeedsStructTest.cpp index 42122c192b..b8604754ee 100644 --- a/wpimath/src/test/native/cpp/kinematics/struct/MecanumDriveWheelSpeedsStructTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/struct/MecanumDriveWheelSpeedsStructTest.cpp @@ -6,11 +6,11 @@ #include "wpi/math/kinematics/MecanumDriveWheelSpeeds.hpp" -using namespace frc; +using namespace wpi::math; namespace { -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; const MecanumDriveWheelSpeeds kExpectedData{ MecanumDriveWheelSpeeds{2.29_mps, 17.4_mps, 4.4_mps, 0.229_mps}}; } // namespace diff --git a/wpimath/src/test/native/cpp/kinematics/struct/SwerveDriveKinematicsStructTest.cpp b/wpimath/src/test/native/cpp/kinematics/struct/SwerveDriveKinematicsStructTest.cpp index 6261ec16b2..eeeb01f67f 100644 --- a/wpimath/src/test/native/cpp/kinematics/struct/SwerveDriveKinematicsStructTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/struct/SwerveDriveKinematicsStructTest.cpp @@ -8,14 +8,14 @@ #include "wpi/math/kinematics/SwerveDriveKinematics.hpp" #include "wpi/math/kinematics/struct/SwerveDriveKinematicsStruct.hpp" -using namespace frc; +using namespace wpi::math; struct SwerveDriveKinematicsStructTestData { using Type = SwerveDriveKinematics<4>; inline static const Type kTestData{ - frc::Translation2d{1.0_m, 0.9_m}, frc::Translation2d{1.1_m, -0.8_m}, - frc::Translation2d{-1.2_m, 0.7_m}, frc::Translation2d{-1.3_m, -0.6_m}}; + wpi::math::Translation2d{1.0_m, 0.9_m}, wpi::math::Translation2d{1.1_m, -0.8_m}, + wpi::math::Translation2d{-1.2_m, 0.7_m}, wpi::math::Translation2d{-1.3_m, -0.6_m}}; static void CheckEq(const Type& testData, const Type& data) { EXPECT_EQ(testData.GetModules(), data.GetModules()); diff --git a/wpimath/src/test/native/cpp/kinematics/struct/SwerveModulePositionStructTest.cpp b/wpimath/src/test/native/cpp/kinematics/struct/SwerveModulePositionStructTest.cpp index 6bd9ebd3e7..5ae0277d2b 100644 --- a/wpimath/src/test/native/cpp/kinematics/struct/SwerveModulePositionStructTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/struct/SwerveModulePositionStructTest.cpp @@ -6,11 +6,11 @@ #include "wpi/math/kinematics/SwerveModulePosition.hpp" -using namespace frc; +using namespace wpi::math; namespace { -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; const SwerveModulePosition kExpectedData{ SwerveModulePosition{3.504_m, Rotation2d{17.4_rad}}}; } // namespace diff --git a/wpimath/src/test/native/cpp/kinematics/struct/SwerveModuleStateStructTest.cpp b/wpimath/src/test/native/cpp/kinematics/struct/SwerveModuleStateStructTest.cpp index 752d28d8a2..9bfd335844 100644 --- a/wpimath/src/test/native/cpp/kinematics/struct/SwerveModuleStateStructTest.cpp +++ b/wpimath/src/test/native/cpp/kinematics/struct/SwerveModuleStateStructTest.cpp @@ -6,11 +6,11 @@ #include "wpi/math/kinematics/SwerveModuleState.hpp" -using namespace frc; +using namespace wpi::math; namespace { -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; const SwerveModuleState kExpectedData{ SwerveModuleState{22.9_mps, Rotation2d{3.3_rad}}}; } // namespace diff --git a/wpimath/src/test/native/cpp/optimization/SimulatedAnnealingTest.cpp b/wpimath/src/test/native/cpp/optimization/SimulatedAnnealingTest.cpp index 56ccc88338..b59fe8725e 100644 --- a/wpimath/src/test/native/cpp/optimization/SimulatedAnnealingTest.cpp +++ b/wpimath/src/test/native/cpp/optimization/SimulatedAnnealingTest.cpp @@ -21,7 +21,7 @@ TEST(SimulatedAnnealingTest, DoubleFunctionOptimizationHeartBeat) { std::mt19937 gen{rd()}; std::uniform_real_distribution<> distr{0.0, 1.0}; - frc::SimulatedAnnealing simulatedAnnealing{ + wpi::math::SimulatedAnnealing simulatedAnnealing{ 2.0, [&](const double& x) { return std::clamp(x + (distr(gen) - 0.5) * stepSize, -3.0, 3.0); @@ -44,7 +44,7 @@ TEST(SimulatedAnnealingTest, DoubleFunctionOptimizationMultimodal) { std::mt19937 gen{rd()}; std::uniform_real_distribution<> distr{0.0, 1.0}; - frc::SimulatedAnnealing simulatedAnnealing{ + wpi::math::SimulatedAnnealing simulatedAnnealing{ 2.0, [&](const double& x) { return std::clamp(x + (distr(gen) - 0.5) * stepSize, 0.0, 7.0); diff --git a/wpimath/src/test/native/cpp/path/TravelingSalesmanTest.cpp b/wpimath/src/test/native/cpp/path/TravelingSalesmanTest.cpp index c180506628..679d9dab3e 100644 --- a/wpimath/src/test/native/cpp/path/TravelingSalesmanTest.cpp +++ b/wpimath/src/test/native/cpp/path/TravelingSalesmanTest.cpp @@ -21,12 +21,12 @@ * @param expected The expected cycle. * @param actual The actual cycle. */ -bool IsMatchingCycle(std::span expected, - std::span actual) { +bool IsMatchingCycle(std::span expected, + std::span actual) { assert(expected.size() == actual.size()); // Check actual has expected cycle (forward) - wpi::circular_buffer actualBufferForward{expected.size()}; + wpi::util::circular_buffer actualBufferForward{expected.size()}; for (size_t i = 0; i < actual.size(); ++i) { actualBufferForward.push_back(actual[i % actual.size()]); } @@ -36,7 +36,7 @@ bool IsMatchingCycle(std::span expected, } // Check actual has expected cycle (reverse) - wpi::circular_buffer actualBufferReverse{expected.size()}; + wpi::util::circular_buffer actualBufferReverse{expected.size()}; for (size_t i = 0; i < actual.size(); ++i) { actualBufferReverse.push_front(actual[(1 + i) % actual.size()]); } @@ -56,15 +56,15 @@ TEST(TravelingSalesmanTest, FiveLengthStaticPathWithDistanceCost) { // ................... // ....3.....1........ // ................... - wpi::array poses{ - frc::Pose2d{3_m, 3_m, 0_rad}, frc::Pose2d{11_m, 5_m, 0_rad}, - frc::Pose2d{9_m, 2_m, 0_rad}, frc::Pose2d{5_m, 5_m, 0_rad}, - frc::Pose2d{14_m, 3_m, 0_rad}}; + wpi::util::array poses{ + wpi::math::Pose2d{3_m, 3_m, 0_rad}, wpi::math::Pose2d{11_m, 5_m, 0_rad}, + wpi::math::Pose2d{9_m, 2_m, 0_rad}, wpi::math::Pose2d{5_m, 5_m, 0_rad}, + wpi::math::Pose2d{14_m, 3_m, 0_rad}}; - frc::TravelingSalesman traveler; - wpi::array solution = traveler.Solve(poses, 500); + wpi::math::TravelingSalesman traveler; + wpi::util::array solution = traveler.Solve(poses, 500); - wpi::array expected{poses[0], poses[2], poses[4], poses[1], + wpi::util::array expected{poses[0], poses[2], poses[4], poses[1], poses[3]}; EXPECT_TRUE(IsMatchingCycle(expected, solution)); @@ -77,17 +77,17 @@ TEST(TravelingSalesmanTest, FiveLengthDynamicPathWithDistanceCost) { // ................... // ....3.....1........ // ................... - wpi::array poses{ - frc::Pose2d{3_m, 3_m, 0_rad}, frc::Pose2d{11_m, 5_m, 0_rad}, - frc::Pose2d{9_m, 2_m, 0_rad}, frc::Pose2d{5_m, 5_m, 0_rad}, - frc::Pose2d{14_m, 3_m, 0_rad}}; + wpi::util::array poses{ + wpi::math::Pose2d{3_m, 3_m, 0_rad}, wpi::math::Pose2d{11_m, 5_m, 0_rad}, + wpi::math::Pose2d{9_m, 2_m, 0_rad}, wpi::math::Pose2d{5_m, 5_m, 0_rad}, + wpi::math::Pose2d{14_m, 3_m, 0_rad}}; - frc::TravelingSalesman traveler; - std::vector solution = - traveler.Solve(std::span{poses}, 500); + wpi::math::TravelingSalesman traveler; + std::vector solution = + traveler.Solve(std::span{poses}, 500); ASSERT_EQ(5u, solution.size()); - wpi::array expected{poses[0], poses[2], poses[4], poses[1], + wpi::util::array expected{poses[0], poses[2], poses[4], poses[1], poses[3]}; EXPECT_TRUE(IsMatchingCycle(expected, solution)); @@ -100,17 +100,17 @@ TEST(TravelingSalesmanTest, TenLengthStaticPathWithDistanceCost) { // .0................. // .....7..5...8...... // ................... - wpi::array poses{ - frc::Pose2d{2_m, 4_m, 0_rad}, frc::Pose2d{10_m, 1_m, 0_rad}, - frc::Pose2d{12_m, 1_m, 0_rad}, frc::Pose2d{7_m, 1_m, 0_rad}, - frc::Pose2d{3_m, 2_m, 0_rad}, frc::Pose2d{9_m, 5_m, 0_rad}, - frc::Pose2d{5_m, 1_m, 0_rad}, frc::Pose2d{6_m, 5_m, 0_rad}, - frc::Pose2d{13_m, 5_m, 0_rad}, frc::Pose2d{14_m, 3_m, 0_rad}}; + wpi::util::array poses{ + wpi::math::Pose2d{2_m, 4_m, 0_rad}, wpi::math::Pose2d{10_m, 1_m, 0_rad}, + wpi::math::Pose2d{12_m, 1_m, 0_rad}, wpi::math::Pose2d{7_m, 1_m, 0_rad}, + wpi::math::Pose2d{3_m, 2_m, 0_rad}, wpi::math::Pose2d{9_m, 5_m, 0_rad}, + wpi::math::Pose2d{5_m, 1_m, 0_rad}, wpi::math::Pose2d{6_m, 5_m, 0_rad}, + wpi::math::Pose2d{13_m, 5_m, 0_rad}, wpi::math::Pose2d{14_m, 3_m, 0_rad}}; - frc::TravelingSalesman traveler; - wpi::array solution = traveler.Solve(poses, 500); + wpi::math::TravelingSalesman traveler; + wpi::util::array solution = traveler.Solve(poses, 500); - wpi::array expected{poses[0], poses[4], poses[6], poses[3], + wpi::util::array expected{poses[0], poses[4], poses[6], poses[3], poses[1], poses[2], poses[9], poses[8], poses[5], poses[7]}; @@ -124,19 +124,19 @@ TEST(TravelingSalesmanTest, TenLengthDynamicPathWithDistanceCost) { // .0................. // .....7..5...8...... // ................... - wpi::array poses{ - frc::Pose2d{2_m, 4_m, 0_rad}, frc::Pose2d{10_m, 1_m, 0_rad}, - frc::Pose2d{12_m, 1_m, 0_rad}, frc::Pose2d{7_m, 1_m, 0_rad}, - frc::Pose2d{3_m, 2_m, 0_rad}, frc::Pose2d{9_m, 5_m, 0_rad}, - frc::Pose2d{5_m, 1_m, 0_rad}, frc::Pose2d{6_m, 5_m, 0_rad}, - frc::Pose2d{13_m, 5_m, 0_rad}, frc::Pose2d{14_m, 3_m, 0_rad}}; + wpi::util::array poses{ + wpi::math::Pose2d{2_m, 4_m, 0_rad}, wpi::math::Pose2d{10_m, 1_m, 0_rad}, + wpi::math::Pose2d{12_m, 1_m, 0_rad}, wpi::math::Pose2d{7_m, 1_m, 0_rad}, + wpi::math::Pose2d{3_m, 2_m, 0_rad}, wpi::math::Pose2d{9_m, 5_m, 0_rad}, + wpi::math::Pose2d{5_m, 1_m, 0_rad}, wpi::math::Pose2d{6_m, 5_m, 0_rad}, + wpi::math::Pose2d{13_m, 5_m, 0_rad}, wpi::math::Pose2d{14_m, 3_m, 0_rad}}; - frc::TravelingSalesman traveler; - std::vector solution = - traveler.Solve(std::span{poses}, 500); + wpi::math::TravelingSalesman traveler; + std::vector solution = + traveler.Solve(std::span{poses}, 500); ASSERT_EQ(10u, solution.size()); - wpi::array expected{poses[0], poses[4], poses[6], poses[3], + wpi::util::array expected{poses[0], poses[4], poses[6], poses[3], poses[1], poses[2], poses[9], poses[8], poses[5], poses[7]}; diff --git a/wpimath/src/test/native/cpp/proto/MatrixProtoTest.cpp b/wpimath/src/test/native/cpp/proto/MatrixProtoTest.cpp index 0023afae8b..3112b0e411 100644 --- a/wpimath/src/test/native/cpp/proto/MatrixProtoTest.cpp +++ b/wpimath/src/test/native/cpp/proto/MatrixProtoTest.cpp @@ -8,7 +8,7 @@ #include "wpi/math/linalg/EigenCore.hpp" #include "wpi/math/linalg/proto/MatrixProto.hpp" -using namespace frc; +using namespace wpi::math; struct MatrixProtoTestData { using Type = Matrixd<2, 3>; diff --git a/wpimath/src/test/native/cpp/proto/VectorProtoTest.cpp b/wpimath/src/test/native/cpp/proto/VectorProtoTest.cpp index 5b0881230f..ecd25273d0 100644 --- a/wpimath/src/test/native/cpp/proto/VectorProtoTest.cpp +++ b/wpimath/src/test/native/cpp/proto/VectorProtoTest.cpp @@ -8,7 +8,7 @@ #include "wpi/math/linalg/EigenCore.hpp" #include "wpi/math/linalg/proto/VectorProto.hpp" -using namespace frc; +using namespace wpi::math; struct VectorProtoTestData { using Type = Vectord<2>; diff --git a/wpimath/src/test/native/cpp/spline/CubicHermiteSplineTest.cpp b/wpimath/src/test/native/cpp/spline/CubicHermiteSplineTest.cpp index d66a2717f2..6e44e1b724 100644 --- a/wpimath/src/test/native/cpp/spline/CubicHermiteSplineTest.cpp +++ b/wpimath/src/test/native/cpp/spline/CubicHermiteSplineTest.cpp @@ -14,9 +14,9 @@ #include "wpi/math/spline/SplineParameterizer.hpp" #include "wpi/units/length.hpp" -using namespace frc; +using namespace wpi::math; -namespace frc { +namespace wpi::math { class CubicHermiteSplineTest : public ::testing::Test { protected: static void Run(const Pose2d& a, const std::vector& waypoints, @@ -79,7 +79,7 @@ class CubicHermiteSplineTest : public ::testing::Test { b.Rotation().Radians().value(), 1E-9); } }; -} // namespace frc +} // namespace wpi::math TEST_F(CubicHermiteSplineTest, StraightLine) { Run(Pose2d{}, std::vector(), Pose2d{3_m, 0_m, 0_deg}); diff --git a/wpimath/src/test/native/cpp/spline/QuinticHermiteSplineTest.cpp b/wpimath/src/test/native/cpp/spline/QuinticHermiteSplineTest.cpp index 556edef50c..9fb801b2e0 100644 --- a/wpimath/src/test/native/cpp/spline/QuinticHermiteSplineTest.cpp +++ b/wpimath/src/test/native/cpp/spline/QuinticHermiteSplineTest.cpp @@ -14,9 +14,9 @@ #include "wpi/units/angle.hpp" #include "wpi/units/length.hpp" -using namespace frc; +using namespace wpi::math; -namespace frc { +namespace wpi::math { class QuinticHermiteSplineTest : public ::testing::Test { protected: static void Run(const Pose2d& a, const Pose2d& b) { @@ -51,7 +51,7 @@ class QuinticHermiteSplineTest : public ::testing::Test { b.Rotation().Radians().value(), 1E-9); } }; -} // namespace frc +} // namespace wpi::math TEST_F(QuinticHermiteSplineTest, StraightLine) { Run(Pose2d{}, Pose2d{3_m, 0_m, 0_deg}); diff --git a/wpimath/src/test/native/cpp/spline/proto/CubicHermiteSplineProtoTest.cpp b/wpimath/src/test/native/cpp/spline/proto/CubicHermiteSplineProtoTest.cpp index 1f2eb5626f..40dba6251e 100644 --- a/wpimath/src/test/native/cpp/spline/proto/CubicHermiteSplineProtoTest.cpp +++ b/wpimath/src/test/native/cpp/spline/proto/CubicHermiteSplineProtoTest.cpp @@ -7,14 +7,14 @@ #include "../../ProtoTestBase.hpp" #include "wpi/math/spline/CubicHermiteSpline.hpp" -using namespace frc; +using namespace wpi::math; struct CubicHermiteSplineProtoTestData { using Type = CubicHermiteSpline; inline static const Type kTestData{ - wpi::array{{0.1, 0.2}}, wpi::array{{0.3, 0.4}}, - wpi::array{{0.5, 0.6}}, wpi::array{{0.7, 0.8}}}; + wpi::util::array{{0.1, 0.2}}, wpi::util::array{{0.3, 0.4}}, + wpi::util::array{{0.5, 0.6}}, wpi::util::array{{0.7, 0.8}}}; static void CheckEq(const Type& testData, const Type& data) { EXPECT_EQ(testData.GetInitialControlVector().x, diff --git a/wpimath/src/test/native/cpp/spline/proto/QuinticHermiteSplineProtoTest.cpp b/wpimath/src/test/native/cpp/spline/proto/QuinticHermiteSplineProtoTest.cpp index 6efc580e17..aff66d39bf 100644 --- a/wpimath/src/test/native/cpp/spline/proto/QuinticHermiteSplineProtoTest.cpp +++ b/wpimath/src/test/native/cpp/spline/proto/QuinticHermiteSplineProtoTest.cpp @@ -7,15 +7,15 @@ #include "../../ProtoTestBase.hpp" #include "wpi/math/spline/QuinticHermiteSpline.hpp" -using namespace frc; +using namespace wpi::math; struct QuinticHermiteSplineProtoTestData { using Type = QuinticHermiteSpline; - inline static const Type kTestData{wpi::array{{0.01, 0.02, 0.03}}, - wpi::array{{0.04, 0.05, 0.06}}, - wpi::array{{0.07, 0.08, 0.09}}, - wpi::array{{0.10, 0.11, 0.11}}}; + inline static const Type kTestData{wpi::util::array{{0.01, 0.02, 0.03}}, + wpi::util::array{{0.04, 0.05, 0.06}}, + wpi::util::array{{0.07, 0.08, 0.09}}, + wpi::util::array{{0.10, 0.11, 0.11}}}; static void CheckEq(const Type& testData, const Type& data) { EXPECT_EQ(testData.GetInitialControlVector().x, diff --git a/wpimath/src/test/native/cpp/spline/struct/CubicHermiteSplineStructTest.cpp b/wpimath/src/test/native/cpp/spline/struct/CubicHermiteSplineStructTest.cpp index 3f269a1731..d315abb91c 100644 --- a/wpimath/src/test/native/cpp/spline/struct/CubicHermiteSplineStructTest.cpp +++ b/wpimath/src/test/native/cpp/spline/struct/CubicHermiteSplineStructTest.cpp @@ -7,14 +7,14 @@ #include "../../StructTestBase.hpp" #include "wpi/math/spline/CubicHermiteSpline.hpp" -using namespace frc; +using namespace wpi::math; struct CubicHermiteSplineStructTestData { using Type = CubicHermiteSpline; inline static const Type kTestData{ - wpi::array{{0.1, 0.2}}, wpi::array{{0.3, 0.4}}, - wpi::array{{0.5, 0.6}}, wpi::array{{0.7, 0.8}}}; + wpi::util::array{{0.1, 0.2}}, wpi::util::array{{0.3, 0.4}}, + wpi::util::array{{0.5, 0.6}}, wpi::util::array{{0.7, 0.8}}}; static void CheckEq(const Type& testData, const Type& data) { EXPECT_EQ(testData.GetInitialControlVector().x, diff --git a/wpimath/src/test/native/cpp/spline/struct/QuinticHermiteSplineStructTest.cpp b/wpimath/src/test/native/cpp/spline/struct/QuinticHermiteSplineStructTest.cpp index 2deb6dee37..1fc254581e 100644 --- a/wpimath/src/test/native/cpp/spline/struct/QuinticHermiteSplineStructTest.cpp +++ b/wpimath/src/test/native/cpp/spline/struct/QuinticHermiteSplineStructTest.cpp @@ -7,15 +7,15 @@ #include "../../StructTestBase.hpp" #include "wpi/math/spline/QuinticHermiteSpline.hpp" -using namespace frc; +using namespace wpi::math; struct QuinticHermiteSplineStructTestData { using Type = QuinticHermiteSpline; - inline static const Type kTestData{wpi::array{{0.01, 0.02, 0.03}}, - wpi::array{{0.04, 0.05, 0.06}}, - wpi::array{{0.07, 0.08, 0.09}}, - wpi::array{{0.10, 0.11, 0.11}}}; + inline static const Type kTestData{wpi::util::array{{0.01, 0.02, 0.03}}, + wpi::util::array{{0.04, 0.05, 0.06}}, + wpi::util::array{{0.07, 0.08, 0.09}}, + wpi::util::array{{0.10, 0.11, 0.11}}}; static void CheckEq(const Type& testData, const Type& data) { EXPECT_EQ(testData.GetInitialControlVector().x, diff --git a/wpimath/src/test/native/cpp/struct/MatrixStructTest.cpp b/wpimath/src/test/native/cpp/struct/MatrixStructTest.cpp index 6faf3600f4..645f9a3082 100644 --- a/wpimath/src/test/native/cpp/struct/MatrixStructTest.cpp +++ b/wpimath/src/test/native/cpp/struct/MatrixStructTest.cpp @@ -8,7 +8,7 @@ #include "wpi/math/linalg/EigenCore.hpp" #include "wpi/math/linalg/struct/StructProto.hpp" -using namespace frc; +using namespace wpi::math; struct MatrixStructTestData { using Type = Matrixd<2, 3>; diff --git a/wpimath/src/test/native/cpp/struct/VectorStructTest.cpp b/wpimath/src/test/native/cpp/struct/VectorStructTest.cpp index 29ab7779b1..b6bb87f118 100644 --- a/wpimath/src/test/native/cpp/struct/VectorStructTest.cpp +++ b/wpimath/src/test/native/cpp/struct/VectorStructTest.cpp @@ -8,7 +8,7 @@ #include "wpi/math/linalg/EigenCore.hpp" #include "wpi/math/linalg/struct/VectorStruct.hpp" -using namespace frc; +using namespace wpi::math; struct VectorStructTestData { using Type = Vectord<2>; diff --git a/wpimath/src/test/native/cpp/system/DiscretizationTest.cpp b/wpimath/src/test/native/cpp/system/DiscretizationTest.cpp index f0eccfa6a9..a5ade643a6 100644 --- a/wpimath/src/test/native/cpp/system/DiscretizationTest.cpp +++ b/wpimath/src/test/native/cpp/system/DiscretizationTest.cpp @@ -14,16 +14,16 @@ // Check that for a simple second-order system that we can easily analyze // analytically, TEST(DiscretizationTest, DiscretizeA) { - frc::Matrixd<2, 2> contA{{0, 1}, {0, 0}}; + wpi::math::Matrixd<2, 2> contA{{0, 1}, {0, 0}}; - frc::Vectord<2> x0{1, 1}; - frc::Matrixd<2, 2> discA; + wpi::math::Vectord<2> x0{1, 1}; + wpi::math::Matrixd<2, 2> discA; - frc::DiscretizeA<2>(contA, 1_s, &discA); - frc::Vectord<2> x1Discrete = discA * x0; + wpi::math::DiscretizeA<2>(contA, 1_s, &discA); + wpi::math::Vectord<2> x1Discrete = discA * x0; // We now have pos = vel = 1 and accel = 0, which should give us: - frc::Vectord<2> x1Truth{1.0 * x0(0) + 1.0 * x0(1), 0.0 * x0(0) + 1.0 * x0(1)}; + wpi::math::Vectord<2> x1Truth{1.0 * x0(0) + 1.0 * x0(1), 0.0 * x0(0) + 1.0 * x0(1)}; EXPECT_EQ(x1Truth, x1Discrete); } @@ -31,19 +31,19 @@ TEST(DiscretizationTest, DiscretizeA) { // Check that for a simple second-order system that we can easily analyze // analytically, TEST(DiscretizationTest, DiscretizeAB) { - frc::Matrixd<2, 2> contA{{0, 1}, {0, 0}}; - frc::Matrixd<2, 1> contB{0, 1}; + wpi::math::Matrixd<2, 2> contA{{0, 1}, {0, 0}}; + wpi::math::Matrixd<2, 1> contB{0, 1}; - frc::Vectord<2> x0{1, 1}; - frc::Vectord<1> u{1}; - frc::Matrixd<2, 2> discA; - frc::Matrixd<2, 1> discB; + wpi::math::Vectord<2> x0{1, 1}; + wpi::math::Vectord<1> u{1}; + wpi::math::Matrixd<2, 2> discA; + wpi::math::Matrixd<2, 1> discB; - frc::DiscretizeAB<2, 1>(contA, contB, 1_s, &discA, &discB); - frc::Vectord<2> x1Discrete = discA * x0 + discB * u; + wpi::math::DiscretizeAB<2, 1>(contA, contB, 1_s, &discA, &discB); + wpi::math::Vectord<2> x1Discrete = discA * x0 + discB * u; // We now have pos = vel = accel = 1, which should give us: - frc::Vectord<2> x1Truth{1.0 * x0(0) + 1.0 * x0(1) + 0.5 * u(0), + wpi::math::Vectord<2> x1Truth{1.0 * x0(0) + 1.0 * x0(1) + 0.5 * u(0), 0.0 * x0(0) + 1.0 * x0(1) + 1.0 * u(0)}; EXPECT_EQ(x1Truth, x1Discrete); @@ -53,27 +53,27 @@ TEST(DiscretizationTest, DiscretizeAB) { // Test that the discrete approximation of Q_d ≈ ∫ e^(Aτ) Q e^(Aᵀτ) dτ // 0 TEST(DiscretizationTest, DiscretizeSlowModelAQ) { - frc::Matrixd<2, 2> contA{{0, 1}, {0, 0}}; - frc::Matrixd<2, 2> contQ{{1, 0}, {0, 1}}; + wpi::math::Matrixd<2, 2> contA{{0, 1}, {0, 0}}; + wpi::math::Matrixd<2, 2> contQ{{1, 0}, {0, 1}}; - constexpr units::second_t dt = 1_s; + constexpr wpi::units::second_t dt = 1_s; // T // Q_d ≈ ∫ e^(Aτ) Q e^(Aᵀτ) dτ // 0 - frc::Matrixd<2, 2> discQIntegrated = - frc::RKDP(units::second_t, - const frc::Matrixd<2, 2>&)>, - frc::Matrixd<2, 2>>( - [&](units::second_t t, const frc::Matrixd<2, 2>&) { - return frc::Matrixd<2, 2>((contA * t.value()).exp() * contQ * + wpi::math::Matrixd<2, 2> discQIntegrated = + wpi::math::RKDP(wpi::units::second_t, + const wpi::math::Matrixd<2, 2>&)>, + wpi::math::Matrixd<2, 2>>( + [&](wpi::units::second_t t, const wpi::math::Matrixd<2, 2>&) { + return wpi::math::Matrixd<2, 2>((contA * t.value()).exp() * contQ * (contA.transpose() * t.value()).exp()); }, - 0_s, frc::Matrixd<2, 2>::Zero(), dt); + 0_s, wpi::math::Matrixd<2, 2>::Zero(), dt); - frc::Matrixd<2, 2> discA; - frc::Matrixd<2, 2> discQ; - frc::DiscretizeAQ<2>(contA, contQ, dt, &discA, &discQ); + wpi::math::Matrixd<2, 2> discA; + wpi::math::Matrixd<2, 2> discQ; + wpi::math::DiscretizeAQ<2>(contA, contQ, dt, &discA, &discQ); EXPECT_LT((discQIntegrated - discQ).norm(), 1e-10) << "Expected these to be nearly equal:\ndiscQ:\n" @@ -85,27 +85,27 @@ TEST(DiscretizationTest, DiscretizeSlowModelAQ) { // Test that the discrete approximation of Q_d ≈ ∫ e^(Aτ) Q e^(Aᵀτ) dτ // 0 TEST(DiscretizationTest, DiscretizeFastModelAQ) { - frc::Matrixd<2, 2> contA{{0, 1}, {0, -1406.29}}; - frc::Matrixd<2, 2> contQ{{0.0025, 0}, {0, 1}}; + wpi::math::Matrixd<2, 2> contA{{0, 1}, {0, -1406.29}}; + wpi::math::Matrixd<2, 2> contQ{{0.0025, 0}, {0, 1}}; - constexpr units::second_t dt = 5_ms; + constexpr wpi::units::second_t dt = 5_ms; // T // Q_d = ∫ e^(Aτ) Q e^(Aᵀτ) dτ // 0 - frc::Matrixd<2, 2> discQIntegrated = - frc::RKDP(units::second_t, - const frc::Matrixd<2, 2>&)>, - frc::Matrixd<2, 2>>( - [&](units::second_t t, const frc::Matrixd<2, 2>&) { - return frc::Matrixd<2, 2>((contA * t.value()).exp() * contQ * + wpi::math::Matrixd<2, 2> discQIntegrated = + wpi::math::RKDP(wpi::units::second_t, + const wpi::math::Matrixd<2, 2>&)>, + wpi::math::Matrixd<2, 2>>( + [&](wpi::units::second_t t, const wpi::math::Matrixd<2, 2>&) { + return wpi::math::Matrixd<2, 2>((contA * t.value()).exp() * contQ * (contA.transpose() * t.value()).exp()); }, - 0_s, frc::Matrixd<2, 2>::Zero(), dt); + 0_s, wpi::math::Matrixd<2, 2>::Zero(), dt); - frc::Matrixd<2, 2> discA; - frc::Matrixd<2, 2> discQ; - frc::DiscretizeAQ<2>(contA, contQ, dt, &discA, &discQ); + wpi::math::Matrixd<2, 2> discA; + wpi::math::Matrixd<2, 2> discQ; + wpi::math::DiscretizeAQ<2>(contA, contQ, dt, &discA, &discQ); EXPECT_LT((discQIntegrated - discQ).norm(), 1e-3) << "Expected these to be nearly equal:\ndiscQ:\n" @@ -115,10 +115,10 @@ TEST(DiscretizationTest, DiscretizeFastModelAQ) { // Test that DiscretizeR() works TEST(DiscretizationTest, DiscretizeR) { - frc::Matrixd<2, 2> contR{{2.0, 0.0}, {0.0, 1.0}}; - frc::Matrixd<2, 2> discRTruth{{4.0, 0.0}, {0.0, 2.0}}; + wpi::math::Matrixd<2, 2> contR{{2.0, 0.0}, {0.0, 1.0}}; + wpi::math::Matrixd<2, 2> discRTruth{{4.0, 0.0}, {0.0, 2.0}}; - frc::Matrixd<2, 2> discR = frc::DiscretizeR<2>(contR, 500_ms); + wpi::math::Matrixd<2, 2> discR = wpi::math::DiscretizeR<2>(contR, 500_ms); EXPECT_LT((discRTruth - discR).norm(), 1e-10) << "Expected these to be nearly equal:\ndiscR:\n" diff --git a/wpimath/src/test/native/cpp/system/LinearSystemIDTest.cpp b/wpimath/src/test/native/cpp/system/LinearSystemIDTest.cpp index b9ca8e452b..23cd484db0 100644 --- a/wpimath/src/test/native/cpp/system/LinearSystemIDTest.cpp +++ b/wpimath/src/test/native/cpp/system/LinearSystemIDTest.cpp @@ -12,64 +12,64 @@ TEST(LinearSystemIDTest, IdentifyDrivetrainVelocitySystem) { #if __GNUC__ <= 11 - auto model = frc::LinearSystemId::DrivetrainVelocitySystem( - frc::DCMotor::NEO(4), 70_kg, 0.05_m, 0.4_m, 6.0_kg_sq_m, 6.0); + auto model = wpi::math::LinearSystemId::DrivetrainVelocitySystem( + wpi::math::DCMotor::NEO(4), 70_kg, 0.05_m, 0.4_m, 6.0_kg_sq_m, 6.0); #else - constexpr auto model = frc::LinearSystemId::DrivetrainVelocitySystem( - frc::DCMotor::NEO(4), 70_kg, 0.05_m, 0.4_m, 6.0_kg_sq_m, 6.0); + constexpr auto model = wpi::math::LinearSystemId::DrivetrainVelocitySystem( + wpi::math::DCMotor::NEO(4), 70_kg, 0.05_m, 0.4_m, 6.0_kg_sq_m, 6.0); #endif ASSERT_TRUE(model.A().isApprox( - frc::Matrixd<2, 2>{{-10.14132, 3.06598}, {3.06598, -10.14132}}, 0.001)); + wpi::math::Matrixd<2, 2>{{-10.14132, 3.06598}, {3.06598, -10.14132}}, 0.001)); ASSERT_TRUE(model.B().isApprox( - frc::Matrixd<2, 2>{{4.2590, -1.28762}, {-1.2876, 4.2590}}, 0.001)); + wpi::math::Matrixd<2, 2>{{4.2590, -1.28762}, {-1.2876, 4.2590}}, 0.001)); ASSERT_TRUE( - model.C().isApprox(frc::Matrixd<2, 2>{{1.0, 0.0}, {0.0, 1.0}}, 0.001)); + model.C().isApprox(wpi::math::Matrixd<2, 2>{{1.0, 0.0}, {0.0, 1.0}}, 0.001)); ASSERT_TRUE( - model.D().isApprox(frc::Matrixd<2, 2>{{0.0, 0.0}, {0.0, 0.0}}, 0.001)); + model.D().isApprox(wpi::math::Matrixd<2, 2>{{0.0, 0.0}, {0.0, 0.0}}, 0.001)); } TEST(LinearSystemIDTest, ElevatorSystem) { - auto model = frc::LinearSystemId::ElevatorSystem(frc::DCMotor::NEO(2), 5_kg, + auto model = wpi::math::LinearSystemId::ElevatorSystem(wpi::math::DCMotor::NEO(2), 5_kg, 0.05_m, 12) .Slice(0); ASSERT_TRUE(model.A().isApprox( - frc::Matrixd<2, 2>{{0.0, 1.0}, {0.0, -99.05473}}, 0.001)); - ASSERT_TRUE(model.B().isApprox(frc::Matrixd<2, 1>{0.0, 20.8}, 0.001)); - ASSERT_TRUE(model.C().isApprox(frc::Matrixd<1, 2>{1.0, 0.0}, 0.001)); - ASSERT_TRUE(model.D().isApprox(frc::Matrixd<1, 1>{0.0}, 0.001)); + wpi::math::Matrixd<2, 2>{{0.0, 1.0}, {0.0, -99.05473}}, 0.001)); + ASSERT_TRUE(model.B().isApprox(wpi::math::Matrixd<2, 1>{0.0, 20.8}, 0.001)); + ASSERT_TRUE(model.C().isApprox(wpi::math::Matrixd<1, 2>{1.0, 0.0}, 0.001)); + ASSERT_TRUE(model.D().isApprox(wpi::math::Matrixd<1, 1>{0.0}, 0.001)); } TEST(LinearSystemIDTest, FlywheelSystem) { #if __GNUC__ <= 11 - auto model = frc::LinearSystemId::FlywheelSystem(frc::DCMotor::NEO(2), + auto model = wpi::math::LinearSystemId::FlywheelSystem(wpi::math::DCMotor::NEO(2), 0.00032_kg_sq_m, 1.0); #else - constexpr auto model = frc::LinearSystemId::FlywheelSystem( - frc::DCMotor::NEO(2), 0.00032_kg_sq_m, 1.0); + constexpr auto model = wpi::math::LinearSystemId::FlywheelSystem( + wpi::math::DCMotor::NEO(2), 0.00032_kg_sq_m, 1.0); #endif - ASSERT_TRUE(model.A().isApprox(frc::Matrixd<1, 1>{-26.87032}, 0.001)); - ASSERT_TRUE(model.B().isApprox(frc::Matrixd<1, 1>{1354.166667}, 0.001)); - ASSERT_TRUE(model.C().isApprox(frc::Matrixd<1, 1>{1.0}, 0.001)); - ASSERT_TRUE(model.D().isApprox(frc::Matrixd<1, 1>{0.0}, 0.001)); + ASSERT_TRUE(model.A().isApprox(wpi::math::Matrixd<1, 1>{-26.87032}, 0.001)); + ASSERT_TRUE(model.B().isApprox(wpi::math::Matrixd<1, 1>{1354.166667}, 0.001)); + ASSERT_TRUE(model.C().isApprox(wpi::math::Matrixd<1, 1>{1.0}, 0.001)); + ASSERT_TRUE(model.D().isApprox(wpi::math::Matrixd<1, 1>{0.0}, 0.001)); } TEST(LinearSystemIDTest, DCMotorSystem) { #if __GNUC__ <= 11 - auto model = frc::LinearSystemId::DCMotorSystem(frc::DCMotor::NEO(2), + auto model = wpi::math::LinearSystemId::DCMotorSystem(wpi::math::DCMotor::NEO(2), 0.00032_kg_sq_m, 1.0); #else - constexpr auto model = frc::LinearSystemId::DCMotorSystem( - frc::DCMotor::NEO(2), 0.00032_kg_sq_m, 1.0); + constexpr auto model = wpi::math::LinearSystemId::DCMotorSystem( + wpi::math::DCMotor::NEO(2), 0.00032_kg_sq_m, 1.0); #endif ASSERT_TRUE( - model.A().isApprox(frc::Matrixd<2, 2>{{0, 1}, {0, -26.87032}}, 0.001)); - ASSERT_TRUE(model.B().isApprox(frc::Matrixd<2, 1>{0, 1354.166667}, 0.001)); + model.A().isApprox(wpi::math::Matrixd<2, 2>{{0, 1}, {0, -26.87032}}, 0.001)); + ASSERT_TRUE(model.B().isApprox(wpi::math::Matrixd<2, 1>{0, 1354.166667}, 0.001)); ASSERT_TRUE( - model.C().isApprox(frc::Matrixd<2, 2>{{1.0, 0.0}, {0.0, 1.0}}, 0.001)); - ASSERT_TRUE(model.D().isApprox(frc::Matrixd<2, 1>{0.0, 0.0}, 0.001)); + model.C().isApprox(wpi::math::Matrixd<2, 2>{{1.0, 0.0}, {0.0, 1.0}}, 0.001)); + ASSERT_TRUE(model.D().isApprox(wpi::math::Matrixd<2, 1>{0.0, 0.0}, 0.001)); } TEST(LinearSystemIDTest, IdentifyPositionSystem) { @@ -79,17 +79,17 @@ TEST(LinearSystemIDTest, IdentifyPositionSystem) { constexpr double ka = 0.5; #if __GNUC__ <= 11 - auto model = frc::LinearSystemId::IdentifyPositionSystem( + auto model = wpi::math::LinearSystemId::IdentifyPositionSystem( kv * 1_V / 1_mps, ka * 1_V / 1_mps_sq); #else constexpr auto model = - frc::LinearSystemId::IdentifyPositionSystem( + wpi::math::LinearSystemId::IdentifyPositionSystem( kv * 1_V / 1_mps, ka * 1_V / 1_mps_sq); #endif ASSERT_TRUE(model.A().isApprox( - frc::Matrixd<2, 2>{{0.0, 1.0}, {0.0, -kv / ka}}, 0.001)); - ASSERT_TRUE(model.B().isApprox(frc::Matrixd<2, 1>{0.0, 1.0 / ka}, 0.001)); + wpi::math::Matrixd<2, 2>{{0.0, 1.0}, {0.0, -kv / ka}}, 0.001)); + ASSERT_TRUE(model.B().isApprox(wpi::math::Matrixd<2, 1>{0.0, 1.0 / ka}, 0.001)); } TEST(LinearSystemIDTest, IdentifyVelocitySystem) { @@ -100,14 +100,14 @@ TEST(LinearSystemIDTest, IdentifyVelocitySystem) { constexpr double ka = 0.5; #if __GNUC__ <= 11 - auto model = frc::LinearSystemId::IdentifyVelocitySystem( + auto model = wpi::math::LinearSystemId::IdentifyVelocitySystem( kv * 1_V / 1_mps, ka * 1_V / 1_mps_sq); #else constexpr auto model = - frc::LinearSystemId::IdentifyVelocitySystem( + wpi::math::LinearSystemId::IdentifyVelocitySystem( kv * 1_V / 1_mps, ka * 1_V / 1_mps_sq); #endif - ASSERT_TRUE(model.A().isApprox(frc::Matrixd<1, 1>{-kv / ka}, 0.001)); - ASSERT_TRUE(model.B().isApprox(frc::Matrixd<1, 1>{1.0 / ka}, 0.001)); + ASSERT_TRUE(model.A().isApprox(wpi::math::Matrixd<1, 1>{-kv / ka}, 0.001)); + ASSERT_TRUE(model.B().isApprox(wpi::math::Matrixd<1, 1>{1.0 / ka}, 0.001)); } diff --git a/wpimath/src/test/native/cpp/system/NumericalIntegrationTest.cpp b/wpimath/src/test/native/cpp/system/NumericalIntegrationTest.cpp index f384bd2cb0..2e38e56f26 100644 --- a/wpimath/src/test/native/cpp/system/NumericalIntegrationTest.cpp +++ b/wpimath/src/test/native/cpp/system/NumericalIntegrationTest.cpp @@ -11,23 +11,23 @@ // Test that integrating dx/dt = eˣ works TEST(NumericalIntegrationTest, Exponential) { - frc::Vectord<1> y0{0.0}; + wpi::math::Vectord<1> y0{0.0}; - frc::Vectord<1> y1 = frc::RK4( - [](const frc::Vectord<1>& x) { return frc::Vectord<1>{std::exp(x(0))}; }, + wpi::math::Vectord<1> y1 = wpi::math::RK4( + [](const wpi::math::Vectord<1>& x) { return wpi::math::Vectord<1>{std::exp(x(0))}; }, y0, 0.1_s); EXPECT_NEAR(y1(0), std::exp(0.1) - std::exp(0), 1e-3); } // Test that integrating dx/dt = eˣ works when we provide a u TEST(NumericalIntegrationTest, ExponentialWithU) { - frc::Vectord<1> y0{0.0}; + wpi::math::Vectord<1> y0{0.0}; - frc::Vectord<1> y1 = frc::RK4( - [](const frc::Vectord<1>& x, const frc::Vectord<1>& u) { - return frc::Vectord<1>{std::exp(u(0) * x(0))}; + wpi::math::Vectord<1> y1 = wpi::math::RK4( + [](const wpi::math::Vectord<1>& x, const wpi::math::Vectord<1>& u) { + return wpi::math::Vectord<1>{std::exp(u(0) * x(0))}; }, - y0, frc::Vectord<1>{1.0}, 0.1_s); + y0, wpi::math::Vectord<1>{1.0}, 0.1_s); EXPECT_NEAR(y1(0), std::exp(0.1) - std::exp(0), 1e-3); } @@ -40,11 +40,11 @@ TEST(NumericalIntegrationTest, ExponentialWithU) { // // x(t) = 12eᵗ/(eᵗ + 1)² TEST(NumericalIntegrationTest, RK4TimeVarying) { - frc::Vectord<1> y0{12.0 * std::exp(5.0) / std::pow(std::exp(5.0) + 1.0, 2.0)}; + wpi::math::Vectord<1> y0{12.0 * std::exp(5.0) / std::pow(std::exp(5.0) + 1.0, 2.0)}; - frc::Vectord<1> y1 = frc::RK4( - [](units::second_t t, const frc::Vectord<1>& x) { - return frc::Vectord<1>{x(0) * + wpi::math::Vectord<1> y1 = wpi::math::RK4( + [](wpi::units::second_t t, const wpi::math::Vectord<1>& x) { + return wpi::math::Vectord<1>{x(0) * (2.0 / (std::exp(t.value()) + 1.0) - 1.0)}; }, 5_s, y0, 1_s); @@ -54,23 +54,23 @@ TEST(NumericalIntegrationTest, RK4TimeVarying) { // Tests that integrating dx/dt = 0 works with RKDP TEST(NumericalIntegrationTest, ZeroRKDP) { - frc::Vectord<1> y1 = frc::RKDP( - [](const frc::Vectord<1>& x, const frc::Vectord<1>& u) { - return frc::Vectord<1>::Zero(); + wpi::math::Vectord<1> y1 = wpi::math::RKDP( + [](const wpi::math::Vectord<1>& x, const wpi::math::Vectord<1>& u) { + return wpi::math::Vectord<1>::Zero(); }, - frc::Vectord<1>{0.0}, frc::Vectord<1>{0.0}, 0.1_s); + wpi::math::Vectord<1>{0.0}, wpi::math::Vectord<1>{0.0}, 0.1_s); EXPECT_NEAR(y1(0), 0.0, 1e-3); } // Tests that integrating dx/dt = eˣ works with RKDP TEST(NumericalIntegrationTest, ExponentialRKDP) { - frc::Vectord<1> y0{0.0}; + wpi::math::Vectord<1> y0{0.0}; - frc::Vectord<1> y1 = frc::RKDP( - [](const frc::Vectord<1>& x, const frc::Vectord<1>& u) { - return frc::Vectord<1>{std::exp(x(0))}; + wpi::math::Vectord<1> y1 = wpi::math::RKDP( + [](const wpi::math::Vectord<1>& x, const wpi::math::Vectord<1>& u) { + return wpi::math::Vectord<1>{std::exp(x(0))}; }, - y0, frc::Vectord<1>{0.0}, 0.1_s); + y0, wpi::math::Vectord<1>{0.0}, 0.1_s); EXPECT_NEAR(y1(0), std::exp(0.1) - std::exp(0), 1e-3); } @@ -83,11 +83,11 @@ TEST(NumericalIntegrationTest, ExponentialRKDP) { // // x(t) = 12eᵗ/(eᵗ + 1)² TEST(NumericalIntegrationTest, RKDPTimeVarying) { - frc::Vectord<1> y0{12.0 * std::exp(5.0) / std::pow(std::exp(5.0) + 1.0, 2.0)}; + wpi::math::Vectord<1> y0{12.0 * std::exp(5.0) / std::pow(std::exp(5.0) + 1.0, 2.0)}; - frc::Vectord<1> y1 = frc::RKDP( - [](units::second_t t, const frc::Vectord<1>& x) { - return frc::Vectord<1>{x(0) * + wpi::math::Vectord<1> y1 = wpi::math::RKDP( + [](wpi::units::second_t t, const wpi::math::Vectord<1>& x) { + return wpi::math::Vectord<1>{x(0) * (2.0 / (std::exp(t.value()) + 1.0) - 1.0)}; }, 5_s, y0, 1_s, 1e-12); diff --git a/wpimath/src/test/native/cpp/system/NumericalJacobianTest.cpp b/wpimath/src/test/native/cpp/system/NumericalJacobianTest.cpp index db5325feb4..a691fbb6f3 100644 --- a/wpimath/src/test/native/cpp/system/NumericalJacobianTest.cpp +++ b/wpimath/src/test/native/cpp/system/NumericalJacobianTest.cpp @@ -6,25 +6,25 @@ #include "wpi/math/system/NumericalJacobian.hpp" -frc::Matrixd<4, 4> A{{1, 2, 4, 1}, {5, 2, 3, 4}, {5, 1, 3, 2}, {1, 1, 3, 7}}; -frc::Matrixd<4, 2> B{{1, 1}, {2, 1}, {3, 2}, {3, 7}}; +wpi::math::Matrixd<4, 4> A{{1, 2, 4, 1}, {5, 2, 3, 4}, {5, 1, 3, 2}, {1, 1, 3, 7}}; +wpi::math::Matrixd<4, 2> B{{1, 1}, {2, 1}, {3, 2}, {3, 7}}; // Function from which to recover A and B -frc::Vectord<4> AxBuFn(const frc::Vectord<4>& x, const frc::Vectord<2>& u) { +wpi::math::Vectord<4> AxBuFn(const wpi::math::Vectord<4>& x, const wpi::math::Vectord<2>& u) { return A * x + B * u; } // Test that we can recover A from AxBuFn() pretty accurately TEST(NumericalJacobianTest, Ax) { - frc::Matrixd<4, 4> newA = frc::NumericalJacobianX<4, 4, 2>( - AxBuFn, frc::Vectord<4>::Zero(), frc::Vectord<2>::Zero()); + wpi::math::Matrixd<4, 4> newA = wpi::math::NumericalJacobianX<4, 4, 2>( + AxBuFn, wpi::math::Vectord<4>::Zero(), wpi::math::Vectord<2>::Zero()); EXPECT_TRUE(newA.isApprox(A)); } // Test that we can recover B from AxBuFn() pretty accurately TEST(NumericalJacobianTest, Bu) { - frc::Matrixd<4, 2> newB = frc::NumericalJacobianU<4, 4, 2>( - AxBuFn, frc::Vectord<4>::Zero(), frc::Vectord<2>::Zero()); + wpi::math::Matrixd<4, 2> newB = wpi::math::NumericalJacobianU<4, 4, 2>( + AxBuFn, wpi::math::Vectord<4>::Zero(), wpi::math::Vectord<2>::Zero()); EXPECT_TRUE(newB.isApprox(B)); } @@ -35,37 +35,37 @@ Eigen::VectorXd AxBuFn_DynamicSize(const Eigen::VectorXd& x, // Test that we can recover A from AxBuFn() pretty accurately TEST(NumericalJacobianTest, Ax_DynamicSize) { - Eigen::MatrixXd newA = frc::NumericalJacobianX( - AxBuFn_DynamicSize, frc::Vectord<4>::Zero(), frc::Vectord<2>::Zero()); + Eigen::MatrixXd newA = wpi::math::NumericalJacobianX( + AxBuFn_DynamicSize, wpi::math::Vectord<4>::Zero(), wpi::math::Vectord<2>::Zero()); EXPECT_TRUE(newA.isApprox(A)); } // Test that we can recover B from AxBuFn() pretty accurately TEST(NumericalJacobianTest, Bu_DynamicSize) { - Eigen::MatrixXd newB = frc::NumericalJacobianU( - AxBuFn_DynamicSize, frc::Vectord<4>::Zero(), frc::Vectord<2>::Zero()); + Eigen::MatrixXd newB = wpi::math::NumericalJacobianU( + AxBuFn_DynamicSize, wpi::math::Vectord<4>::Zero(), wpi::math::Vectord<2>::Zero()); EXPECT_TRUE(newB.isApprox(B)); } -frc::Matrixd<3, 4> C{{1, 2, 4, 1}, {5, 2, 3, 4}, {5, 1, 3, 2}}; -frc::Matrixd<3, 2> D{{1, 1}, {2, 1}, {3, 2}}; +wpi::math::Matrixd<3, 4> C{{1, 2, 4, 1}, {5, 2, 3, 4}, {5, 1, 3, 2}}; +wpi::math::Matrixd<3, 2> D{{1, 1}, {2, 1}, {3, 2}}; // Function from which to recover C and D -frc::Vectord<3> CxDuFn(const frc::Vectord<4>& x, const frc::Vectord<2>& u) { +wpi::math::Vectord<3> CxDuFn(const wpi::math::Vectord<4>& x, const wpi::math::Vectord<2>& u) { return C * x + D * u; } // Test that we can recover C from CxDuFn() pretty accurately TEST(NumericalJacobianTest, Cx) { - frc::Matrixd<3, 4> newC = frc::NumericalJacobianX<3, 4, 2>( - CxDuFn, frc::Vectord<4>::Zero(), frc::Vectord<2>::Zero()); + wpi::math::Matrixd<3, 4> newC = wpi::math::NumericalJacobianX<3, 4, 2>( + CxDuFn, wpi::math::Vectord<4>::Zero(), wpi::math::Vectord<2>::Zero()); EXPECT_TRUE(newC.isApprox(C)); } // Test that we can recover D from CxDuFn() pretty accurately TEST(NumericalJacobianTest, Du) { - frc::Matrixd<3, 2> newD = frc::NumericalJacobianU<3, 4, 2>( - CxDuFn, frc::Vectord<4>::Zero(), frc::Vectord<2>::Zero()); + wpi::math::Matrixd<3, 2> newD = wpi::math::NumericalJacobianU<3, 4, 2>( + CxDuFn, wpi::math::Vectord<4>::Zero(), wpi::math::Vectord<2>::Zero()); EXPECT_TRUE(newD.isApprox(D)); } @@ -75,13 +75,13 @@ Eigen::VectorXd CxDuFn_DynamicSize(const Eigen::VectorXd& x, } TEST(NumericalJacobianTest, Cx_DynamicSize) { - Eigen::MatrixXd newC = frc::NumericalJacobianX( + Eigen::MatrixXd newC = wpi::math::NumericalJacobianX( CxDuFn_DynamicSize, Eigen::VectorXd::Zero(4), Eigen::VectorXd::Zero(2)); EXPECT_TRUE(newC.isApprox(C)); } TEST(NumericalJacobianTest, Du_DynamicSize) { - Eigen::MatrixXd newD = frc::NumericalJacobianU( + Eigen::MatrixXd newD = wpi::math::NumericalJacobianU( CxDuFn_DynamicSize, Eigen::VectorXd::Zero(4), Eigen::VectorXd::Zero(2)); EXPECT_TRUE(newD.isApprox(D)); } diff --git a/wpimath/src/test/native/cpp/system/plant/proto/DCMotorProtoTest.cpp b/wpimath/src/test/native/cpp/system/plant/proto/DCMotorProtoTest.cpp index 5013167455..ce65cced7a 100644 --- a/wpimath/src/test/native/cpp/system/plant/proto/DCMotorProtoTest.cpp +++ b/wpimath/src/test/native/cpp/system/plant/proto/DCMotorProtoTest.cpp @@ -7,16 +7,16 @@ #include "wpi/math/system/plant/DCMotor.hpp" #include "wpi/util/SmallVector.hpp" -using namespace frc; +using namespace wpi::math; -using ProtoType = wpi::Protobuf; +using ProtoType = wpi::util::Protobuf; inline constexpr DCMotor kExpectedData = DCMotor{1.91_V, 19.1_Nm, 1.74_A, 2.29_A, 2.2_rad_per_s, 2}; TEST(DCMotorProtoTest, Roundtrip) { - wpi::ProtobufMessage message; - wpi::SmallVector buf; + wpi::util::ProtobufMessage message; + wpi::util::SmallVector buf; ASSERT_TRUE(message.Pack(buf, kExpectedData)); auto unpacked_data = message.Unpack(buf); diff --git a/wpimath/src/test/native/cpp/system/plant/struct/DCMotorStructTest.cpp b/wpimath/src/test/native/cpp/system/plant/struct/DCMotorStructTest.cpp index 8be94a9e7f..ac66b326cf 100644 --- a/wpimath/src/test/native/cpp/system/plant/struct/DCMotorStructTest.cpp +++ b/wpimath/src/test/native/cpp/system/plant/struct/DCMotorStructTest.cpp @@ -6,9 +6,9 @@ #include "wpi/math/system/plant/DCMotor.hpp" -using namespace frc; +using namespace wpi::math; -using StructType = wpi::Struct; +using StructType = wpi::util::Struct; inline constexpr DCMotor kExpectedData = DCMotor{1.91_V, 19.1_Nm, 1.74_A, 2.29_A, 2.2_rad_per_s, 2}; diff --git a/wpimath/src/test/native/cpp/system/proto/LinearSystemProtoTest.cpp b/wpimath/src/test/native/cpp/system/proto/LinearSystemProtoTest.cpp index 9cf93ee8c9..f9c98982aa 100644 --- a/wpimath/src/test/native/cpp/system/proto/LinearSystemProtoTest.cpp +++ b/wpimath/src/test/native/cpp/system/proto/LinearSystemProtoTest.cpp @@ -8,7 +8,7 @@ #include "wpi/math/system/LinearSystem.hpp" #include "wpi/math/system/proto/LinearSystemProto.hpp" -using namespace frc; +using namespace wpi::math; struct LinearSystemProtoTestData { using Type = LinearSystem<2, 3, 4>; diff --git a/wpimath/src/test/native/cpp/system/struct/LinearSystemStructTest.cpp b/wpimath/src/test/native/cpp/system/struct/LinearSystemStructTest.cpp index fbe57dbfc7..21590e8ccf 100644 --- a/wpimath/src/test/native/cpp/system/struct/LinearSystemStructTest.cpp +++ b/wpimath/src/test/native/cpp/system/struct/LinearSystemStructTest.cpp @@ -8,7 +8,7 @@ #include "wpi/math/system/LinearSystem.hpp" #include "wpi/math/system/struct/LinearSystemStruct.hpp" -using namespace frc; +using namespace wpi::math; struct LinearSystemStructTestData { using Type = LinearSystem<2, 3, 4>; diff --git a/wpimath/src/test/native/cpp/trajectory/CentripetalAccelerationConstraintTest.cpp b/wpimath/src/test/native/cpp/trajectory/CentripetalAccelerationConstraintTest.cpp index 1678cfdd47..c6934911d3 100644 --- a/wpimath/src/test/native/cpp/trajectory/CentripetalAccelerationConstraintTest.cpp +++ b/wpimath/src/test/native/cpp/trajectory/CentripetalAccelerationConstraintTest.cpp @@ -15,7 +15,7 @@ #include "wpi/units/math.hpp" #include "wpi/units/velocity.hpp" -using namespace frc; +using namespace wpi::math; TEST(CentripetalAccelerationConstraintTest, Constraint) { const auto maxCentripetalAcceleration = 7_fps_sq; @@ -26,16 +26,16 @@ TEST(CentripetalAccelerationConstraintTest, Constraint) { auto trajectory = TestTrajectory::GetTrajectory(config); - units::second_t time = 0_s; - units::second_t dt = 20_ms; - units::second_t duration = trajectory.TotalTime(); + wpi::units::second_t time = 0_s; + wpi::units::second_t dt = 20_ms; + wpi::units::second_t duration = trajectory.TotalTime(); while (time < duration) { const Trajectory::State point = trajectory.Sample(time); time += dt; auto centripetalAcceleration = - units::math::pow<2>(point.velocity) * point.curvature / 1_rad; + wpi::units::math::pow<2>(point.velocity) * point.curvature / 1_rad; EXPECT_TRUE(centripetalAcceleration < maxCentripetalAcceleration + 0.05_mps_sq); diff --git a/wpimath/src/test/native/cpp/trajectory/DifferentialDriveKinematicsTest.cpp b/wpimath/src/test/native/cpp/trajectory/DifferentialDriveKinematicsTest.cpp index 53ce0410f4..9c5e4d52fa 100644 --- a/wpimath/src/test/native/cpp/trajectory/DifferentialDriveKinematicsTest.cpp +++ b/wpimath/src/test/native/cpp/trajectory/DifferentialDriveKinematicsTest.cpp @@ -12,7 +12,7 @@ #include "wpi/math/trajectory/constraint/DifferentialDriveKinematicsConstraint.hpp" #include "wpi/units/time.hpp" -using namespace frc; +using namespace wpi::math; TEST(DifferentialDriveKinematicsConstraintTest, Constraint) { const auto maxVelocity = 12_fps; @@ -24,9 +24,9 @@ TEST(DifferentialDriveKinematicsConstraintTest, Constraint) { auto trajectory = TestTrajectory::GetTrajectory(config); - units::second_t time = 0_s; - units::second_t dt = 20_ms; - units::second_t duration = trajectory.TotalTime(); + wpi::units::second_t time = 0_s; + wpi::units::second_t dt = 20_ms; + wpi::units::second_t duration = trajectory.TotalTime(); while (time < duration) { const Trajectory::State point = trajectory.Sample(time); diff --git a/wpimath/src/test/native/cpp/trajectory/DifferentialDriveVoltageTest.cpp b/wpimath/src/test/native/cpp/trajectory/DifferentialDriveVoltageTest.cpp index 8c85895132..23ea8c64a6 100644 --- a/wpimath/src/test/native/cpp/trajectory/DifferentialDriveVoltageTest.cpp +++ b/wpimath/src/test/native/cpp/trajectory/DifferentialDriveVoltageTest.cpp @@ -18,11 +18,11 @@ #include "wpi/units/velocity.hpp" #include "wpi/units/voltage.hpp" -using namespace frc; +using namespace wpi::math; TEST(DifferentialDriveVoltageConstraintTest, Constraint) { // Pick an unreasonably large kA to ensure the constraint has to do some work - SimpleMotorFeedforward feedforward{1_V, 1_V / 1_mps, + SimpleMotorFeedforward feedforward{1_V, 1_V / 1_mps, 3_V / 1_mps_sq}; const DifferentialDriveKinematics kinematics{0.5_m}; const auto maxVoltage = 10_V; @@ -33,9 +33,9 @@ TEST(DifferentialDriveVoltageConstraintTest, Constraint) { auto trajectory = TestTrajectory::GetTrajectory(config); - units::second_t time = 0_s; - units::second_t dt = 20_ms; - units::second_t duration = trajectory.TotalTime(); + wpi::units::second_t time = 0_s; + wpi::units::second_t dt = 20_ms; + wpi::units::second_t duration = trajectory.TotalTime(); while (time < duration) { const Trajectory::State point = trajectory.Sample(time); @@ -63,7 +63,7 @@ TEST(DifferentialDriveVoltageConstraintTest, Constraint) { } TEST(DifferentialDriveVoltageConstraintTest, HighCurvature) { - SimpleMotorFeedforward feedforward{1_V, 1_V / 1_mps, + SimpleMotorFeedforward feedforward{1_V, 1_V / 1_mps, 3_V / 1_mps_sq}; // Large trackwidth - need to test with radius of curvature less than half of // trackwidth diff --git a/wpimath/src/test/native/cpp/trajectory/EllipticalRegionConstraintTest.cpp b/wpimath/src/test/native/cpp/trajectory/EllipticalRegionConstraintTest.cpp index d4986142f3..2ce3e96c09 100644 --- a/wpimath/src/test/native/cpp/trajectory/EllipticalRegionConstraintTest.cpp +++ b/wpimath/src/test/native/cpp/trajectory/EllipticalRegionConstraintTest.cpp @@ -12,11 +12,11 @@ #include "wpi/units/length.hpp" #include "wpi/units/velocity.hpp" -using namespace frc; +using namespace wpi::math; TEST(EllipticalRegionConstraintTest, Constraint) { constexpr auto maxVelocity = 2_fps; - constexpr frc::Ellipse2d ellipse{{5_ft, 2.5_ft, 180_deg}, 5_ft, 2.5_ft}; + constexpr wpi::math::Ellipse2d ellipse{{5_ft, 2.5_ft, 180_deg}, 5_ft, 2.5_ft}; auto config = TrajectoryConfig(13_fps, 13_fps_sq); config.AddConstraint( @@ -26,8 +26,8 @@ TEST(EllipticalRegionConstraintTest, Constraint) { bool exceededConstraintOutsideRegion = false; for (auto& point : trajectory.States()) { if (ellipse.Contains(point.pose.Translation())) { - EXPECT_TRUE(units::math::abs(point.velocity) < maxVelocity + 0.05_mps); - } else if (units::math::abs(point.velocity) >= maxVelocity + 0.05_mps) { + EXPECT_TRUE(wpi::units::math::abs(point.velocity) < maxVelocity + 0.05_mps); + } else if (wpi::units::math::abs(point.velocity) >= maxVelocity + 0.05_mps) { exceededConstraintOutsideRegion = true; } } diff --git a/wpimath/src/test/native/cpp/trajectory/ExponentialProfileTest.cpp b/wpimath/src/test/native/cpp/trajectory/ExponentialProfileTest.cpp index 2b2e57cddf..6cdcdb1601 100644 --- a/wpimath/src/test/native/cpp/trajectory/ExponentialProfileTest.cpp +++ b/wpimath/src/test/native/cpp/trajectory/ExponentialProfileTest.cpp @@ -24,7 +24,7 @@ static constexpr auto kV = 2.5629_V / 1_mps; static constexpr auto kA = 0.43277_V / 1_mps_sq; #define EXPECT_NEAR_UNITS(val1, val2, eps) \ - EXPECT_LE(units::math::abs(val1 - val2), eps) + EXPECT_LE(wpi::units::math::abs(val1 - val2), eps) #define EXPECT_LT_OR_NEAR_UNITS(val1, val2, eps) \ if (val1 <= val2) { \ @@ -33,29 +33,29 @@ static constexpr auto kA = 0.43277_V / 1_mps_sq; EXPECT_NEAR_UNITS(val1, val2, eps); \ } -frc::ExponentialProfile::State CheckDynamics( - frc::ExponentialProfile profile, - frc::ExponentialProfile::Constraints +wpi::math::ExponentialProfile::State CheckDynamics( + wpi::math::ExponentialProfile profile, + wpi::math::ExponentialProfile::Constraints constraints, - frc::SimpleMotorFeedforward feedforward, - frc::ExponentialProfile::State current, - frc::ExponentialProfile::State goal) { + wpi::math::SimpleMotorFeedforward feedforward, + wpi::math::ExponentialProfile::State current, + wpi::math::ExponentialProfile::State goal) { auto next = profile.Calculate(kDt, current, goal); auto signal = feedforward.Calculate(current.velocity, next.velocity); - EXPECT_LE(units::math::abs(signal), (constraints.maxInput + 1e-9_V)); + EXPECT_LE(wpi::units::math::abs(signal), (constraints.maxInput + 1e-9_V)); return next; } TEST(ExponentialProfileTest, ReachesGoal) { - frc::ExponentialProfile::Constraints constraints{ + wpi::math::ExponentialProfile::Constraints constraints{ 12_V, -kV / kA, 1 / kA}; - frc::ExponentialProfile profile{constraints}; - frc::SimpleMotorFeedforward feedforward{ + wpi::math::ExponentialProfile profile{constraints}; + wpi::math::SimpleMotorFeedforward feedforward{ 0_V, 2.5629_V / 1_mps, 0.43277_V / 1_mps_sq, kDt}; - frc::ExponentialProfile::State goal{10_m, 0_mps}; - frc::ExponentialProfile::State state{0_m, 0_mps}; + wpi::math::ExponentialProfile::State goal{10_m, 0_mps}; + wpi::math::ExponentialProfile::State state{0_m, 0_mps}; for (int i = 0; i < 450; ++i) { state = CheckDynamics(profile, constraints, feedforward, state, goal); @@ -66,19 +66,19 @@ TEST(ExponentialProfileTest, ReachesGoal) { // Tests that decreasing the maximum velocity in the middle when it is already // moving faster than the new max is handled correctly TEST(ExponentialProfileTest, PosContinuousUnderVelChange) { - frc::ExponentialProfile::Constraints constraints{ + wpi::math::ExponentialProfile::Constraints constraints{ 12_V, -kV / kA, 1 / kA}; - frc::ExponentialProfile profile{constraints}; - frc::SimpleMotorFeedforward feedforward{ + wpi::math::ExponentialProfile profile{constraints}; + wpi::math::SimpleMotorFeedforward feedforward{ 0_V, 2.5629_V / 1_mps, 0.43277_V / 1_mps_sq, kDt}; - frc::ExponentialProfile::State goal{10_m, 0_mps}; - frc::ExponentialProfile::State state{0_m, 0_mps}; + wpi::math::ExponentialProfile::State goal{10_m, 0_mps}; + wpi::math::ExponentialProfile::State state{0_m, 0_mps}; for (int i = 0; i < 300; ++i) { if (i == 150) { constraints.maxInput = 9_V; profile = - frc::ExponentialProfile{constraints}; + wpi::math::ExponentialProfile{constraints}; } state = CheckDynamics(profile, constraints, feedforward, state, goal); @@ -89,19 +89,19 @@ TEST(ExponentialProfileTest, PosContinuousUnderVelChange) { // Tests that decreasing the maximum velocity in the middle when it is already // moving faster than the new max is handled correctly TEST(ExponentialProfileTest, PosContinuousUnderVelChangeBackward) { - frc::ExponentialProfile::Constraints constraints{ + wpi::math::ExponentialProfile::Constraints constraints{ 12_V, -kV / kA, 1 / kA}; - frc::ExponentialProfile profile{constraints}; - frc::SimpleMotorFeedforward feedforward{ + wpi::math::ExponentialProfile profile{constraints}; + wpi::math::SimpleMotorFeedforward feedforward{ 0_V, 2.5629_V / 1_mps, 0.43277_V / 1_mps_sq, kDt}; - frc::ExponentialProfile::State goal{-10_m, 0_mps}; - frc::ExponentialProfile::State state{0_m, 0_mps}; + wpi::math::ExponentialProfile::State goal{-10_m, 0_mps}; + wpi::math::ExponentialProfile::State state{0_m, 0_mps}; for (int i = 0; i < 300; ++i) { if (i == 150) { constraints.maxInput = 9_V; profile = - frc::ExponentialProfile{constraints}; + wpi::math::ExponentialProfile{constraints}; } state = CheckDynamics(profile, constraints, feedforward, state, goal); @@ -111,13 +111,13 @@ TEST(ExponentialProfileTest, PosContinuousUnderVelChangeBackward) { // There is some somewhat tricky code for dealing with going backwards TEST(ExponentialProfileTest, Backwards) { - frc::ExponentialProfile::Constraints constraints{ + wpi::math::ExponentialProfile::Constraints constraints{ 12_V, -kV / kA, 1 / kA}; - frc::ExponentialProfile profile{constraints}; - frc::SimpleMotorFeedforward feedforward{ + wpi::math::ExponentialProfile profile{constraints}; + wpi::math::SimpleMotorFeedforward feedforward{ 0_V, 2.5629_V / 1_mps, 0.43277_V / 1_mps_sq, kDt}; - frc::ExponentialProfile::State goal{-10_m, 0_mps}; - frc::ExponentialProfile::State state; + wpi::math::ExponentialProfile::State goal{-10_m, 0_mps}; + wpi::math::ExponentialProfile::State state; for (int i = 0; i < 400; ++i) { state = CheckDynamics(profile, constraints, feedforward, state, goal); @@ -126,13 +126,13 @@ TEST(ExponentialProfileTest, Backwards) { } TEST(ExponentialProfileTest, SwitchGoalInMiddle) { - frc::ExponentialProfile::Constraints constraints{ + wpi::math::ExponentialProfile::Constraints constraints{ 12_V, -kV / kA, 1 / kA}; - frc::ExponentialProfile profile{constraints}; - frc::SimpleMotorFeedforward feedforward{ + wpi::math::ExponentialProfile profile{constraints}; + wpi::math::SimpleMotorFeedforward feedforward{ 0_V, 2.5629_V / 1_mps, 0.43277_V / 1_mps_sq, kDt}; - frc::ExponentialProfile::State goal{-10_m, 0_mps}; - frc::ExponentialProfile::State state{0_m, 0_mps}; + wpi::math::ExponentialProfile::State goal{-10_m, 0_mps}; + wpi::math::ExponentialProfile::State state{0_m, 0_mps}; for (int i = 0; i < 50; ++i) { state = CheckDynamics(profile, constraints, feedforward, state, goal); @@ -148,19 +148,19 @@ TEST(ExponentialProfileTest, SwitchGoalInMiddle) { // Checks to make sure that it hits top speed on long trajectories TEST(ExponentialProfileTest, TopSpeed) { - frc::ExponentialProfile::Constraints constraints{ + wpi::math::ExponentialProfile::Constraints constraints{ 12_V, -kV / kA, 1 / kA}; - frc::ExponentialProfile profile{constraints}; - frc::SimpleMotorFeedforward feedforward{ + wpi::math::ExponentialProfile profile{constraints}; + wpi::math::SimpleMotorFeedforward feedforward{ 0_V, 2.5629_V / 1_mps, 0.43277_V / 1_mps_sq, kDt}; - frc::ExponentialProfile::State goal{40_m, 0_mps}; - frc::ExponentialProfile::State state; + wpi::math::ExponentialProfile::State goal{40_m, 0_mps}; + wpi::math::ExponentialProfile::State state; - units::meters_per_second_t maxSpeed = 0_mps; + wpi::units::meters_per_second_t maxSpeed = 0_mps; for (int i = 0; i < 900; ++i) { state = CheckDynamics(profile, constraints, feedforward, state, goal); - maxSpeed = units::math::max(state.velocity, maxSpeed); + maxSpeed = wpi::units::math::max(state.velocity, maxSpeed); } EXPECT_NEAR_UNITS(constraints.MaxVelocity(), maxSpeed, 1e-5_mps); @@ -169,19 +169,19 @@ TEST(ExponentialProfileTest, TopSpeed) { // Checks to make sure that it hits top speed on long trajectories TEST(ExponentialProfileTest, TopSpeedBackward) { - frc::ExponentialProfile::Constraints constraints{ + wpi::math::ExponentialProfile::Constraints constraints{ 12_V, -kV / kA, 1 / kA}; - frc::ExponentialProfile profile{constraints}; - frc::SimpleMotorFeedforward feedforward{ + wpi::math::ExponentialProfile profile{constraints}; + wpi::math::SimpleMotorFeedforward feedforward{ 0_V, 2.5629_V / 1_mps, 0.43277_V / 1_mps_sq, kDt}; - frc::ExponentialProfile::State goal{-40_m, 0_mps}; - frc::ExponentialProfile::State state; + wpi::math::ExponentialProfile::State goal{-40_m, 0_mps}; + wpi::math::ExponentialProfile::State state; - units::meters_per_second_t maxSpeed = 0_mps; + wpi::units::meters_per_second_t maxSpeed = 0_mps; for (int i = 0; i < 900; ++i) { state = CheckDynamics(profile, constraints, feedforward, state, goal); - maxSpeed = units::math::min(state.velocity, maxSpeed); + maxSpeed = wpi::units::math::min(state.velocity, maxSpeed); } EXPECT_NEAR_UNITS(-constraints.MaxVelocity(), maxSpeed, 1e-5_mps); @@ -190,13 +190,13 @@ TEST(ExponentialProfileTest, TopSpeedBackward) { // Checks to make sure that it hits top speed on long trajectories TEST(ExponentialProfileTest, HighInitialSpeed) { - frc::ExponentialProfile::Constraints constraints{ + wpi::math::ExponentialProfile::Constraints constraints{ 12_V, -kV / kA, 1 / kA}; - frc::ExponentialProfile profile{constraints}; - frc::SimpleMotorFeedforward feedforward{ + wpi::math::ExponentialProfile profile{constraints}; + wpi::math::SimpleMotorFeedforward feedforward{ 0_V, 2.5629_V / 1_mps, 0.43277_V / 1_mps_sq, kDt}; - frc::ExponentialProfile::State goal{40_m, 0_mps}; - frc::ExponentialProfile::State state{0_m, 8_mps}; + wpi::math::ExponentialProfile::State goal{40_m, 0_mps}; + wpi::math::ExponentialProfile::State state{0_m, 8_mps}; for (int i = 0; i < 900; ++i) { state = CheckDynamics(profile, constraints, feedforward, state, goal); @@ -207,13 +207,13 @@ TEST(ExponentialProfileTest, HighInitialSpeed) { // Checks to make sure that it hits top speed on long trajectories TEST(ExponentialProfileTest, HighInitialSpeedBackward) { - frc::ExponentialProfile::Constraints constraints{ + wpi::math::ExponentialProfile::Constraints constraints{ 12_V, -kV / kA, 1 / kA}; - frc::ExponentialProfile profile{constraints}; - frc::SimpleMotorFeedforward feedforward{ + wpi::math::ExponentialProfile profile{constraints}; + wpi::math::SimpleMotorFeedforward feedforward{ 0_V, 2.5629_V / 1_mps, 0.43277_V / 1_mps_sq, kDt}; - frc::ExponentialProfile::State goal{-40_m, 0_mps}; - frc::ExponentialProfile::State state{0_m, -8_mps}; + wpi::math::ExponentialProfile::State goal{-40_m, 0_mps}; + wpi::math::ExponentialProfile::State state{0_m, -8_mps}; for (int i = 0; i < 900; ++i) { state = CheckDynamics(profile, constraints, feedforward, state, goal); @@ -223,13 +223,13 @@ TEST(ExponentialProfileTest, HighInitialSpeedBackward) { } TEST(ExponentialProfileTest, TestHeuristic) { - frc::ExponentialProfile::Constraints constraints{ + wpi::math::ExponentialProfile::Constraints constraints{ 12_V, -kV / kA, 1 / kA}; - frc::ExponentialProfile profile{constraints}; + wpi::math::ExponentialProfile profile{constraints}; std::vector::State, // initial - frc::ExponentialProfile::State, // goal - frc::ExponentialProfile::State> // inflection + wpi::math::ExponentialProfile::State, // initial + wpi::math::ExponentialProfile::State, // goal + wpi::math::ExponentialProfile::State> // inflection // point > testCases{ @@ -275,13 +275,13 @@ TEST(ExponentialProfileTest, TestHeuristic) { } TEST(ExponentialProfileTest, TimingToCurrent) { - frc::ExponentialProfile::Constraints constraints{ + wpi::math::ExponentialProfile::Constraints constraints{ 12_V, -kV / kA, 1 / kA}; - frc::ExponentialProfile profile{constraints}; - frc::SimpleMotorFeedforward feedforward{ + wpi::math::ExponentialProfile profile{constraints}; + wpi::math::SimpleMotorFeedforward feedforward{ 0_V, 2.5629_V / 1_mps, 0.43277_V / 1_mps_sq, kDt}; - frc::ExponentialProfile::State goal{2_m, 0_mps}; - frc::ExponentialProfile::State state{0_m, 0_mps}; + wpi::math::ExponentialProfile::State goal{2_m, 0_mps}; + wpi::math::ExponentialProfile::State state{0_m, 0_mps}; for (int i = 0; i < 900; ++i) { state = CheckDynamics(profile, constraints, feedforward, state, goal); @@ -292,13 +292,13 @@ TEST(ExponentialProfileTest, TimingToCurrent) { } TEST(ExponentialProfileTest, TimingToGoal) { - frc::ExponentialProfile::Constraints constraints{ + wpi::math::ExponentialProfile::Constraints constraints{ 12_V, -kV / kA, 1 / kA}; - frc::ExponentialProfile profile{constraints}; - frc::SimpleMotorFeedforward feedforward{ + wpi::math::ExponentialProfile profile{constraints}; + wpi::math::SimpleMotorFeedforward feedforward{ 0_V, 2.5629_V / 1_mps, 0.43277_V / 1_mps_sq, kDt}; - frc::ExponentialProfile::State goal{2_m, 0_mps}; - frc::ExponentialProfile::State state{0_m, 0_mps}; + wpi::math::ExponentialProfile::State goal{2_m, 0_mps}; + wpi::math::ExponentialProfile::State state{0_m, 0_mps}; auto prediction = profile.TimeLeftUntil(state, goal); auto reachedGoal = false; @@ -315,13 +315,13 @@ TEST(ExponentialProfileTest, TimingToGoal) { } TEST(ExponentialProfileTest, TimingToNegativeGoal) { - frc::ExponentialProfile::Constraints constraints{ + wpi::math::ExponentialProfile::Constraints constraints{ 12_V, -kV / kA, 1 / kA}; - frc::ExponentialProfile profile{constraints}; - frc::SimpleMotorFeedforward feedforward{ + wpi::math::ExponentialProfile profile{constraints}; + wpi::math::SimpleMotorFeedforward feedforward{ 0_V, 2.5629_V / 1_mps, 0.43277_V / 1_mps_sq, kDt}; - frc::ExponentialProfile::State goal{-2_m, 0_mps}; - frc::ExponentialProfile::State state{0_m, 0_mps}; + wpi::math::ExponentialProfile::State goal{-2_m, 0_mps}; + wpi::math::ExponentialProfile::State state{0_m, 0_mps}; auto prediction = profile.TimeLeftUntil(state, goal); auto reachedGoal = false; diff --git a/wpimath/src/test/native/cpp/trajectory/RectangularRegionConstraintTest.cpp b/wpimath/src/test/native/cpp/trajectory/RectangularRegionConstraintTest.cpp index cdd9f4ef12..309731179f 100644 --- a/wpimath/src/test/native/cpp/trajectory/RectangularRegionConstraintTest.cpp +++ b/wpimath/src/test/native/cpp/trajectory/RectangularRegionConstraintTest.cpp @@ -12,11 +12,11 @@ #include "wpi/units/math.hpp" #include "wpi/units/velocity.hpp" -using namespace frc; +using namespace wpi::math; TEST(RectangularRegionConstraintTest, Constraint) { constexpr auto maxVelocity = 2_fps; - constexpr frc::Rectangle2d rectangle{{1_ft, 1_ft}, {5_ft, 27_ft}}; + constexpr wpi::math::Rectangle2d rectangle{{1_ft, 1_ft}, {5_ft, 27_ft}}; auto config = TrajectoryConfig(13_fps, 13_fps_sq); config.AddConstraint(RectangularRegionConstraint{ @@ -26,8 +26,8 @@ TEST(RectangularRegionConstraintTest, Constraint) { bool exceededConstraintOutsideRegion = false; for (auto& point : trajectory.States()) { if (rectangle.Contains(point.pose.Translation())) { - EXPECT_TRUE(units::math::abs(point.velocity) < maxVelocity + 0.05_mps); - } else if (units::math::abs(point.velocity) >= maxVelocity + 0.05_mps) { + EXPECT_TRUE(wpi::units::math::abs(point.velocity) < maxVelocity + 0.05_mps); + } else if (wpi::units::math::abs(point.velocity) >= maxVelocity + 0.05_mps) { exceededConstraintOutsideRegion = true; } } diff --git a/wpimath/src/test/native/cpp/trajectory/TrajectoryConcatenateTest.cpp b/wpimath/src/test/native/cpp/trajectory/TrajectoryConcatenateTest.cpp index 5d191c1334..c7daf8b8a6 100644 --- a/wpimath/src/test/native/cpp/trajectory/TrajectoryConcatenateTest.cpp +++ b/wpimath/src/test/native/cpp/trajectory/TrajectoryConcatenateTest.cpp @@ -8,9 +8,9 @@ #include "wpi/math/trajectory/TrajectoryGenerator.hpp" TEST(TrajectoryConcatenateTest, States) { - auto t1 = frc::TrajectoryGenerator::GenerateTrajectory( + auto t1 = wpi::math::TrajectoryGenerator::GenerateTrajectory( {}, {}, {1_m, 1_m, 0_deg}, {2_mps, 2_mps_sq}); - auto t2 = frc::TrajectoryGenerator::GenerateTrajectory( + auto t2 = wpi::math::TrajectoryGenerator::GenerateTrajectory( {1_m, 1_m, 0_deg}, {}, {2_m, 2_m, 45_deg}, {2_mps, 2_mps_sq}); auto t = t1 + t2; diff --git a/wpimath/src/test/native/cpp/trajectory/TrajectoryGeneratorTest.cpp b/wpimath/src/test/native/cpp/trajectory/TrajectoryGeneratorTest.cpp index 054dcd65e0..c82941ed25 100644 --- a/wpimath/src/test/native/cpp/trajectory/TrajectoryGeneratorTest.cpp +++ b/wpimath/src/test/native/cpp/trajectory/TrajectoryGeneratorTest.cpp @@ -13,22 +13,22 @@ #include "wpi/math/trajectory/constraint/TrajectoryConstraint.hpp" #include "wpi/units/math.hpp" -using namespace frc; +using namespace wpi::math; TEST(TrajectoryGenerationTest, ObeysConstraints) { TrajectoryConfig config{12_fps, 12_fps_sq}; auto trajectory = TestTrajectory::GetTrajectory(config); - units::second_t time = 0_s; - units::second_t dt = 20_ms; - units::second_t duration = trajectory.TotalTime(); + wpi::units::second_t time = 0_s; + wpi::units::second_t dt = 20_ms; + wpi::units::second_t duration = trajectory.TotalTime(); while (time < duration) { const Trajectory::State point = trajectory.Sample(time); time += dt; - EXPECT_TRUE(units::math::abs(point.velocity) <= 12_fps + 0.01_fps); - EXPECT_TRUE(units::math::abs(point.acceleration) <= + EXPECT_TRUE(wpi::units::math::abs(point.velocity) <= 12_fps + 0.01_fps); + EXPECT_TRUE(wpi::units::math::abs(point.acceleration) <= 12_fps_sq + 0.01_fps_sq); } } diff --git a/wpimath/src/test/native/cpp/trajectory/TrajectoryTransformTest.cpp b/wpimath/src/test/native/cpp/trajectory/TrajectoryTransformTest.cpp index ec5234cf59..ffd2782c08 100644 --- a/wpimath/src/test/native/cpp/trajectory/TrajectoryTransformTest.cpp +++ b/wpimath/src/test/native/cpp/trajectory/TrajectoryTransformTest.cpp @@ -10,8 +10,8 @@ #include "wpi/math/trajectory/TrajectoryConfig.hpp" #include "wpi/math/trajectory/TrajectoryGenerator.hpp" -void TestSameShapedTrajectory(std::vector statesA, - std::vector statesB) { +void TestSameShapedTrajectory(std::vector statesA, + std::vector statesB) { for (unsigned int i = 0; i < statesA.size() - 1; i++) { auto a1 = statesA[i].pose; auto a2 = statesA[i + 1].pose; @@ -30,9 +30,9 @@ void TestSameShapedTrajectory(std::vector statesA, } TEST(TrajectoryTransformsTest, TransformBy) { - frc::TrajectoryConfig config{3_mps, 3_mps_sq}; - auto trajectory = frc::TrajectoryGenerator::GenerateTrajectory( - frc::Pose2d{}, {}, frc::Pose2d{1_m, 1_m, 90_deg}, config); + wpi::math::TrajectoryConfig config{3_mps, 3_mps_sq}; + auto trajectory = wpi::math::TrajectoryGenerator::GenerateTrajectory( + wpi::math::Pose2d{}, {}, wpi::math::Pose2d{1_m, 1_m, 90_deg}, config); auto transformedTrajectory = trajectory.TransformBy({{1_m, 2_m}, 30_deg}); @@ -46,9 +46,9 @@ TEST(TrajectoryTransformsTest, TransformBy) { } TEST(TrajectoryTransformsTest, RelativeTo) { - frc::TrajectoryConfig config{3_mps, 3_mps_sq}; - auto trajectory = frc::TrajectoryGenerator::GenerateTrajectory( - frc::Pose2d{1_m, 2_m, 30_deg}, {}, frc::Pose2d{5_m, 7_m, 90_deg}, config); + wpi::math::TrajectoryConfig config{3_mps, 3_mps_sq}; + auto trajectory = wpi::math::TrajectoryGenerator::GenerateTrajectory( + wpi::math::Pose2d{1_m, 2_m, 30_deg}, {}, wpi::math::Pose2d{5_m, 7_m, 90_deg}, config); auto transformedTrajectory = trajectory.RelativeTo({1_m, 2_m, 30_deg}); diff --git a/wpimath/src/test/native/cpp/trajectory/TrapezoidProfileTest.cpp b/wpimath/src/test/native/cpp/trajectory/TrapezoidProfileTest.cpp index 38dab55968..fca98b6181 100644 --- a/wpimath/src/test/native/cpp/trajectory/TrapezoidProfileTest.cpp +++ b/wpimath/src/test/native/cpp/trajectory/TrapezoidProfileTest.cpp @@ -17,7 +17,7 @@ static constexpr auto kDt = 10_ms; #define EXPECT_NEAR_UNITS(val1, val2, eps) \ - EXPECT_LE(units::math::abs(val1 - val2), eps) + EXPECT_LE(wpi::units::math::abs(val1 - val2), eps) #define EXPECT_LT_OR_NEAR_UNITS(val1, val2, eps) \ if (val1 <= val2) { \ @@ -27,12 +27,12 @@ static constexpr auto kDt = 10_ms; } TEST(TrapezoidProfileTest, ReachesGoal) { - frc::TrapezoidProfile::Constraints constraints{1.75_mps, + wpi::math::TrapezoidProfile::Constraints constraints{1.75_mps, 0.75_mps_sq}; - frc::TrapezoidProfile::State goal{3_m, 0_mps}; - frc::TrapezoidProfile::State state; + wpi::math::TrapezoidProfile::State goal{3_m, 0_mps}; + wpi::math::TrapezoidProfile::State state; - frc::TrapezoidProfile profile{constraints}; + wpi::math::TrapezoidProfile profile{constraints}; for (int i = 0; i < 450; ++i) { state = profile.Calculate(kDt, state, goal); } @@ -42,19 +42,19 @@ TEST(TrapezoidProfileTest, ReachesGoal) { // Tests that decreasing the maximum velocity in the middle when it is already // moving faster than the new max is handled correctly TEST(TrapezoidProfileTest, PosContinuousUnderVelChange) { - frc::TrapezoidProfile::Constraints constraints{1.75_mps, + wpi::math::TrapezoidProfile::Constraints constraints{1.75_mps, 0.75_mps_sq}; - frc::TrapezoidProfile::State goal{12_m, 0_mps}; + wpi::math::TrapezoidProfile::State goal{12_m, 0_mps}; - frc::TrapezoidProfile profile{constraints}; + wpi::math::TrapezoidProfile profile{constraints}; auto state = profile.Calculate( - kDt, frc::TrapezoidProfile::State{}, goal); + kDt, wpi::math::TrapezoidProfile::State{}, goal); auto lastPos = state.position; for (int i = 0; i < 1600; ++i) { if (i == 400) { constraints.maxVelocity = 0.75_mps; - profile = frc::TrapezoidProfile{constraints}; + profile = wpi::math::TrapezoidProfile{constraints}; } state = profile.Calculate(kDt, state, goal); @@ -76,12 +76,12 @@ TEST(TrapezoidProfileTest, PosContinuousUnderVelChange) { // There is some somewhat tricky code for dealing with going backwards TEST(TrapezoidProfileTest, Backwards) { - frc::TrapezoidProfile::Constraints constraints{0.75_mps, + wpi::math::TrapezoidProfile::Constraints constraints{0.75_mps, 0.75_mps_sq}; - frc::TrapezoidProfile::State goal{-2_m, 0_mps}; - frc::TrapezoidProfile::State state; + wpi::math::TrapezoidProfile::State goal{-2_m, 0_mps}; + wpi::math::TrapezoidProfile::State state; - frc::TrapezoidProfile profile{constraints}; + wpi::math::TrapezoidProfile profile{constraints}; for (int i = 0; i < 400; ++i) { state = profile.Calculate(kDt, state, goal); } @@ -89,19 +89,19 @@ TEST(TrapezoidProfileTest, Backwards) { } TEST(TrapezoidProfileTest, SwitchGoalInMiddle) { - frc::TrapezoidProfile::Constraints constraints{0.75_mps, + wpi::math::TrapezoidProfile::Constraints constraints{0.75_mps, 0.75_mps_sq}; - frc::TrapezoidProfile::State goal{-2_m, 0_mps}; - frc::TrapezoidProfile::State state; + wpi::math::TrapezoidProfile::State goal{-2_m, 0_mps}; + wpi::math::TrapezoidProfile::State state; - frc::TrapezoidProfile profile{constraints}; + wpi::math::TrapezoidProfile profile{constraints}; for (int i = 0; i < 200; ++i) { state = profile.Calculate(kDt, state, goal); } EXPECT_NE(state, goal); goal = {0.0_m, 0.0_mps}; - profile = frc::TrapezoidProfile{constraints}; + profile = wpi::math::TrapezoidProfile{constraints}; for (int i = 0; i < 550; ++i) { state = profile.Calculate(kDt, state, goal); } @@ -110,18 +110,18 @@ TEST(TrapezoidProfileTest, SwitchGoalInMiddle) { // Checks to make sure that it hits top speed TEST(TrapezoidProfileTest, TopSpeed) { - frc::TrapezoidProfile::Constraints constraints{0.75_mps, + wpi::math::TrapezoidProfile::Constraints constraints{0.75_mps, 0.75_mps_sq}; - frc::TrapezoidProfile::State goal{4_m, 0_mps}; - frc::TrapezoidProfile::State state; + wpi::math::TrapezoidProfile::State goal{4_m, 0_mps}; + wpi::math::TrapezoidProfile::State state; - frc::TrapezoidProfile profile{constraints}; + wpi::math::TrapezoidProfile profile{constraints}; for (int i = 0; i < 200; ++i) { state = profile.Calculate(kDt, state, goal); } EXPECT_NEAR_UNITS(constraints.maxVelocity, state.velocity, 10e-5_mps); - profile = frc::TrapezoidProfile{constraints}; + profile = wpi::math::TrapezoidProfile{constraints}; for (int i = 0; i < 2000; ++i) { state = profile.Calculate(kDt, state, goal); } @@ -129,12 +129,12 @@ TEST(TrapezoidProfileTest, TopSpeed) { } TEST(TrapezoidProfileTest, TimingToCurrent) { - frc::TrapezoidProfile::Constraints constraints{0.75_mps, + wpi::math::TrapezoidProfile::Constraints constraints{0.75_mps, 0.75_mps_sq}; - frc::TrapezoidProfile::State goal{2_m, 0_mps}; - frc::TrapezoidProfile::State state; + wpi::math::TrapezoidProfile::State goal{2_m, 0_mps}; + wpi::math::TrapezoidProfile::State state; - frc::TrapezoidProfile profile{constraints}; + wpi::math::TrapezoidProfile profile{constraints}; for (int i = 0; i < 400; i++) { state = profile.Calculate(kDt, state, goal); EXPECT_NEAR_UNITS(profile.TimeLeftUntil(state.position), 0_s, 2e-2_s); @@ -142,15 +142,15 @@ TEST(TrapezoidProfileTest, TimingToCurrent) { } TEST(TrapezoidProfileTest, TimingToGoal) { - using units::unit_cast; + using wpi::units::unit_cast; - frc::TrapezoidProfile::Constraints constraints{0.75_mps, + wpi::math::TrapezoidProfile::Constraints constraints{0.75_mps, 0.75_mps_sq}; - frc::TrapezoidProfile::State goal{2_m, 0_mps}; + wpi::math::TrapezoidProfile::State goal{2_m, 0_mps}; - frc::TrapezoidProfile profile{constraints}; + wpi::math::TrapezoidProfile profile{constraints}; auto state = profile.Calculate(kDt, goal, - frc::TrapezoidProfile::State{}); + wpi::math::TrapezoidProfile::State{}); auto predictedTimeLeft = profile.TimeLeftUntil(goal.position); bool reachedGoal = false; @@ -166,22 +166,22 @@ TEST(TrapezoidProfileTest, TimingToGoal) { } TEST(TrapezoidProfileTest, TimingBeforeGoal) { - using units::unit_cast; + using wpi::units::unit_cast; - frc::TrapezoidProfile::Constraints constraints{0.75_mps, + wpi::math::TrapezoidProfile::Constraints constraints{0.75_mps, 0.75_mps_sq}; - frc::TrapezoidProfile::State goal{2_m, 0_mps}; + wpi::math::TrapezoidProfile::State goal{2_m, 0_mps}; - frc::TrapezoidProfile profile{constraints}; + wpi::math::TrapezoidProfile profile{constraints}; auto state = profile.Calculate(kDt, goal, - frc::TrapezoidProfile::State{}); + wpi::math::TrapezoidProfile::State{}); auto predictedTimeLeft = profile.TimeLeftUntil(1_m); bool reachedGoal = false; for (int i = 0; i < 400; i++) { state = profile.Calculate(kDt, state, goal); if (!reachedGoal && - (units::math::abs(state.velocity - 1_mps) < 10e-5_mps)) { + (wpi::units::math::abs(state.velocity - 1_mps) < 10e-5_mps)) { EXPECT_NEAR(unit_cast(predictedTimeLeft), i / 100.0, 2e-2); reachedGoal = true; } @@ -189,15 +189,15 @@ TEST(TrapezoidProfileTest, TimingBeforeGoal) { } TEST(TrapezoidProfileTest, TimingToNegativeGoal) { - using units::unit_cast; + using wpi::units::unit_cast; - frc::TrapezoidProfile::Constraints constraints{0.75_mps, + wpi::math::TrapezoidProfile::Constraints constraints{0.75_mps, 0.75_mps_sq}; - frc::TrapezoidProfile::State goal{-2_m, 0_mps}; + wpi::math::TrapezoidProfile::State goal{-2_m, 0_mps}; - frc::TrapezoidProfile profile{constraints}; + wpi::math::TrapezoidProfile profile{constraints}; auto state = profile.Calculate(kDt, goal, - frc::TrapezoidProfile::State{}); + wpi::math::TrapezoidProfile::State{}); auto predictedTimeLeft = profile.TimeLeftUntil(goal.position); bool reachedGoal = false; @@ -213,22 +213,22 @@ TEST(TrapezoidProfileTest, TimingToNegativeGoal) { } TEST(TrapezoidProfileTest, TimingBeforeNegativeGoal) { - using units::unit_cast; + using wpi::units::unit_cast; - frc::TrapezoidProfile::Constraints constraints{0.75_mps, + wpi::math::TrapezoidProfile::Constraints constraints{0.75_mps, 0.75_mps_sq}; - frc::TrapezoidProfile::State goal{-2_m, 0_mps}; + wpi::math::TrapezoidProfile::State goal{-2_m, 0_mps}; - frc::TrapezoidProfile profile{constraints}; + wpi::math::TrapezoidProfile profile{constraints}; auto state = profile.Calculate(kDt, goal, - frc::TrapezoidProfile::State{}); + wpi::math::TrapezoidProfile::State{}); auto predictedTimeLeft = profile.TimeLeftUntil(-1_m); bool reachedGoal = false; for (int i = 0; i < 400; i++) { state = profile.Calculate(kDt, state, goal); if (!reachedGoal && - (units::math::abs(state.velocity + 1_mps) < 10e-5_mps)) { + (wpi::units::math::abs(state.velocity + 1_mps) < 10e-5_mps)) { EXPECT_NEAR(unit_cast(predictedTimeLeft), i / 100.0, 2e-2); reachedGoal = true; } @@ -236,53 +236,53 @@ TEST(TrapezoidProfileTest, TimingBeforeNegativeGoal) { } TEST(TrapezoidProfileTest, InitalizationOfCurrentState) { - frc::TrapezoidProfile::Constraints constraints{1_mps, 1_mps_sq}; - frc::TrapezoidProfile profile{constraints}; + wpi::math::TrapezoidProfile::Constraints constraints{1_mps, 1_mps_sq}; + wpi::math::TrapezoidProfile profile{constraints}; EXPECT_NEAR_UNITS(profile.TimeLeftUntil(0_m), 0_s, 1e-10_s); EXPECT_NEAR_UNITS(profile.TotalTime(), 0_s, 1e-10_s); } TEST(TrapezoidProfileTest, InitialVelocityConstraints) { - frc::TrapezoidProfile::Constraints constraints{0.75_mps, + wpi::math::TrapezoidProfile::Constraints constraints{0.75_mps, 0.75_mps_sq}; - frc::TrapezoidProfile::State goal{10_m, 0_mps}; - frc::TrapezoidProfile::State state{0_m, -10_mps}; + wpi::math::TrapezoidProfile::State goal{10_m, 0_mps}; + wpi::math::TrapezoidProfile::State state{0_m, -10_mps}; - frc::TrapezoidProfile profile{constraints}; + wpi::math::TrapezoidProfile profile{constraints}; for (int i = 0; i < 200; ++i) { state = profile.Calculate(kDt, state, goal); - EXPECT_LE(units::math::abs(state.velocity), - units::math::abs(constraints.maxVelocity)); + EXPECT_LE(wpi::units::math::abs(state.velocity), + wpi::units::math::abs(constraints.maxVelocity)); } } TEST(TrapezoidProfileTest, GoalVelocityConstraints) { - frc::TrapezoidProfile::Constraints constraints{0.75_mps, + wpi::math::TrapezoidProfile::Constraints constraints{0.75_mps, 0.75_mps_sq}; - frc::TrapezoidProfile::State goal{10_m, 5_mps}; - frc::TrapezoidProfile::State state{0_m, 0.75_mps}; + wpi::math::TrapezoidProfile::State goal{10_m, 5_mps}; + wpi::math::TrapezoidProfile::State state{0_m, 0.75_mps}; - frc::TrapezoidProfile profile{constraints}; + wpi::math::TrapezoidProfile profile{constraints}; for (int i = 0; i < 200; ++i) { state = profile.Calculate(kDt, state, goal); - EXPECT_LE(units::math::abs(state.velocity), - units::math::abs(constraints.maxVelocity)); + EXPECT_LE(wpi::units::math::abs(state.velocity), + wpi::units::math::abs(constraints.maxVelocity)); } } TEST(TrapezoidProfileTest, NegativeGoalVelocityConstraints) { - frc::TrapezoidProfile::Constraints constraints{0.75_mps, + wpi::math::TrapezoidProfile::Constraints constraints{0.75_mps, 0.75_mps_sq}; - frc::TrapezoidProfile::State goal{10_m, -5_mps}; - frc::TrapezoidProfile::State state{0_m, 0.75_mps}; + wpi::math::TrapezoidProfile::State goal{10_m, -5_mps}; + wpi::math::TrapezoidProfile::State state{0_m, 0.75_mps}; - frc::TrapezoidProfile profile{constraints}; + wpi::math::TrapezoidProfile profile{constraints}; for (int i = 0; i < 200; ++i) { state = profile.Calculate(kDt, state, goal); - EXPECT_LE(units::math::abs(state.velocity), - units::math::abs(constraints.maxVelocity)); + EXPECT_LE(wpi::units::math::abs(state.velocity), + wpi::units::math::abs(constraints.maxVelocity)); } } diff --git a/wpimath/src/test/native/cpp/trajectory/proto/TrajectoryProtoTest.cpp b/wpimath/src/test/native/cpp/trajectory/proto/TrajectoryProtoTest.cpp index c4b87f6997..ac9c399548 100644 --- a/wpimath/src/test/native/cpp/trajectory/proto/TrajectoryProtoTest.cpp +++ b/wpimath/src/test/native/cpp/trajectory/proto/TrajectoryProtoTest.cpp @@ -7,27 +7,27 @@ #include "wpi/math/trajectory/Trajectory.hpp" #include "wpi/util/SmallVector.hpp" -using namespace frc; +using namespace wpi::math; namespace { -using ProtoType = wpi::Protobuf; +using ProtoType = wpi::util::Protobuf; -const Trajectory kExpectedData = Trajectory{std::vector{ +const Trajectory kExpectedData = Trajectory{std::vector{ Trajectory::State{1.1_s, 2.2_mps, 3.3_mps_sq, Pose2d(Translation2d(1.1_m, 2.2_m), Rotation2d(2.2_rad)), - units::curvature_t{6.6}}, + wpi::units::curvature_t{6.6}}, Trajectory::State{2.1_s, 2.2_mps, 3.3_mps_sq, Pose2d(Translation2d(2.1_m, 2.2_m), Rotation2d(2.2_rad)), - units::curvature_t{6.6}}, + wpi::units::curvature_t{6.6}}, Trajectory::State{3.1_s, 2.2_mps, 3.3_mps_sq, Pose2d(Translation2d(3.1_m, 2.2_m), Rotation2d(2.2_rad)), - units::curvature_t{6.6}}}}; + wpi::units::curvature_t{6.6}}}}; } // namespace TEST(TrajectoryProtoTest, Roundtrip) { - wpi::ProtobufMessage message; - wpi::SmallVector buf; + wpi::util::ProtobufMessage message; + wpi::util::SmallVector buf; ASSERT_TRUE(message.Pack(buf, kExpectedData)); auto unpacked_data = message.Unpack(buf); diff --git a/wpimath/src/test/native/cpp/trajectory/proto/TrajectoryStateProtoTest.cpp b/wpimath/src/test/native/cpp/trajectory/proto/TrajectoryStateProtoTest.cpp index 9b27dcf3c2..1fe0d4b7d3 100644 --- a/wpimath/src/test/native/cpp/trajectory/proto/TrajectoryStateProtoTest.cpp +++ b/wpimath/src/test/native/cpp/trajectory/proto/TrajectoryStateProtoTest.cpp @@ -7,21 +7,21 @@ #include "wpi/math/trajectory/Trajectory.hpp" #include "wpi/util/SmallVector.hpp" -using namespace frc; +using namespace wpi::math; namespace { -using ProtoType = wpi::Protobuf; +using ProtoType = wpi::util::Protobuf; const Trajectory::State kExpectedData = Trajectory::State{ 1.91_s, 4.4_mps, 17.4_mps_sq, Pose2d{Translation2d{1.74_m, 19.1_m}, Rotation2d{22.9_rad}}, - units::curvature_t{0.174}}; + wpi::units::curvature_t{0.174}}; } // namespace TEST(TrajectoryStateProtoTest, Roundtrip) { - wpi::ProtobufMessage message; - wpi::SmallVector buf; + wpi::util::ProtobufMessage message; + wpi::util::SmallVector buf; ASSERT_TRUE(message.Pack(buf, kExpectedData)); auto unpacked_data = message.Unpack(buf); diff --git a/wpimath/src/test/native/include/wpi/math/trajectory/TestTrajectory.hpp b/wpimath/src/test/native/include/wpi/math/trajectory/TestTrajectory.hpp index af9f9e9b73..f25a7ef7fb 100644 --- a/wpimath/src/test/native/include/wpi/math/trajectory/TestTrajectory.hpp +++ b/wpimath/src/test/native/include/wpi/math/trajectory/TestTrajectory.hpp @@ -12,7 +12,7 @@ #include "wpi/math/trajectory/TrajectoryGenerator.hpp" #include "wpi/math/trajectory/constraint/TrajectoryConstraint.hpp" -namespace frc { +namespace wpi::math { class TestTrajectory { public: static Trajectory GetTrajectory(TrajectoryConfig& config) { @@ -33,4 +33,4 @@ class TestTrajectory { } }; -} // namespace frc +} // namespace wpi::math diff --git a/wpimath/src/test/python/cpp/wpimath_test/include/module.h b/wpimath/src/test/python/cpp/wpimath_test/include/module.h index 7d2f256f50..3e2b18876b 100644 --- a/wpimath/src/test/python/cpp/wpimath_test/include/module.h +++ b/wpimath/src/test/python/cpp/wpimath_test/include/module.h @@ -7,18 +7,18 @@ struct SomeClass { static constexpr auto s_constant = 2_s; static constexpr auto ms_constant1 = 20_ms; - static constexpr units::second_t ms_constant2 = 50_ms; - static constexpr units::millisecond_t ms_constant3 = 0.20_s; + static constexpr wpi::units::second_t ms_constant2 = 50_ms; + static constexpr wpi::units::millisecond_t ms_constant3 = 0.20_s; - bool checkDefaultByName1(units::second_t period = ms_constant1); - bool checkDefaultByName2(units::second_t period = ms_constant2); - bool checkDefaultByNum1(units::second_t period = 50_ms); - bool checkDefaultByNum2(units::second_t period = 0.5_s); + bool checkDefaultByName1(wpi::units::second_t period = ms_constant1); + bool checkDefaultByName2(wpi::units::second_t period = ms_constant2); + bool checkDefaultByNum1(wpi::units::second_t period = 50_ms); + bool checkDefaultByNum2(wpi::units::second_t period = 0.5_s); - units::second_t ms2s(units::millisecond_t ms); - units::millisecond_t s2ms(units::second_t s); + wpi::units::second_t ms2s(wpi::units::millisecond_t ms); + wpi::units::millisecond_t s2ms(wpi::units::second_t s); - static constexpr units::foot_t five_ft = 5_ft; + static constexpr wpi::units::foot_t five_ft = 5_ft; - units::meter_t ft2m(units::foot_t f); + wpi::units::meter_t ft2m(wpi::units::foot_t f); }; \ No newline at end of file diff --git a/wpimath/src/test/python/cpp/wpimath_test/src/module.cpp b/wpimath/src/test/python/cpp/wpimath_test/src/module.cpp index c101790b32..129fdb402b 100644 --- a/wpimath/src/test/python/cpp/wpimath_test/src/module.cpp +++ b/wpimath/src/test/python/cpp/wpimath_test/src/module.cpp @@ -8,46 +8,46 @@ SEMIWRAP_PYBIND11_MODULE(m) initWrapper(m); } -bool SomeClass::checkDefaultByName1(units::second_t period) +bool SomeClass::checkDefaultByName1(wpi::units::second_t period) { if (period != SomeClass::ms_constant1) { - throw std::runtime_error(units::to_string(period)); + throw std::runtime_error(wpi::units::to_string(period)); } return true; } -bool SomeClass::checkDefaultByName2(units::second_t period) +bool SomeClass::checkDefaultByName2(wpi::units::second_t period) { if (period != SomeClass::ms_constant2) { - throw std::runtime_error(units::to_string(period)); + throw std::runtime_error(wpi::units::to_string(period)); } return true; } -bool SomeClass::checkDefaultByNum1(units::second_t period) +bool SomeClass::checkDefaultByNum1(wpi::units::second_t period) { if (period != 50_ms) { - throw std::runtime_error(units::to_string(period)); + throw std::runtime_error(wpi::units::to_string(period)); } return true; } -bool SomeClass::checkDefaultByNum2(units::second_t period) +bool SomeClass::checkDefaultByNum2(wpi::units::second_t period) { if (period != 50_ms) { - throw std::runtime_error(units::to_string(period)); + throw std::runtime_error(wpi::units::to_string(period)); } return true; } -units::meter_t SomeClass::ft2m(units::foot_t f) { +wpi::units::meter_t SomeClass::ft2m(wpi::units::foot_t f) { return f; } -units::second_t SomeClass::ms2s(units::millisecond_t ms) { +wpi::units::second_t SomeClass::ms2s(wpi::units::millisecond_t ms) { return ms; } -units::millisecond_t SomeClass::s2ms(units::second_t s) { +wpi::units::millisecond_t SomeClass::s2ms(wpi::units::second_t s) { return s; } diff --git a/wpinet/examples/dsclient/dsclient.cpp b/wpinet/examples/dsclient/dsclient.cpp index 3e4e03d705..713cc13452 100644 --- a/wpinet/examples/dsclient/dsclient.cpp +++ b/wpinet/examples/dsclient/dsclient.cpp @@ -10,7 +10,7 @@ #include "wpi/util/Logger.hpp" #include "wpi/util/print.hpp" -namespace uv = wpi::uv; +namespace uv = wpi::net::uv; static void logfunc(unsigned int level, const char* file, unsigned int line, const char* msg) { @@ -18,15 +18,15 @@ static void logfunc(unsigned int level, const char* file, unsigned int line, } int main() { - wpi::Logger logger{logfunc, 0}; + wpi::util::Logger logger{logfunc, 0}; // Kick off the event loop on a separate thread - wpi::EventLoopRunner loop; - std::shared_ptr client; + wpi::net::EventLoopRunner loop; + std::shared_ptr client; loop.ExecAsync([&](uv::Loop& loop) { - client = wpi::DsClient::Create(loop, logger); + client = wpi::net::DsClient::Create(loop, logger); client->setIp.connect( - [](std::string_view ip) { wpi::print("got IP: {}\n", ip); }); + [](std::string_view ip) { wpi::util::print("got IP: {}\n", ip); }); client->clearIp.connect([] { std::fputs("cleared IP\n", stdout); }); }); diff --git a/wpinet/examples/parallelconnect/parallelconnect.cpp b/wpinet/examples/parallelconnect/parallelconnect.cpp index 6f1c680921..81442f8bb3 100644 --- a/wpinet/examples/parallelconnect/parallelconnect.cpp +++ b/wpinet/examples/parallelconnect/parallelconnect.cpp @@ -11,7 +11,7 @@ #include "wpi/net/uv/Tcp.hpp" #include "wpi/util/Logger.hpp" -namespace uv = wpi::uv; +namespace uv = wpi::net::uv; static void logfunc(unsigned int level, const char* file, unsigned int line, const char* msg) { @@ -19,13 +19,13 @@ static void logfunc(unsigned int level, const char* file, unsigned int line, } int main() { - wpi::Logger logger{logfunc, 0}; + wpi::util::Logger logger{logfunc, 0}; // Kick off the event loop on a separate thread - wpi::EventLoopRunner loop; - std::shared_ptr connect; + wpi::net::EventLoopRunner loop; + std::shared_ptr connect; loop.ExecAsync([&](uv::Loop& loop) { - connect = wpi::ParallelTcpConnector::Create( + connect = wpi::net::ParallelTcpConnector::Create( loop, uv::Timer::Time{2000}, logger, [&](uv::Tcp& tcp) { std::fputs("Got connection, accepting!\n", stdout); tcp.StartRead(); diff --git a/wpinet/examples/webserver/webserver.cpp b/wpinet/examples/webserver/webserver.cpp index 92483fede6..4430947a67 100644 --- a/wpinet/examples/webserver/webserver.cpp +++ b/wpinet/examples/webserver/webserver.cpp @@ -12,9 +12,9 @@ #include "wpi/net/uv/Tcp.hpp" #include "wpi/util/print.hpp" -namespace uv = wpi::uv; +namespace uv = wpi::net::uv; -class MyHttpServerConnection : public wpi::HttpServerConnection { +class MyHttpServerConnection : public wpi::net::HttpServerConnection { public: explicit MyHttpServerConnection(std::shared_ptr stream) : HttpServerConnection(stream) {} @@ -24,9 +24,9 @@ class MyHttpServerConnection : public wpi::HttpServerConnection { }; void MyHttpServerConnection::ProcessRequest() { - wpi::print(stderr, "HTTP request: '{}'\n", m_request.GetUrl()); - wpi::UrlParser url{m_request.GetUrl(), - m_request.GetMethod() == wpi::HTTP_CONNECT}; + wpi::util::print(stderr, "HTTP request: '{}'\n", m_request.GetUrl()); + wpi::net::UrlParser url{m_request.GetUrl(), + m_request.GetMethod() == wpi::net::HTTP_CONNECT}; if (!url.IsValid()) { // failed to parse URL SendError(400); @@ -37,15 +37,15 @@ void MyHttpServerConnection::ProcessRequest() { if (url.HasPath()) { path = url.GetPath(); } - wpi::print(stderr, "path: \"{}\"\n", path); + wpi::util::print(stderr, "path: \"{}\"\n", path); std::string_view query; if (url.HasQuery()) { query = url.GetQuery(); } - wpi::print(stderr, "query: \"{}\"\n", query); + wpi::util::print(stderr, "query: \"{}\"\n", query); - const bool isGET = m_request.GetMethod() == wpi::HTTP_GET; + const bool isGET = m_request.GetMethod() == wpi::net::HTTP_GET; if (isGET && path == "/") { // build HTML root page SendResponse(200, "OK", "text/html", @@ -59,7 +59,7 @@ void MyHttpServerConnection::ProcessRequest() { int main() { // Kick off the event loop on a separate thread - wpi::EventLoopRunner loop; + wpi::net::EventLoopRunner loop; loop.ExecAsync([](uv::Loop& loop) { auto tcp = uv::Tcp::Create(loop); diff --git a/wpinet/src/dev/native/cpp/main.cpp b/wpinet/src/dev/native/cpp/main.cpp index 74f17fbfea..e5b9d37af1 100644 --- a/wpinet/src/dev/native/cpp/main.cpp +++ b/wpinet/src/dev/native/cpp/main.cpp @@ -6,6 +6,6 @@ #include "wpi/util/print.hpp" int main() { - wpi::SmallString<128> v1("Hello"); - wpi::print("{}\n", v1.str()); + wpi::util::SmallString<128> v1("Hello"); + wpi::util::print("{}\n", v1.str()); } diff --git a/wpinet/src/main/native/cpp/DsClient.cpp b/wpinet/src/main/native/cpp/DsClient.cpp index 6e0d2ae376..8c44ae0bf8 100644 --- a/wpinet/src/main/native/cpp/DsClient.cpp +++ b/wpinet/src/main/native/cpp/DsClient.cpp @@ -14,11 +14,11 @@ #include "wpi/util/StringExtras.hpp" #include "wpi/util/json.hpp" -using namespace wpi; +using namespace wpi::net; static constexpr uv::Timer::Time kReconnectTime{500}; -DsClient::DsClient(wpi::uv::Loop& loop, wpi::Logger& logger, +DsClient::DsClient(wpi::net::uv::Loop& loop, wpi::util::Logger& logger, const private_init&) : m_logger{logger}, m_tcp{uv::Tcp::Create(loop)}, @@ -32,7 +32,7 @@ DsClient::DsClient(wpi::uv::Loop& loop, wpi::Logger& logger, // try to connect again m_tcp->Reuse([this] { m_timer->Start(kReconnectTime); }); }); - m_tcp->data.connect([this](wpi::uv::Buffer buf, size_t len) { + m_tcp->data.connect([this](wpi::net::uv::Buffer buf, size_t len) { HandleIncoming({buf.base, len}); }); m_timer->timeout.connect([this] { Connect(); }); @@ -71,7 +71,7 @@ void DsClient::HandleIncoming(std::string_view in) { // if json is empty, look for the first { (and discard) if (m_json.empty()) { auto start = in.find('{'); - in = wpi::slice(in, start, std::string_view::npos); + in = wpi::util::slice(in, start, std::string_view::npos); } // look for the terminating } (and save) @@ -83,8 +83,8 @@ void DsClient::HandleIncoming(std::string_view in) { // have complete json message ++end; - m_json.append(wpi::slice(in, 0, end)); - in = wpi::slice(in, end, std::string_view::npos); + m_json.append(wpi::util::slice(in, 0, end)); + in = wpi::util::slice(in, end, std::string_view::npos); ParseJson(); m_json.clear(); } @@ -94,8 +94,8 @@ void DsClient::ParseJson() { WPI_DEBUG4(m_logger, "DsClient JSON: {}", m_json); unsigned int ip = 0; try { - ip = wpi::json::parse(m_json).at("robotIP").get(); - } catch (wpi::json::exception& e) { + ip = wpi::util::json::parse(m_json).at("robotIP").get(); + } catch (wpi::util::json::exception& e) { WPI_INFO(m_logger, "DsClient JSON error: {}", e.what()); return; } diff --git a/wpinet/src/main/native/cpp/EventLoopRunner.cpp b/wpinet/src/main/native/cpp/EventLoopRunner.cpp index 8bff0c5afe..138b925bee 100644 --- a/wpinet/src/main/native/cpp/EventLoopRunner.cpp +++ b/wpinet/src/main/native/cpp/EventLoopRunner.cpp @@ -13,9 +13,9 @@ #include "wpi/util/condition_variable.hpp" #include "wpi/util/mutex.hpp" -using namespace wpi; +using namespace wpi::net; -class EventLoopRunner::Thread : public SafeThread { +class EventLoopRunner::Thread : public wpi::util::SafeThread { public: using UvExecFunc = uv::AsyncFunction; @@ -75,7 +75,7 @@ void EventLoopRunner::ExecAsync(LoopFunc func) { } void EventLoopRunner::ExecSync(LoopFunc func) { - wpi::future f; + wpi::util::future f; if (auto thr = m_owner.GetThread()) { if (auto doExec = thr->m_doExec.lock()) { f = doExec->Call(std::move(func)); diff --git a/wpinet/src/main/native/cpp/HttpParser.cpp b/wpinet/src/main/native/cpp/HttpParser.cpp index ab7bf0547d..056c5979f1 100644 --- a/wpinet/src/main/native/cpp/HttpParser.cpp +++ b/wpinet/src/main/native/cpp/HttpParser.cpp @@ -4,7 +4,7 @@ #include "wpi/net/HttpParser.hpp" -using namespace wpi; +using namespace wpi::net; uint32_t HttpParser::GetParserVersion() { return static_cast(http_parser_version()); diff --git a/wpinet/src/main/native/cpp/HttpServerConnection.cpp b/wpinet/src/main/native/cpp/HttpServerConnection.cpp index b49a9c02af..eda57693de 100644 --- a/wpinet/src/main/native/cpp/HttpServerConnection.cpp +++ b/wpinet/src/main/native/cpp/HttpServerConnection.cpp @@ -14,7 +14,7 @@ #include "wpi/util/fmt/raw_ostream.hpp" #include "wpi/util/print.hpp" -using namespace wpi; +using namespace wpi::net; HttpServerConnection::HttpServerConnection(std::shared_ptr stream) : m_stream(*stream) { @@ -29,8 +29,8 @@ HttpServerConnection::HttpServerConnection(std::shared_ptr stream) m_request.messageBegin.connect([this] { m_acceptGzip = false; }); m_request.header.connect( [this](std::string_view name, std::string_view value) { - if (wpi::equals_lower(name, "accept-encoding") && - wpi::contains(value, "gzip")) { + if (wpi::util::equals_lower(name, "accept-encoding") && + wpi::util::contains(value, "gzip")) { m_acceptGzip = true; } }); @@ -53,7 +53,7 @@ HttpServerConnection::HttpServerConnection(std::shared_ptr stream) stream->StartRead(); } -void HttpServerConnection::BuildCommonHeaders(raw_ostream& os) { +void HttpServerConnection::BuildCommonHeaders(wpi::util::raw_ostream& os) { os << "Server: WebServer/1.0\r\n" "Cache-Control: no-store, no-cache, must-revalidate, pre-check=0, " "post-check=0, max-age=0\r\n" @@ -61,12 +61,12 @@ void HttpServerConnection::BuildCommonHeaders(raw_ostream& os) { "Expires: Mon, 3 Jan 2000 12:34:56 GMT\r\n"; } -void HttpServerConnection::BuildHeader(raw_ostream& os, int code, +void HttpServerConnection::BuildHeader(wpi::util::raw_ostream& os, int code, std::string_view codeText, std::string_view contentType, uint64_t contentLength, std::string_view extra) { - wpi::print(os, "HTTP/{}.{} {} {}\r\n", m_request.GetMajor(), + wpi::util::print(os, "HTTP/{}.{} {} {}\r\n", m_request.GetMajor(), m_request.GetMinor(), code, codeText); if (contentLength == 0) { m_keepAlive = false; @@ -77,7 +77,7 @@ void HttpServerConnection::BuildHeader(raw_ostream& os, int code, BuildCommonHeaders(os); os << "Content-Type: " << contentType << "\r\n"; if (contentLength != 0) { - wpi::print(os, "Content-Length: {}\r\n", contentLength); + wpi::util::print(os, "Content-Length: {}\r\n", contentLength); } os << "Access-Control-Allow-Origin: *\r\nAccess-Control-Allow-Methods: *\r\n"; if (!extra.empty()) { @@ -102,7 +102,7 @@ void HttpServerConnection::SendResponse(int code, std::string_view codeText, std::string_view contentType, std::string_view content, std::string_view extraHeader) { - SmallVector toSend; + wpi::util::SmallVector toSend; raw_uv_ostream os{toSend, 4096}; BuildHeader(os, code, codeText, contentType, content.size(), extraHeader); os << content; @@ -120,7 +120,7 @@ void HttpServerConnection::SendStaticResponse( contentEncodingHeader = "Content-Encoding: gzip\r\n"; } - SmallVector bufs; + wpi::util::SmallVector bufs; raw_uv_ostream os{bufs, 4096}; BuildHeader(os, code, codeText, contentType, content.size(), fmt::format("{}{}", extraHeader, contentEncodingHeader)); @@ -130,7 +130,7 @@ void HttpServerConnection::SendStaticResponse( m_stream.Write(bufs, [closeAfter = !m_keepAlive, stream = &m_stream]( auto bufs, uv::Error) { // don't deallocate the static content - for (auto&& buf : wpi::drop_back(bufs)) { + for (auto&& buf : wpi::util::drop_back(bufs)) { buf.Deallocate(); } if (closeAfter) { @@ -173,7 +173,7 @@ void HttpServerConnection::SendError(int code, std::string_view message) { baseMessage = "501: Not Implemented!"; break; } - SmallString<256> content{baseMessage}; + wpi::util::SmallString<256> content{baseMessage}; content += "\r\n"; content += message; SendResponse(code, codeText, "text/plain", content.str(), extra); diff --git a/wpinet/src/main/native/cpp/HttpUtil.cpp b/wpinet/src/main/native/cpp/HttpUtil.cpp index 3e55ce53e5..636363943b 100644 --- a/wpinet/src/main/native/cpp/HttpUtil.cpp +++ b/wpinet/src/main/native/cpp/HttpUtil.cpp @@ -14,9 +14,9 @@ #include "wpi/util/StringExtras.hpp" #include "wpi/util/raw_ostream.hpp" -namespace wpi { +namespace wpi::net { -std::string_view UnescapeURI(std::string_view str, SmallVectorImpl& buf, +std::string_view UnescapeURI(std::string_view str, wpi::util::SmallVectorImpl& buf, bool* error) { buf.clear(); for (auto i = str.begin(), end = str.end(); i != end; ++i) { @@ -38,12 +38,12 @@ std::string_view UnescapeURI(std::string_view str, SmallVectorImpl& buf, } // replace %xx with the corresponding character - unsigned val1 = hexDigitValue(*++i); + unsigned val1 = wpi::util::hexDigitValue(*++i); if (val1 == -1U) { *error = true; return {}; } - unsigned val2 = hexDigitValue(*++i); + unsigned val2 = wpi::util::hexDigitValue(*++i); if (val2 == -1U) { *error = true; return {}; @@ -55,7 +55,7 @@ std::string_view UnescapeURI(std::string_view str, SmallVectorImpl& buf, return {buf.data(), buf.size()}; } -std::string_view EscapeURI(std::string_view str, SmallVectorImpl& buf, +std::string_view EscapeURI(std::string_view str, wpi::util::SmallVectorImpl& buf, bool spacePlus) { static const char* const hexLut = "0123456789ABCDEF"; @@ -82,7 +82,7 @@ std::string_view EscapeURI(std::string_view str, SmallVectorImpl& buf, return {buf.data(), buf.size()}; } -std::string_view EscapeHTML(std::string_view str, SmallVectorImpl& buf) { +std::string_view EscapeHTML(std::string_view str, wpi::util::SmallVectorImpl& buf) { buf.clear(); for (auto i = str.begin(), end = str.end(); i != end; ++i) { if (*i == '&') { @@ -99,11 +99,11 @@ std::string_view EscapeHTML(std::string_view str, SmallVectorImpl& buf) { } HttpQueryMap::HttpQueryMap(std::string_view query) { - split(query, '&', 100, false, [&](auto elem) { - auto [nameEsc, valueEsc] = split(elem, '='); - SmallString<64> nameBuf; + wpi::util::split(query, '&', 100, false, [&](auto elem) { + auto [nameEsc, valueEsc] = wpi::util::split(elem, '='); + wpi::util::SmallString<64> nameBuf; bool err = false; - auto name = wpi::UnescapeURI(nameEsc, nameBuf, &err); + auto name = wpi::net::UnescapeURI(nameEsc, nameBuf, &err); // note: ignores duplicates if (!err) { m_elems.try_emplace(name, valueEsc); @@ -112,13 +112,13 @@ HttpQueryMap::HttpQueryMap(std::string_view query) { } std::optional HttpQueryMap::Get( - std::string_view name, wpi::SmallVectorImpl& buf) const { + std::string_view name, wpi::util::SmallVectorImpl& buf) const { auto it = m_elems.find(name); if (it == m_elems.end()) { return {}; } bool err = false; - auto val = wpi::UnescapeURI(it->second, buf, &err); + auto val = wpi::net::UnescapeURI(it->second, buf, &err); if (err) { return {}; } @@ -131,10 +131,10 @@ HttpPath::HttpPath(std::string_view path) { m_pathEnds.emplace_back(0); return; } - split(path, '/', 100, false, [&](auto elem) { - SmallString<64> buf; + wpi::util::split(path, '/', 100, false, [&](auto elem) { + wpi::util::SmallString<64> buf; bool err = false; - auto val = wpi::UnescapeURI(elem, buf, &err); + auto val = wpi::net::UnescapeURI(elem, buf, &err); if (err) { m_pathEnds.clear(); return; @@ -166,8 +166,8 @@ std::string_view HttpPath::operator[](size_t n) const { return slice(m_pathBuf, n == 0 ? 0 : m_pathEnds[n - 1], m_pathEnds[n]); } -bool ParseHttpHeaders(raw_istream& is, SmallVectorImpl* contentType, - SmallVectorImpl* contentLength) { +bool ParseHttpHeaders(wpi::util::raw_istream& is, wpi::util::SmallVectorImpl* contentType, + wpi::util::SmallVectorImpl* contentLength) { if (contentType) { contentType->clear(); } @@ -177,9 +177,9 @@ bool ParseHttpHeaders(raw_istream& is, SmallVectorImpl* contentType, bool inContentType = false; bool inContentLength = false; - SmallString<64> lineBuf; + wpi::util::SmallString<64> lineBuf; for (;;) { - std::string_view line = rtrim(is.getline(lineBuf, 1024)); + std::string_view line = wpi::util::rtrim(is.getline(lineBuf, 1024)); if (is.has_error()) { return false; } @@ -192,11 +192,11 @@ bool ParseHttpHeaders(raw_istream& is, SmallVectorImpl* contentType, inContentType = false; inContentLength = false; std::string_view field; - std::tie(field, line) = split(line, ':'); - field = rtrim(field); - if (equals_lower(field, "content-type")) { + std::tie(field, line) = wpi::util::split(line, ':'); + field = wpi::util::rtrim(field); + if (wpi::util::equals_lower(field, "content-type")) { inContentType = true; - } else if (equals_lower(field, "content-length")) { + } else if (wpi::util::equals_lower(field, "content-length")) { inContentLength = true; } else { continue; // ignore other fields @@ -204,7 +204,7 @@ bool ParseHttpHeaders(raw_istream& is, SmallVectorImpl* contentType, } // collapse whitespace - line = ltrim(line); + line = wpi::util::ltrim(line); // save field data if (inContentType && contentType) { @@ -215,9 +215,9 @@ bool ParseHttpHeaders(raw_istream& is, SmallVectorImpl* contentType, } } -bool FindMultipartBoundary(raw_istream& is, std::string_view boundary, +bool FindMultipartBoundary(wpi::util::raw_istream& is, std::string_view boundary, std::string* saveBuf) { - SmallString<64> searchBuf; + wpi::util::SmallString<64> searchBuf; searchBuf.resize(boundary.size() + 2); size_t searchPos = 0; @@ -246,7 +246,7 @@ bool FindMultipartBoundary(raw_istream& is, std::string_view boundary, // Did we find the boundary? if (searchBuf[0] == '-' && searchBuf[1] == '-' && - wpi::substr(searchBuf, 2) == boundary) { + wpi::util::substr(searchBuf, 2) == boundary) { return true; } @@ -277,15 +277,15 @@ HttpLocation::HttpLocation(std::string_view url_, bool* error, // scheme: std::string_view scheme; - std::tie(scheme, query) = split(query, ':'); - if (!equals_lower(scheme, "http")) { + std::tie(scheme, query) = wpi::util::split(query, ':'); + if (!wpi::util::equals_lower(scheme, "http")) { *errorMsg = "only supports http URLs"; *error = true; return; } // "//" - if (!starts_with(query, "//")) { + if (!wpi::util::starts_with(query, "//")) { *errorMsg = "expected http://..."; *error = true; return; @@ -294,9 +294,9 @@ HttpLocation::HttpLocation(std::string_view url_, bool* error, // user:password@host:port/ std::string_view authority; - std::tie(authority, query) = split(query, '/'); + std::tie(authority, query) = wpi::util::split(query, '/'); - auto [userpass, hostport] = split(authority, '@'); + auto [userpass, hostport] = wpi::util::split(authority, '@'); // split leaves the RHS empty if the split char isn't present... if (hostport.empty()) { hostport = userpass; @@ -304,8 +304,8 @@ HttpLocation::HttpLocation(std::string_view url_, bool* error, } if (!userpass.empty()) { - auto [rawUser, rawPassword] = split(userpass, ':'); - SmallString<64> userBuf, passBuf; + auto [rawUser, rawPassword] = wpi::util::split(userpass, ':'); + wpi::util::SmallString<64> userBuf, passBuf; user = UnescapeURI(rawUser, userBuf, error); if (*error) { *errorMsg = fmt::format("could not unescape user \"{}\"", rawUser); @@ -320,7 +320,7 @@ HttpLocation::HttpLocation(std::string_view url_, bool* error, } std::string_view portStr; - std::tie(host, portStr) = rsplit(hostport, ':'); + std::tie(host, portStr) = wpi::util::rsplit(hostport, ':'); if (host.empty()) { *errorMsg = "host is empty"; *error = true; @@ -328,7 +328,7 @@ HttpLocation::HttpLocation(std::string_view url_, bool* error, } if (portStr.empty()) { port = 80; - } else if (auto p = parse_integer(portStr, 10)) { + } else if (auto p = wpi::util::parse_integer(portStr, 10)) { port = p.value(); } else { *errorMsg = fmt::format("port \"{}\" is not an integer", portStr); @@ -337,22 +337,22 @@ HttpLocation::HttpLocation(std::string_view url_, bool* error, } // path?query#fragment - std::tie(query, fragment) = split(query, '#'); - std::tie(path, query) = split(query, '?'); + std::tie(query, fragment) = wpi::util::split(query, '#'); + std::tie(path, query) = wpi::util::split(query, '?'); // Split query string into parameters while (!query.empty()) { // split out next param and value std::string_view rawParam, rawValue; - std::tie(rawParam, query) = split(query, '&'); + std::tie(rawParam, query) = wpi::util::split(query, '&'); if (rawParam.empty()) { continue; // ignore "&&" } - std::tie(rawParam, rawValue) = split(rawParam, '='); + std::tie(rawParam, rawValue) = wpi::util::split(rawParam, '='); // unescape param *error = false; - SmallString<64> paramBuf; + wpi::util::SmallString<64> paramBuf; std::string_view param = UnescapeURI(rawParam, paramBuf, error); if (*error) { *errorMsg = fmt::format("could not unescape parameter \"{}\"", rawParam); @@ -360,7 +360,7 @@ HttpLocation::HttpLocation(std::string_view url_, bool* error, } // unescape value - SmallString<64> valueBuf; + wpi::util::SmallString<64> valueBuf; std::string_view value = UnescapeURI(rawValue, valueBuf, error); if (*error) { *errorMsg = fmt::format("could not unescape value \"{}\"", rawValue); @@ -375,11 +375,11 @@ HttpLocation::HttpLocation(std::string_view url_, bool* error, void HttpRequest::SetAuth(const HttpLocation& loc) { if (!loc.user.empty()) { - SmallString<64> userpass; + wpi::util::SmallString<64> userpass; userpass += loc.user; userpass += ':'; userpass += loc.password; - Base64Encode(userpass.str(), &auth); + wpi::util::Base64Encode(userpass.str(), &auth); } } @@ -395,8 +395,8 @@ bool HttpConnection::Handshake(const HttpRequest& request, os.flush(); // read first line of response - SmallString<64> lineBuf; - std::string_view line = rtrim(is.getline(lineBuf, 1024)); + wpi::util::SmallString<64> lineBuf; + std::string_view line = wpi::util::rtrim(is.getline(lineBuf, 1024)); if (is.has_error()) { *warnMsg = "disconnected before response"; return false; @@ -404,9 +404,9 @@ bool HttpConnection::Handshake(const HttpRequest& request, // see if we got a HTTP 200 response std::string_view httpver, code, codeText; - std::tie(httpver, line) = split(line, ' '); - std::tie(code, codeText) = split(line, ' '); - if (!starts_with(httpver, "HTTP")) { + std::tie(httpver, line) = wpi::util::split(line, ' '); + std::tie(code, codeText) = wpi::util::split(line, ' '); + if (!wpi::util::starts_with(httpver, "HTTP")) { *warnMsg = "did not receive HTTP response"; return false; } @@ -487,7 +487,7 @@ std::string_view HttpMultipartScanner::Execute(std::string_view in) { } if (m_state == kPadding) { - for (char ch : drop_front(in, pos)) { + for (char ch : wpi::util::drop_front(in, pos)) { ++pos; if (ch == '\n') { // Found the LF; return remaining input buffer (following it) @@ -495,7 +495,7 @@ std::string_view HttpMultipartScanner::Execute(std::string_view in) { if (m_saveSkipped) { m_buf.resize(m_buf.size() - in.size() + pos); } - return drop_front(in, pos); + return wpi::util::drop_front(in, pos); } } } @@ -504,4 +504,4 @@ std::string_view HttpMultipartScanner::Execute(std::string_view in) { return {}; } -} // namespace wpi +} // namespace wpi::net diff --git a/wpinet/src/main/native/cpp/MimeTypes.cpp b/wpinet/src/main/native/cpp/MimeTypes.cpp index 0eb58cfee0..b852b8c8bf 100644 --- a/wpinet/src/main/native/cpp/MimeTypes.cpp +++ b/wpinet/src/main/native/cpp/MimeTypes.cpp @@ -7,13 +7,13 @@ #include "wpi/util/StringExtras.hpp" #include "wpi/util/StringMap.hpp" -namespace wpi { +namespace wpi::net { // derived partially from // https://github.com/DEGoodmanWilson/libmime/blob/stable/0.1.2/mime/mime.cpp std::string_view MimeTypeFromPath(std::string_view path) { // https://developer.mozilla.org/en-US/docs/Web/HTTP/Basics_of_HTTP/MIME_types - static StringMap mimeTypes{ + static wpi::util::StringMap mimeTypes{ // text {"css", "text/css"}, {"csv", "text/csv"}, @@ -54,11 +54,11 @@ std::string_view MimeTypeFromPath(std::string_view path) { auto pos = path.find_last_of("/"); if (pos != std::string_view::npos) { - path = wpi::substr(path, pos + 1); + path = wpi::util::substr(path, pos + 1); } auto dot_pos = path.find_last_of("."); if (dot_pos > 0 && dot_pos != std::string_view::npos) { - auto type = mimeTypes.find(wpi::substr(path, dot_pos + 1)); + auto type = mimeTypes.find(wpi::util::substr(path, dot_pos + 1)); if (type != mimeTypes.end()) { return type->second; } @@ -66,4 +66,4 @@ std::string_view MimeTypeFromPath(std::string_view path) { return defaultType; } -} // namespace wpi +} // namespace wpi::net diff --git a/wpinet/src/main/native/cpp/MulticastHandleManager.cpp b/wpinet/src/main/native/cpp/MulticastHandleManager.cpp index 5d6c8ac3ea..6bba30a579 100644 --- a/wpinet/src/main/native/cpp/MulticastHandleManager.cpp +++ b/wpinet/src/main/native/cpp/MulticastHandleManager.cpp @@ -4,9 +4,9 @@ #include "MulticastHandleManager.hpp" -using namespace wpi; +using namespace wpi::net; -MulticastHandleManager& wpi::GetMulticastManager() { +MulticastHandleManager& wpi::net::GetMulticastManager() { static MulticastHandleManager manager; return manager; } diff --git a/wpinet/src/main/native/cpp/MulticastHandleManager.hpp b/wpinet/src/main/native/cpp/MulticastHandleManager.hpp index d7916cc0e4..f78a98e526 100644 --- a/wpinet/src/main/native/cpp/MulticastHandleManager.hpp +++ b/wpinet/src/main/native/cpp/MulticastHandleManager.hpp @@ -11,13 +11,13 @@ #include "wpi/util/DenseMap.hpp" #include "wpi/util/UidVector.hpp" -namespace wpi { +namespace wpi::net { struct MulticastHandleManager { - wpi::mutex mutex; - wpi::UidVector handleIds; - wpi::DenseMap> + wpi::util::mutex mutex; + wpi::util::UidVector handleIds; + wpi::util::DenseMap> resolvers; - wpi::DenseMap> + wpi::util::DenseMap> announcers; #ifdef _WIN32 ~MulticastHandleManager(); @@ -25,4 +25,4 @@ struct MulticastHandleManager { }; MulticastHandleManager& GetMulticastManager(); -} // namespace wpi +} // namespace wpi::net diff --git a/wpinet/src/main/native/cpp/MulticastServiceAnnouncer.cpp b/wpinet/src/main/native/cpp/MulticastServiceAnnouncer.cpp index 462e484748..e5aba552de 100644 --- a/wpinet/src/main/native/cpp/MulticastServiceAnnouncer.cpp +++ b/wpinet/src/main/native/cpp/MulticastServiceAnnouncer.cpp @@ -16,17 +16,17 @@ WPI_MulticastServiceAnnouncerHandle WPI_CreateMulticastServiceAnnouncer( int32_t txtCount, const char** keys, const char** values) { - auto& manager = wpi::GetMulticastManager(); + auto& manager = wpi::net::GetMulticastManager(); std::scoped_lock lock{manager.mutex}; - wpi::SmallVector, 8> txts; + wpi::util::SmallVector, 8> txts; for (int32_t i = 0; i < txtCount; i++) { txts.emplace_back( std::pair{keys[i], values[i]}); } - auto announcer = std::make_unique( + auto announcer = std::make_unique( serviceName, serviceType, port, txts); size_t index = manager.handleIds.emplace_back(3); @@ -37,7 +37,7 @@ WPI_MulticastServiceAnnouncerHandle WPI_CreateMulticastServiceAnnouncer( void WPI_FreeMulticastServiceAnnouncer( WPI_MulticastServiceAnnouncerHandle handle) { - auto& manager = wpi::GetMulticastManager(); + auto& manager = wpi::net::GetMulticastManager(); std::scoped_lock lock{manager.mutex}; manager.announcers[handle] = nullptr; manager.handleIds.erase(handle); @@ -45,7 +45,7 @@ void WPI_FreeMulticastServiceAnnouncer( void WPI_StartMulticastServiceAnnouncer( WPI_MulticastServiceAnnouncerHandle handle) { - auto& manager = wpi::GetMulticastManager(); + auto& manager = wpi::net::GetMulticastManager(); std::scoped_lock lock{manager.mutex}; auto& announcer = manager.announcers[handle]; announcer->Start(); @@ -53,7 +53,7 @@ void WPI_StartMulticastServiceAnnouncer( void WPI_StopMulticastServiceAnnouncer( WPI_MulticastServiceAnnouncerHandle handle) { - auto& manager = wpi::GetMulticastManager(); + auto& manager = wpi::net::GetMulticastManager(); std::scoped_lock lock{manager.mutex}; auto& announcer = manager.announcers[handle]; announcer->Stop(); @@ -61,7 +61,7 @@ void WPI_StopMulticastServiceAnnouncer( int32_t WPI_GetMulticastServiceAnnouncerHasImplementation( WPI_MulticastServiceAnnouncerHandle handle) { - auto& manager = wpi::GetMulticastManager(); + auto& manager = wpi::net::GetMulticastManager(); std::scoped_lock lock{manager.mutex}; auto& announcer = manager.announcers[handle]; return announcer->HasImplementation(); diff --git a/wpinet/src/main/native/cpp/MulticastServiceResolver.cpp b/wpinet/src/main/native/cpp/MulticastServiceResolver.cpp index a230523460..90ebcc6164 100644 --- a/wpinet/src/main/native/cpp/MulticastServiceResolver.cpp +++ b/wpinet/src/main/native/cpp/MulticastServiceResolver.cpp @@ -16,10 +16,10 @@ WPI_MulticastServiceResolverHandle WPI_CreateMulticastServiceResolver( const char* serviceType) { - auto& manager = wpi::GetMulticastManager(); + auto& manager = wpi::net::GetMulticastManager(); std::scoped_lock lock{manager.mutex}; - auto resolver = std::make_unique(serviceType); + auto resolver = std::make_unique(serviceType); size_t index = manager.handleIds.emplace_back(2); manager.resolvers[index] = std::move(resolver); @@ -29,7 +29,7 @@ WPI_MulticastServiceResolverHandle WPI_CreateMulticastServiceResolver( void WPI_FreeMulticastServiceResolver( WPI_MulticastServiceResolverHandle handle) { - auto& manager = wpi::GetMulticastManager(); + auto& manager = wpi::net::GetMulticastManager(); std::scoped_lock lock{manager.mutex}; manager.resolvers[handle] = nullptr; manager.handleIds.erase(handle); @@ -37,7 +37,7 @@ void WPI_FreeMulticastServiceResolver( void WPI_StartMulticastServiceResolver( WPI_MulticastServiceResolverHandle handle) { - auto& manager = wpi::GetMulticastManager(); + auto& manager = wpi::net::GetMulticastManager(); std::scoped_lock lock{manager.mutex}; auto& resolver = manager.resolvers[handle]; resolver->Start(); @@ -45,7 +45,7 @@ void WPI_StartMulticastServiceResolver( void WPI_StopMulticastServiceResolver( WPI_MulticastServiceResolverHandle handle) { - auto& manager = wpi::GetMulticastManager(); + auto& manager = wpi::net::GetMulticastManager(); std::scoped_lock lock{manager.mutex}; auto& resolver = manager.resolvers[handle]; resolver->Stop(); @@ -53,7 +53,7 @@ void WPI_StopMulticastServiceResolver( int32_t WPI_GetMulticastServiceResolverHasImplementation( WPI_MulticastServiceResolverHandle handle) { - auto& manager = wpi::GetMulticastManager(); + auto& manager = wpi::net::GetMulticastManager(); std::scoped_lock lock{manager.mutex}; auto& resolver = manager.resolvers[handle]; return resolver->HasImplementation(); @@ -61,7 +61,7 @@ int32_t WPI_GetMulticastServiceResolverHasImplementation( WPI_EventHandle WPI_GetMulticastServiceResolverEventHandle( WPI_MulticastServiceResolverHandle handle) { - auto& manager = wpi::GetMulticastManager(); + auto& manager = wpi::net::GetMulticastManager(); std::scoped_lock lock{manager.mutex}; auto& resolver = manager.resolvers[handle]; return resolver->GetEventHandle(); @@ -69,9 +69,9 @@ WPI_EventHandle WPI_GetMulticastServiceResolverEventHandle( WPI_ServiceData* WPI_GetMulticastServiceResolverData( WPI_MulticastServiceResolverHandle handle, int32_t* dataCount) { - std::vector allData; + std::vector allData; { - auto& manager = wpi::GetMulticastManager(); + auto& manager = wpi::net::GetMulticastManager(); std::scoped_lock lock{manager.mutex}; auto& resolver = manager.resolvers[handle]; allData = resolver->GetData(); @@ -99,7 +99,7 @@ WPI_ServiceData* WPI_GetMulticastServiceResolverData( allocSize += valuesTotalLength; } - uint8_t* cDataRaw = reinterpret_cast(wpi::safe_malloc(allocSize)); + uint8_t* cDataRaw = reinterpret_cast(wpi::util::safe_malloc(allocSize)); if (!cDataRaw) { return nullptr; } diff --git a/wpinet/src/main/native/cpp/ParallelTcpConnector.cpp b/wpinet/src/main/native/cpp/ParallelTcpConnector.cpp index 9d157d9c93..5339ef7ba6 100644 --- a/wpinet/src/main/native/cpp/ParallelTcpConnector.cpp +++ b/wpinet/src/main/native/cpp/ParallelTcpConnector.cpp @@ -19,11 +19,11 @@ #include "wpi/net/uv/util.hpp" #include "wpi/util/Logger.hpp" -using namespace wpi; +using namespace wpi::net; ParallelTcpConnector::ParallelTcpConnector( - wpi::uv::Loop& loop, wpi::uv::Timer::Time reconnectRate, - wpi::Logger& logger, std::function connected, + wpi::net::uv::Loop& loop, wpi::net::uv::Timer::Time reconnectRate, + wpi::util::Logger& logger, std::function connected, bool ipv4Only, const private_init&) : m_loop{loop}, m_logger{logger}, @@ -141,7 +141,7 @@ void ParallelTcpConnector::Connect() { auto connreq = std::make_shared(); connreq->connected.connect( [this, tcp = tcp.get()] { - if (m_logger.min_level() <= wpi::WPI_LOG_DEBUG4) { + if (m_logger.min_level() <= wpi::util::WPI_LOG_DEBUG4) { std::string ip; unsigned int port = 0; uv::AddrToName(tcp->GetPeer(), &ip, &port); @@ -167,7 +167,7 @@ void ParallelTcpConnector::Connect() { } }; - if (m_logger.min_level() <= wpi::WPI_LOG_DEBUG4) { + if (m_logger.min_level() <= wpi::util::WPI_LOG_DEBUG4) { std::string ip; unsigned int port = 0; uv::AddrToName(*reinterpret_cast(ai->ai_addr), @@ -203,7 +203,7 @@ void ParallelTcpConnector::Connect() { } } -void ParallelTcpConnector::CancelAll(wpi::uv::Tcp* except) { +void ParallelTcpConnector::CancelAll(wpi::net::uv::Tcp* except) { WPI_DEBUG4(m_logger, "canceling previous attempts"); for (auto&& resolverWeak : m_resolvers) { if (auto resolver = resolverWeak.lock()) { diff --git a/wpinet/src/main/native/cpp/PortForwarder.cpp b/wpinet/src/main/native/cpp/PortForwarder.cpp index e6a2816394..b504c5cc5e 100644 --- a/wpinet/src/main/native/cpp/PortForwarder.cpp +++ b/wpinet/src/main/native/cpp/PortForwarder.cpp @@ -16,12 +16,12 @@ #include "wpi/util/DenseMap.hpp" #include "wpi/util/print.hpp" -using namespace wpi; +using namespace wpi::net; struct PortForwarder::Impl { public: EventLoopRunner runner; - DenseMap> servers; + wpi::util::DenseMap> servers; }; PortForwarder::PortForwarder() : m_impl{new Impl} {} @@ -54,7 +54,7 @@ void PortForwarder::Add(unsigned int port, std::string_view remoteHost, m_impl->runner.ExecSync([&](uv::Loop& loop) { auto server = uv::Tcp::Create(loop); if (!server) { - wpi::print(stderr, "PortForwarder: Creating server failed\n"); + wpi::util::print(stderr, "PortForwarder: Creating server failed\n"); return; } @@ -67,7 +67,7 @@ void PortForwarder::Add(unsigned int port, std::string_view remoteHost, auto& loop = serverPtr->GetLoopRef(); auto client = serverPtr->Accept(); if (!client) { - wpi::print(stderr, "PortForwarder: Connecting to client failed\n"); + wpi::util::print(stderr, "PortForwarder: Connecting to client failed\n"); return; } @@ -81,7 +81,7 @@ void PortForwarder::Add(unsigned int port, std::string_view remoteHost, auto remote = uv::Tcp::Create(loop); if (!remote) { - wpi::print(stderr, "PortForwarder: Creating remote failed\n"); + wpi::util::print(stderr, "PortForwarder: Creating remote failed\n"); client->Close(); return; } @@ -113,7 +113,7 @@ void PortForwarder::Add(unsigned int port, std::string_view remoteHost, return; } *(client->GetData()) = true; - wpi::print("PortForwarder: Connected to remote port\n"); + wpi::util::print("PortForwarder: Connected to remote port\n"); // close both when either side closes client->end.connect([clientPtr = client.get(), remoteWeak] { diff --git a/wpinet/src/main/native/cpp/SocketError.cpp b/wpinet/src/main/native/cpp/SocketError.cpp index 27c4f43169..6e3c04de28 100644 --- a/wpinet/src/main/native/cpp/SocketError.cpp +++ b/wpinet/src/main/native/cpp/SocketError.cpp @@ -13,7 +13,7 @@ #include #endif -namespace wpi { +namespace wpi::net { int SocketErrno() { #ifdef _WIN32 @@ -36,4 +36,4 @@ std::string SocketStrerror(int code) { #endif } -} // namespace wpi +} // namespace wpi::net diff --git a/wpinet/src/main/native/cpp/UDPClient.cpp b/wpinet/src/main/native/cpp/UDPClient.cpp index ef80809f1c..dd1086f60d 100644 --- a/wpinet/src/main/native/cpp/UDPClient.cpp +++ b/wpinet/src/main/native/cpp/UDPClient.cpp @@ -22,11 +22,11 @@ #include "wpi/util/Logger.hpp" #include "wpi/util/SmallString.hpp" -using namespace wpi; +using namespace wpi::net; -UDPClient::UDPClient(Logger& logger) : UDPClient("", logger) {} +UDPClient::UDPClient(wpi::util::Logger& logger) : UDPClient("", logger) {} -UDPClient::UDPClient(std::string_view address, Logger& logger) +UDPClient::UDPClient(std::string_view address, wpi::util::Logger& logger) : m_lsd(0), m_port(0), m_address(address), m_logger(logger) {} UDPClient::UDPClient(UDPClient&& other) @@ -85,7 +85,7 @@ int UDPClient::start(int port) { addr.sin_family = AF_INET; if (m_address.size() > 0) { #ifdef _WIN32 - SmallString<128> addr_copy(m_address); + wpi::util::SmallString<128> addr_copy(m_address); addr_copy.push_back('\0'); int res = InetPton(PF_INET, addr_copy.data(), &(addr.sin_addr)); #else @@ -143,7 +143,7 @@ int UDPClient::send(std::span data, std::string_view server, struct sockaddr_in addr; std::memset(&addr, 0, sizeof(addr)); addr.sin_family = AF_INET; - SmallString<128> remoteAddr{server}; + wpi::util::SmallString<128> remoteAddr{server}; if (remoteAddr.empty()) { WPI_ERROR(m_logger, "server must be passed"); return -1; @@ -172,7 +172,7 @@ int UDPClient::send(std::string_view data, std::string_view server, int port) { struct sockaddr_in addr; std::memset(&addr, 0, sizeof(addr)); addr.sin_family = AF_INET; - SmallString<128> remoteAddr{server}; + wpi::util::SmallString<128> remoteAddr{server}; if (remoteAddr.empty()) { WPI_ERROR(m_logger, "server must be passed"); return -1; @@ -203,7 +203,7 @@ int UDPClient::receive(uint8_t* data_received, int receive_len) { } int UDPClient::receive(uint8_t* data_received, int receive_len, - SmallVectorImpl* addr_received, + wpi::util::SmallVectorImpl* addr_received, int* port_received) { if (m_port == 0) { return -1; // return if not receiving diff --git a/wpinet/src/main/native/cpp/WebServer.cpp b/wpinet/src/main/native/cpp/WebServer.cpp index 738426ef0c..e019620348 100644 --- a/wpinet/src/main/native/cpp/WebServer.cpp +++ b/wpinet/src/main/native/cpp/WebServer.cpp @@ -33,13 +33,13 @@ #include "wpi/net/uv/Tcp.hpp" #include "wpi/net/uv/Timer.hpp" -using namespace wpi; +using namespace wpi::net; namespace { -class MyHttpConnection : public wpi::HttpServerConnection, +class MyHttpConnection : public wpi::net::HttpServerConnection, public std::enable_shared_from_this { public: - explicit MyHttpConnection(std::shared_ptr stream, + explicit MyHttpConnection(std::shared_ptr stream, std::string_view path) : HttpServerConnection{std::move(stream)}, m_path{path} {} @@ -96,7 +96,7 @@ class SendfileReq : public uv::RequestImpl { return err; } - wpi::sig::Signal<> complete; + wpi::util::sig::Signal<> complete; private: uv_file m_out; @@ -120,7 +120,7 @@ static void Sendfile(uv::Loop& loop, uv_file out, uv_file in, int64_t inOffset, #endif static std::string_view GetMimeType(std::string_view ext) { - static const wpi::StringMap map{ + static const wpi::util::StringMap map{ {"css", "text/css"}, {"csv", "text/csv"}, {"gif", "image/gif"}, @@ -155,14 +155,14 @@ void MyHttpConnection::SendFileResponse(int code, std::string_view codeText, fs::path filename, std::string_view extraHeader) { #ifdef _WIN32 - auto membuf = wpi::MemoryBuffer::GetFile(filename.string()); + auto membuf = wpi::util::MemoryBuffer::GetFile(filename.string()); if (!membuf) { SendError(404); return; } - wpi::SmallVector toSend; - wpi::raw_uv_ostream os{toSend, 4096}; + wpi::util::SmallVector toSend; + wpi::net::raw_uv_ostream os{toSend, 4096}; BuildHeader(os, code, codeText, contentType, (*membuf)->size(), extraHeader); SendData(os.bufs(), false); auto buf = (*membuf)->GetBuffer(); @@ -205,8 +205,8 @@ void MyHttpConnection::SendFileResponse(int code, std::string_view codeText, return; } - wpi::SmallVector toSend; - wpi::raw_uv_ostream os{toSend, 4096}; + wpi::util::SmallVector toSend; + wpi::net::raw_uv_ostream os{toSend, 4096}; BuildHeader(os, code, codeText, contentType, size, extraHeader); SendData(os.bufs(), false); @@ -227,8 +227,8 @@ void MyHttpConnection::SendFileResponse(int code, std::string_view codeText, void MyHttpConnection::ProcessRequest() { // fmt::print(stderr, "HTTP request: '{}'\n", m_request.GetUrl()); - wpi::UrlParser url{m_request.GetUrl(), - m_request.GetMethod() == wpi::HTTP_CONNECT}; + wpi::net::UrlParser url{m_request.GetUrl(), + m_request.GetMethod() == wpi::net::HTTP_CONNECT}; if (!url.IsValid()) { // failed to parse URL SendError(400); @@ -241,7 +241,7 @@ void MyHttpConnection::ProcessRequest() { } // fmt::print(stderr, "path: \"{}\"\n", path); - wpi::SmallString<128> pathBuf; + wpi::util::SmallString<128> pathBuf; bool error; path = UnescapeURI(path, pathBuf, &error); if (error) { @@ -256,49 +256,49 @@ void MyHttpConnection::ProcessRequest() { // fmt::print(stderr, "query: \"{}\"\n", query); HttpQueryMap qmap{query}; - const bool isGET = m_request.GetMethod() == wpi::HTTP_GET; - if (isGET && wpi::starts_with(path, '/') && !wpi::contains(path, "..")) { + const bool isGET = m_request.GetMethod() == wpi::net::HTTP_GET; + if (isGET && wpi::util::starts_with(path, '/') && !wpi::util::contains(path, "..")) { fs::path fullpath = fmt::format("{}{}", m_path, path); std::error_code ec; bool isdir = fs::is_directory(fullpath, ec); if (isdir) { - if (!wpi::ends_with(path, '/')) { + if (!wpi::util::ends_with(path, '/')) { // redirect to trailing / location SendResponse(301, "Moved Permanently", "text/plain", "", fmt::format("Location: {}/\r\n\r\n", path)); return; } // generate directory listing - wpi::SmallString<64> formatBuf; + wpi::util::SmallString<64> formatBuf; fs::path indexpath = fs::path{fullpath} / "index.html"; if (qmap.Get("format", formatBuf).value_or("") == "json") { - wpi::json dirs = wpi::json::array(); - wpi::json files = wpi::json::array(); + wpi::util::json dirs = wpi::util::json::array(); + wpi::util::json files = wpi::util::json::array(); for (auto&& entry : fs::directory_iterator{fullpath}) { bool subdir = entry.is_directory(ec); std::string name = entry.path().filename().string(); if (subdir) { - dirs.emplace_back(wpi::json{{"name", std::move(name)}}); + dirs.emplace_back(wpi::util::json{{"name", std::move(name)}}); } else { files.emplace_back( - wpi::json{{"name", std::move(name)}, + wpi::util::json{{"name", std::move(name)}, {"size", subdir ? 0 : entry.file_size(ec)}}); } } SendResponse( 200, "OK", "text/json", - wpi::json{{"dirs", std::move(dirs)}, {"files", std::move(files)}} + wpi::util::json{{"dirs", std::move(dirs)}, {"files", std::move(files)}} .dump()); } else if (fs::exists(indexpath)) { SendFileResponse(200, "OK", GetMimeType("html"), indexpath, "Content-Disposition: filename=\"index.html\"\r\n"); } else { - wpi::StringMap dirs; - wpi::StringMap files; + wpi::util::StringMap dirs; + wpi::util::StringMap files; for (auto&& entry : fs::directory_iterator{fullpath}) { bool subdir = entry.is_directory(ec); std::string name = entry.path().filename().string(); - wpi::SmallString<128> nameUriBuf, nameHtmlBuf; + wpi::util::SmallString<128> nameUriBuf, nameHtmlBuf; if (subdir) { dirs.emplace( name, fmt::format( @@ -328,12 +328,12 @@ void MyHttpConnection::ProcessRequest() { SendResponse(200, "OK", "text/html", html); } } else { - wpi::SmallString<128> extraHeadersBuf; - wpi::raw_svector_ostream os{extraHeadersBuf}; + wpi::util::SmallString<128> extraHeadersBuf; + wpi::util::raw_svector_ostream os{extraHeadersBuf}; os << "Content-Disposition: filename=\""; os.write_escaped(fullpath.filename().string()); os << "\"\r\n"; - SendFileResponse(200, "OK", GetMimeType(wpi::rsplit(path, '.').second), + SendFileResponse(200, "OK", GetMimeType(wpi::util::rsplit(path, '.').second), fullpath, os.str()); } } else { @@ -344,7 +344,7 @@ void MyHttpConnection::ProcessRequest() { struct WebServer::Impl { public: EventLoopRunner runner; - DenseMap> servers; + wpi::util::DenseMap> servers; }; WebServer::WebServer() : m_impl{new Impl} {} @@ -358,7 +358,7 @@ void WebServer::Start(unsigned int port, std::string_view path) { m_impl->runner.ExecSync([&](uv::Loop& loop) { auto server = uv::Tcp::Create(loop); if (!server) { - wpi::print(stderr, "WebServer: Creating server failed\n"); + wpi::util::print(stderr, "WebServer: Creating server failed\n"); return; } @@ -370,7 +370,7 @@ void WebServer::Start(unsigned int port, std::string_view path) { [serverPtr = server.get(), path = std::string{path}] { auto client = serverPtr->Accept(); if (!client) { - wpi::print(stderr, "WebServer: Connecting to client failed\n"); + wpi::util::print(stderr, "WebServer: Connecting to client failed\n"); return; } diff --git a/wpinet/src/main/native/cpp/WebSocket.cpp b/wpinet/src/main/native/cpp/WebSocket.cpp index bdacbbea2b..4f91ae4da4 100644 --- a/wpinet/src/main/native/cpp/WebSocket.cpp +++ b/wpinet/src/main/native/cpp/WebSocket.cpp @@ -25,12 +25,12 @@ #include "wpi/util/raw_ostream.hpp" #include "wpi/util/sha1.hpp" -using namespace wpi; +using namespace wpi::net; static std::string DebugBinary(std::span val) { #ifdef WPINET_WEBSOCKET_VERBOSE_DEBUG_CONTENT std::string str; - wpi::raw_string_ostream stros{str}; + wpi::util::raw_string_ostream stros{str}; size_t limited = 0; if (val.size() > 30) { limited = val.size(); @@ -122,8 +122,8 @@ class WebSocket::ClientHandshakeData { for (char& v : nonce) { v = static_cast(dist(gen)); } - raw_svector_ostream os(key); - Base64Encode(os, {nonce, 16}); + wpi::util::raw_svector_ostream os(key); + wpi::util::Base64Encode(os, {nonce, 16}); } ~ClientHandshakeData() { if (auto t = timer.lock()) { @@ -132,8 +132,8 @@ class WebSocket::ClientHandshakeData { } } - SmallString<64> key; // the key sent to the server - SmallVector protocols; // valid protocols + wpi::util::SmallString<64> key; // the key sent to the server + wpi::util::SmallVector protocols; // valid protocols HttpParser parser{HttpParser::kResponse}; // server response parser bool hasUpgrade = false; bool hasConnection = false; @@ -144,12 +144,12 @@ class WebSocket::ClientHandshakeData { }; static std::string_view AcceptHash(std::string_view key, - SmallVectorImpl& buf) { - SHA1 hash; + wpi::util::SmallVectorImpl& buf) { + wpi::util::SHA1 hash; hash.Update(key); hash.Update("258EAFA5-E914-47DA-95CA-C5AB0DC85B11"); - SmallString<64> hashBuf; - return Base64Encode(hash.RawFinal(hashBuf), buf); + wpi::util::SmallString<64> hashBuf; + return wpi::util::Base64Encode(hash.RawFinal(hashBuf), buf); } WebSocket::WebSocket(uv::Stream& stream, bool server, const private_init&) @@ -221,7 +221,7 @@ void WebSocket::StartClient(std::string_view uri, std::string_view host, m_clientHandshake = std::make_unique(); // Build client request - SmallVector bufs; + wpi::util::SmallVector bufs; raw_uv_ostream os{bufs, kWriteAllocSize}; os << "GET " << uri << " HTTP/1.1\r\n"; @@ -272,34 +272,34 @@ void WebSocket::StartClient(std::string_view uri, std::string_view host, }); m_clientHandshake->parser.header.connect( [this](std::string_view name, std::string_view value) { - value = trim(value); - if (equals_lower(name, "upgrade")) { - if (!equals_lower(value, "websocket")) { + value = wpi::util::trim(value); + if (wpi::util::equals_lower(name, "upgrade")) { + if (!wpi::util::equals_lower(value, "websocket")) { return Terminate(1002, "invalid upgrade response value"); } m_clientHandshake->hasUpgrade = true; - } else if (equals_lower(name, "connection")) { - if (!equals_lower(value, "upgrade")) { + } else if (wpi::util::equals_lower(name, "connection")) { + if (!wpi::util::equals_lower(value, "upgrade")) { return Terminate(1002, "invalid connection response value"); } m_clientHandshake->hasConnection = true; - } else if (equals_lower(name, "sec-websocket-accept")) { + } else if (wpi::util::equals_lower(name, "sec-websocket-accept")) { // Check against expected response - SmallString<64> acceptBuf; - if (!equals(value, AcceptHash(m_clientHandshake->key, acceptBuf))) { + wpi::util::SmallString<64> acceptBuf; + if (!wpi::util::equals(value, AcceptHash(m_clientHandshake->key, acceptBuf))) { return Terminate(1002, "invalid accept key"); } m_clientHandshake->hasAccept = true; - } else if (equals_lower(name, "sec-websocket-extensions")) { + } else if (wpi::util::equals_lower(name, "sec-websocket-extensions")) { // No extensions are supported if (!value.empty()) { return Terminate(1010, "unsupported extension"); } - } else if (equals_lower(name, "sec-websocket-protocol")) { + } else if (wpi::util::equals_lower(name, "sec-websocket-protocol")) { // Make sure it was one of the provided protocols bool match = false; for (auto&& protocol : m_clientHandshake->protocols) { - if (equals_lower(value, protocol)) { + if (wpi::util::equals_lower(value, protocol)) { match = true; break; } @@ -340,7 +340,7 @@ void WebSocket::StartServer(std::string_view key, std::string_view version, m_protocol = protocol; // Build server response - SmallVector bufs; + wpi::util::SmallVector bufs; raw_uv_ostream os{bufs, kWriteAllocSize}; // Handle unsupported version @@ -364,7 +364,7 @@ void WebSocket::StartServer(std::string_view key, std::string_view version, os << "Connection: Upgrade\r\n"; // accept hash - SmallString<64> acceptBuf; + wpi::util::SmallString<64> acceptBuf; os << "Sec-WebSocket-Accept: " << AcceptHash(key, acceptBuf) << "\r\n"; if (!protocol.empty()) { @@ -387,7 +387,7 @@ void WebSocket::StartServer(std::string_view key, std::string_view version, } void WebSocket::SendClose(uint16_t code, std::string_view reason) { - SmallVector bufs; + wpi::util::SmallVector bufs; if (code != 1005) { raw_uv_ostream os{bufs, kWriteAllocSize}; const uint8_t codeMsb[] = {static_cast((code >> 8) & 0xff), @@ -641,7 +641,7 @@ void WebSocket::HandleIncoming(uv::Buffer& buf, size_t size) { code = (static_cast(m_controlPayload[0]) << 8) | static_cast(m_controlPayload[1]); reason = - drop_front({reinterpret_cast(m_controlPayload.data()), + wpi::util::drop_front({reinterpret_cast(m_controlPayload.data()), m_controlPayload.size()}, 2); } @@ -662,7 +662,7 @@ void WebSocket::HandleIncoming(uv::Buffer& buf, size_t size) { } // If the connection is open, send a Pong in response if (m_state == OPEN) { - SmallVector bufs; + wpi::util::SmallVector bufs; { raw_uv_ostream os{bufs, kWriteAllocSize}; os << m_controlPayload; @@ -710,35 +710,35 @@ void WebSocket::HandleIncoming(uv::Buffer& buf, size_t size) { static void VerboseDebug(const WebSocket::Frame& frame) { #ifdef WPINET_WEBSOCKET_VERBOSE_DEBUG if ((frame.opcode & 0x7f) == 0x01) { - SmallString<128> str; + wpi::util::SmallString<128> str; #ifdef WPINET_WEBSOCKET_VERBOSE_DEBUG_CONTENT for (auto&& d : frame.data) { str.append(std::string_view(d.base, d.len)); } #endif - wpi::print("WS SendText({})\n", str.str()); + wpi::util::print("WS SendText({})\n", str.str()); } else if ((frame.opcode & 0x7f) == 0x02) { - SmallString<128> str; + wpi::util::SmallString<128> str; #ifdef WPINET_WEBSOCKET_VERBOSE_DEBUG_CONTENT - raw_svector_ostream stros{str}; + wpi::util::raw_svector_ostream stros{str}; for (auto&& d : frame.data) { for (auto ch : d.data()) { stros << fmt::format("{:02x},", static_cast(ch) & 0xff); } } #endif - wpi::print("WS SendBinary({})\n", str.str()); + wpi::util::print("WS SendBinary({})\n", str.str()); } else { - SmallString<128> str; + wpi::util::SmallString<128> str; #ifdef WPINET_WEBSOCKET_VERBOSE_DEBUG_CONTENT - raw_svector_ostream stros{str}; + wpi::util::raw_svector_ostream stros{str}; for (auto&& d : frame.data) { for (auto ch : d.data()) { stros << fmt::format("{:02x},", static_cast(ch) & 0xff); } } #endif - wpi::print("WS SendOp({}, {})\n", frame.opcode, str.str()); + wpi::util::print("WS SendOp({}, {})\n", frame.opcode, str.str()); } #endif } @@ -855,7 +855,7 @@ void WebSocket::SendError( } else { err = UV_ESHUTDOWN; } - SmallVector bufs; + wpi::util::SmallVector bufs; for (auto&& frame : frames) { bufs.append(frame.data.begin(), frame.data.end()); } diff --git a/wpinet/src/main/native/cpp/WebSocketSerializer.cpp b/wpinet/src/main/native/cpp/WebSocketSerializer.cpp index dc1946ba69..0a79af4f36 100644 --- a/wpinet/src/main/native/cpp/WebSocketSerializer.cpp +++ b/wpinet/src/main/native/cpp/WebSocketSerializer.cpp @@ -6,14 +6,14 @@ #include -using namespace wpi::detail; +using namespace wpi::net::detail; static constexpr uint8_t kFlagMasking = 0x80; static constexpr size_t kWriteAllocSize = 4096; static std::span BuildHeader(std::span header, bool server, - const wpi::WebSocket::Frame& frame) { + const wpi::net::WebSocket::Frame& frame) { uint8_t* pHeader = header.data(); // opcode (includes FIN bit) diff --git a/wpinet/src/main/native/cpp/WebSocketSerializer.hpp b/wpinet/src/main/native/cpp/WebSocketSerializer.hpp index 2c8f7b1a4b..a6666d6046 100644 --- a/wpinet/src/main/native/cpp/WebSocketSerializer.hpp +++ b/wpinet/src/main/native/cpp/WebSocketSerializer.hpp @@ -14,7 +14,7 @@ #include "wpi/util/SmallVector.hpp" #include "wpi/util/SpanExtras.hpp" -namespace wpi::detail { +namespace wpi::net::detail { class SerializedFrames { public: @@ -41,8 +41,8 @@ class SerializedFrames { m_allocBufs.clear(); } - SmallVector m_allocBufs; - SmallVector m_bufs; + wpi::util::SmallVector m_allocBufs; + wpi::util::SmallVector m_bufs; size_t m_allocBufPos = 0; }; @@ -51,9 +51,9 @@ class WebSocketWriteReqBase { template int Continue(Stream& stream, std::shared_ptr req); - SmallVector m_userBufs; + wpi::util::SmallVector m_userBufs; SerializedFrames m_frames; - SmallVector m_continueFrameOffs; + wpi::util::SmallVector m_continueFrameOffs; size_t m_continueBufPos = 0; size_t m_continueFramePos = 0; }; @@ -94,7 +94,7 @@ int WebSocketWriteReqBase::Continue(Stream& stream, std::shared_ptr req) { assert(offIt != offEnd); // build a list of buffers to send as a normal write: - SmallVector writeBufs; + wpi::util::SmallVector writeBufs; auto bufIt = bufs.begin(); auto bufEnd = bufs.end(); @@ -105,7 +105,7 @@ int WebSocketWriteReqBase::Continue(Stream& stream, std::shared_ptr req) { } if (bufIt != bufs.begin() && pos != sentBytes) { writeBufs.emplace_back( - wpi::take_back((bufIt - 1)->bytes(), pos - sentBytes)); + wpi::util::take_back((bufIt - 1)->bytes(), pos - sentBytes)); } // continue through the last buffer of the last partial frame @@ -153,7 +153,7 @@ std::span TrySendFrames( // build buffers to send SerializedFrames sendFrames; - SmallVector frameOffs; + wpi::util::SmallVector frameOffs; int numBytes = 0; while (frameIt != frameEnd) { numBytes += sendFrames.AddFrame(*frameIt++, server); @@ -173,7 +173,7 @@ std::span TrySendFrames( if (sentBytes == 0) { // we haven't started a frame yet; clean up any bufs that have actually // sent, and return unsent frames - SmallVector bufs; + wpi::util::SmallVector bufs; for (auto it = frames.begin(); it != frameStart; ++it) { bufs.append(it->data.begin(), it->data.end()); } @@ -187,7 +187,7 @@ std::span TrySendFrames( #endif } else if (sentBytes < 0) { // error - SmallVector bufs; + wpi::util::SmallVector bufs; for (auto&& frame : frames) { bufs.append(frame.data.begin(), frame.data.end()); } @@ -208,7 +208,7 @@ std::span TrySendFrames( if (offIt != offEnd && *offIt == sentBytes && isFin) { // we finished at a normal FIN frame boundary; no need for a Write() ++frameStart; - SmallVector bufs; + wpi::util::SmallVector bufs; for (auto it = frames.begin(); it != frameStart; ++it) { bufs.append(it->data.begin(), it->data.end()); } @@ -223,7 +223,7 @@ std::span TrySendFrames( } // build a list of buffers to send as a normal write: - SmallVector writeBufs; + wpi::util::SmallVector writeBufs; auto bufIt = sendFrames.m_bufs.begin(); auto bufEnd = sendFrames.m_bufs.end(); @@ -234,7 +234,7 @@ std::span TrySendFrames( } if (bufIt != sendFrames.m_bufs.begin() && pos != sentBytes) { writeBufs.emplace_back( - wpi::take_back((bufIt - 1)->bytes(), pos - sentBytes)); + wpi::util::take_back((bufIt - 1)->bytes(), pos - sentBytes)); } // continue through the last buffer of the last partial frame @@ -293,7 +293,7 @@ std::span TrySendFrames( } // nothing left to send - SmallVector bufs; + wpi::util::SmallVector bufs; for (auto&& frame : frames) { bufs.append(frame.data.begin(), frame.data.end()); } @@ -301,4 +301,4 @@ std::span TrySendFrames( return {}; } -} // namespace wpi::detail +} // namespace wpi::net::detail diff --git a/wpinet/src/main/native/cpp/WebSocketServer.cpp b/wpinet/src/main/native/cpp/WebSocketServer.cpp index 57dd89e856..d35c11ea7e 100644 --- a/wpinet/src/main/native/cpp/WebSocketServer.cpp +++ b/wpinet/src/main/native/cpp/WebSocketServer.cpp @@ -15,24 +15,24 @@ #include "wpi/util/fmt/raw_ostream.hpp" #include "wpi/util/print.hpp" -using namespace wpi; +using namespace wpi::net; WebSocketServerHelper::WebSocketServerHelper(HttpParser& req) { req.header.connect([this](std::string_view name, std::string_view value) { - if (equals_lower(name, "host")) { + if (wpi::util::equals_lower(name, "host")) { m_gotHost = true; - } else if (equals_lower(name, "upgrade")) { - if (equals_lower(value, "websocket")) { + } else if (wpi::util::equals_lower(name, "upgrade")) { + if (wpi::util::equals_lower(value, "websocket")) { m_websocket = true; } - } else if (equals_lower(name, "sec-websocket-key")) { + } else if (wpi::util::equals_lower(name, "sec-websocket-key")) { m_key = value; - } else if (equals_lower(name, "sec-websocket-version")) { + } else if (wpi::util::equals_lower(name, "sec-websocket-version")) { m_version = value; - } else if (equals_lower(name, "sec-websocket-protocol")) { + } else if (wpi::util::equals_lower(name, "sec-websocket-protocol")) { // Protocols are comma delimited, repeated headers add to list - split(value, ',', -1, false, [&](auto protocol) { - protocol = trim(protocol); + wpi::util::split(value, ',', -1, false, [&](auto protocol) { + protocol = wpi::util::trim(protocol); if (!protocol.empty()) { m_protocols.emplace_back(protocol); } @@ -85,7 +85,7 @@ WebSocketServer::WebSocketServer(uv::Stream& stream, m_options{std::move(options)} { // Header handling m_req.header.connect([this](std::string_view name, std::string_view value) { - if (equals_lower(name, "host")) { + if (wpi::util::equals_lower(name, "host")) { if (m_options.checkHost) { if (!m_options.checkHost(value)) { Abort(401, "Unrecognized Host"); @@ -167,11 +167,11 @@ void WebSocketServer::Abort(uint16_t code, std::string_view reason) { m_aborted = true; // Build response - SmallVector bufs; + wpi::util::SmallVector bufs; raw_uv_ostream os{bufs, 1024}; // Handle unsupported version - wpi::print(os, "HTTP/1.1 {} {}\r\n", code, reason); + wpi::util::print(os, "HTTP/1.1 {} {}\r\n", code, reason); if (code == 426) { os << "Upgrade: WebSocket\r\n"; } diff --git a/wpinet/src/main/native/cpp/hostname.cpp b/wpinet/src/main/native/cpp/hostname.cpp index 5483b0467b..34bf6c6c84 100644 --- a/wpinet/src/main/native/cpp/hostname.cpp +++ b/wpinet/src/main/native/cpp/hostname.cpp @@ -11,7 +11,7 @@ #include "uv.h" #include "wpi/util/SmallVector.hpp" -namespace wpi { +namespace wpi::net { std::string GetHostname() { std::string rv; @@ -33,8 +33,8 @@ std::string GetHostname() { return rv; } -std::string_view GetHostname(SmallVectorImpl& name) { - // Use a tmp array to not require the SmallVector to be too large. +std::string_view GetHostname(wpi::util::SmallVectorImpl& name) { + // Use a tmp array to not require the wpi::util::SmallVector to be too large. char tmpName[256]; size_t size = sizeof(tmpName); @@ -54,4 +54,4 @@ std::string_view GetHostname(SmallVectorImpl& name) { return {name.data(), size}; } -} // namespace wpi +} // namespace wpi::net diff --git a/wpinet/src/main/native/cpp/http_parser.cpp b/wpinet/src/main/native/cpp/http_parser.cpp index d9e12a70da..3ca7bdeee8 100644 --- a/wpinet/src/main/native/cpp/http_parser.cpp +++ b/wpinet/src/main/native/cpp/http_parser.cpp @@ -172,7 +172,7 @@ do { \ #define KEEP_ALIVE "keep-alive" #define CLOSE "close" -namespace wpi { +namespace wpi::net { static const char *method_strings[] = @@ -2478,4 +2478,4 @@ http_parser_version(void) { HTTP_PARSER_VERSION_PATCH * 0x00001; } -} // namespace wpi +} // namespace wpi::net diff --git a/wpinet/src/main/native/cpp/jni/WPINetJNI.cpp b/wpinet/src/main/native/cpp/jni/WPINetJNI.cpp index 32d16f170b..0d93f864d1 100644 --- a/wpinet/src/main/native/cpp/jni/WPINetJNI.cpp +++ b/wpinet/src/main/native/cpp/jni/WPINetJNI.cpp @@ -17,7 +17,7 @@ #include "wpi/net/WebServer.hpp" #include "wpi/util/jni_util.hpp" -using namespace wpi::java; +using namespace wpi::util::java; static JClass serviceDataCls; static JGlobal serviceDataEmptyArray; @@ -63,7 +63,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_net_WPINetJNI_addPortForwarder (JNIEnv* env, jclass, jint port, jstring remoteHost, jint remotePort) { - wpi::PortForwarder::GetInstance().Add(static_cast(port), + wpi::net::PortForwarder::GetInstance().Add(static_cast(port), JStringRef{env, remoteHost}.str(), static_cast(remotePort)); } @@ -77,7 +77,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_net_WPINetJNI_removePortForwarder (JNIEnv* env, jclass, jint port) { - wpi::PortForwarder::GetInstance().Remove(port); + wpi::net::PortForwarder::GetInstance().Remove(port); } /* @@ -89,7 +89,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_net_WPINetJNI_startWebServer (JNIEnv* env, jclass, jint port, jstring path) { - wpi::WebServer::GetInstance().Start(static_cast(port), + wpi::net::WebServer::GetInstance().Start(static_cast(port), JStringRef{env, path}.str()); } @@ -102,7 +102,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_net_WPINetJNI_stopWebServer (JNIEnv* env, jclass, jint port) { - wpi::WebServer::GetInstance().Stop(port); + wpi::net::WebServer::GetInstance().Stop(port); } /* @@ -115,13 +115,13 @@ Java_org_wpilib_net_WPINetJNI_createMulticastServiceAnnouncer (JNIEnv* env, jclass, jstring serviceName, jstring serviceType, jint port, jobjectArray keys, jobjectArray values) { - auto& manager = wpi::GetMulticastManager(); + auto& manager = wpi::net::GetMulticastManager(); std::scoped_lock lock{manager.mutex}; JStringRef serviceNameRef{env, serviceName}; JStringRef serviceTypeRef{env, serviceType}; - wpi::SmallVector, 8> txtVec; + wpi::util::SmallVector, 8> txtVec; if (keys != nullptr && values != nullptr) { size_t keysLen = env->GetArrayLength(keys); @@ -138,7 +138,7 @@ Java_org_wpilib_net_WPINetJNI_createMulticastServiceAnnouncer } } - auto announcer = std::make_unique( + auto announcer = std::make_unique( serviceNameRef.str(), serviceTypeRef.str(), port, txtVec); size_t index = manager.handleIds.emplace_back(1); @@ -157,7 +157,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_net_WPINetJNI_freeMulticastServiceAnnouncer (JNIEnv* env, jclass, jint handle) { - auto& manager = wpi::GetMulticastManager(); + auto& manager = wpi::net::GetMulticastManager(); std::scoped_lock lock{manager.mutex}; manager.announcers[handle] = nullptr; manager.handleIds.erase(handle); @@ -172,7 +172,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_net_WPINetJNI_startMulticastServiceAnnouncer (JNIEnv* env, jclass, jint handle) { - auto& manager = wpi::GetMulticastManager(); + auto& manager = wpi::net::GetMulticastManager(); std::scoped_lock lock{manager.mutex}; auto& announcer = manager.announcers[handle]; announcer->Start(); @@ -187,7 +187,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_net_WPINetJNI_stopMulticastServiceAnnouncer (JNIEnv* env, jclass, jint handle) { - auto& manager = wpi::GetMulticastManager(); + auto& manager = wpi::net::GetMulticastManager(); std::scoped_lock lock{manager.mutex}; auto& announcer = manager.announcers[handle]; announcer->Stop(); @@ -202,7 +202,7 @@ JNIEXPORT jboolean JNICALL Java_org_wpilib_net_WPINetJNI_getMulticastServiceAnnouncerHasImplementation (JNIEnv* env, jclass, jint handle) { - auto& manager = wpi::GetMulticastManager(); + auto& manager = wpi::net::GetMulticastManager(); std::scoped_lock lock{manager.mutex}; auto& announcer = manager.announcers[handle]; return announcer->HasImplementation(); @@ -217,12 +217,12 @@ JNIEXPORT jint JNICALL Java_org_wpilib_net_WPINetJNI_createMulticastServiceResolver (JNIEnv* env, jclass, jstring serviceType) { - auto& manager = wpi::GetMulticastManager(); + auto& manager = wpi::net::GetMulticastManager(); std::scoped_lock lock{manager.mutex}; JStringRef serviceTypeRef{env, serviceType}; auto resolver = - std::make_unique(serviceTypeRef.str()); + std::make_unique(serviceTypeRef.str()); size_t index = manager.handleIds.emplace_back(2); @@ -240,7 +240,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_net_WPINetJNI_freeMulticastServiceResolver (JNIEnv* env, jclass, jint handle) { - auto& manager = wpi::GetMulticastManager(); + auto& manager = wpi::net::GetMulticastManager(); std::scoped_lock lock{manager.mutex}; manager.resolvers[handle] = nullptr; manager.handleIds.erase(handle); @@ -255,7 +255,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_net_WPINetJNI_startMulticastServiceResolver (JNIEnv* env, jclass, jint handle) { - auto& manager = wpi::GetMulticastManager(); + auto& manager = wpi::net::GetMulticastManager(); std::scoped_lock lock{manager.mutex}; auto& resolver = manager.resolvers[handle]; resolver->Start(); @@ -270,7 +270,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_net_WPINetJNI_stopMulticastServiceResolver (JNIEnv* env, jclass, jint handle) { - auto& manager = wpi::GetMulticastManager(); + auto& manager = wpi::net::GetMulticastManager(); std::scoped_lock lock{manager.mutex}; auto& resolver = manager.resolvers[handle]; resolver->Stop(); @@ -285,7 +285,7 @@ JNIEXPORT jboolean JNICALL Java_org_wpilib_net_WPINetJNI_getMulticastServiceResolverHasImplementation (JNIEnv* env, jclass, jint handle) { - auto& manager = wpi::GetMulticastManager(); + auto& manager = wpi::net::GetMulticastManager(); std::scoped_lock lock{manager.mutex}; auto& resolver = manager.resolvers[handle]; return resolver->HasImplementation(); @@ -300,7 +300,7 @@ JNIEXPORT jint JNICALL Java_org_wpilib_net_WPINetJNI_getMulticastServiceResolverEventHandle (JNIEnv* env, jclass, jint handle) { - auto& manager = wpi::GetMulticastManager(); + auto& manager = wpi::net::GetMulticastManager(); std::scoped_lock lock{manager.mutex}; auto& resolver = manager.resolvers[handle]; return resolver->GetEventHandle(); @@ -319,8 +319,8 @@ Java_org_wpilib_net_WPINetJNI_getMulticastServiceResolverData env->GetMethodID(serviceDataCls, "", "(JILjava/lang/String;Ljava/lang/String;[Ljava/lang/" "String;[Ljava/lang/String;)V"); - auto& manager = wpi::GetMulticastManager(); - std::vector allData; + auto& manager = wpi::net::GetMulticastManager(); + std::vector allData; { std::scoped_lock lock{manager.mutex}; auto& resolver = manager.resolvers[handle]; @@ -337,8 +337,8 @@ Java_org_wpilib_net_WPINetJNI_getMulticastServiceResolverData JLocal serviceName{env, MakeJString(env, data.serviceName)}; JLocal hostName{env, MakeJString(env, data.hostName)}; - wpi::SmallVector keysRef; - wpi::SmallVector valuesRef; + wpi::util::SmallVector keysRef; + wpi::util::SmallVector valuesRef; size_t index = 0; for (auto&& txt : data.txt) { diff --git a/wpinet/src/main/native/cpp/raw_socket_istream.cpp b/wpinet/src/main/native/cpp/raw_socket_istream.cpp index e687aefcb6..3ef1290f39 100644 --- a/wpinet/src/main/native/cpp/raw_socket_istream.cpp +++ b/wpinet/src/main/native/cpp/raw_socket_istream.cpp @@ -6,7 +6,7 @@ #include "wpi/net/NetworkStream.hpp" -using namespace wpi; +using namespace wpi::net; void raw_socket_istream::read_impl(void* data, size_t len) { char* cdata = static_cast(data); diff --git a/wpinet/src/main/native/cpp/raw_socket_ostream.cpp b/wpinet/src/main/native/cpp/raw_socket_ostream.cpp index ae0fe3d2c0..53d017de27 100644 --- a/wpinet/src/main/native/cpp/raw_socket_ostream.cpp +++ b/wpinet/src/main/native/cpp/raw_socket_ostream.cpp @@ -6,7 +6,7 @@ #include "wpi/net/NetworkStream.hpp" -using namespace wpi; +using namespace wpi::net; raw_socket_ostream::~raw_socket_ostream() { flush(); diff --git a/wpinet/src/main/native/cpp/raw_uv_ostream.cpp b/wpinet/src/main/native/cpp/raw_uv_ostream.cpp index facb9e2adb..f1e300f2f9 100644 --- a/wpinet/src/main/native/cpp/raw_uv_ostream.cpp +++ b/wpinet/src/main/native/cpp/raw_uv_ostream.cpp @@ -6,7 +6,7 @@ #include -using namespace wpi; +using namespace wpi::net; void raw_uv_ostream::write_impl(const char* data, size_t len) { while (len > 0) { diff --git a/wpinet/src/main/native/cpp/uv/Async.cpp b/wpinet/src/main/native/cpp/uv/Async.cpp index bd444bbfa1..acc2953ef0 100644 --- a/wpinet/src/main/native/cpp/uv/Async.cpp +++ b/wpinet/src/main/native/cpp/uv/Async.cpp @@ -8,7 +8,7 @@ #include "wpi/net/uv/Loop.hpp" -namespace wpi::uv { +namespace wpi::net::uv { Async<>::~Async() noexcept { if (auto loop = m_loop.lock()) { @@ -35,4 +35,4 @@ std::shared_ptr> Async<>::Create(const std::shared_ptr& loop) { return h; } -} // namespace wpi::uv +} // namespace wpi::net::uv diff --git a/wpinet/src/main/native/cpp/uv/Check.cpp b/wpinet/src/main/native/cpp/uv/Check.cpp index 0a8dbf415e..ea21513d47 100644 --- a/wpinet/src/main/native/cpp/uv/Check.cpp +++ b/wpinet/src/main/native/cpp/uv/Check.cpp @@ -8,7 +8,7 @@ #include "wpi/net/uv/Loop.hpp" -namespace wpi::uv { +namespace wpi::net::uv { std::shared_ptr Check::Create(Loop& loop) { if (loop.IsClosing()) { @@ -34,4 +34,4 @@ void Check::Start() { }); } -} // namespace wpi::uv +} // namespace wpi::net::uv diff --git a/wpinet/src/main/native/cpp/uv/FsEvent.cpp b/wpinet/src/main/native/cpp/uv/FsEvent.cpp index 9720a5e94b..8f6657eaeb 100644 --- a/wpinet/src/main/native/cpp/uv/FsEvent.cpp +++ b/wpinet/src/main/native/cpp/uv/FsEvent.cpp @@ -11,7 +11,7 @@ #include "wpi/net/uv/Loop.hpp" #include "wpi/util/SmallString.hpp" -namespace wpi::uv { +namespace wpi::net::uv { std::shared_ptr FsEvent::Create(Loop& loop) { if (loop.IsClosing()) { @@ -28,7 +28,7 @@ std::shared_ptr FsEvent::Create(Loop& loop) { } void FsEvent::Start(std::string_view path, unsigned int flags) { - SmallString<128> pathBuf{path}; + wpi::util::SmallString<128> pathBuf{path}; Invoke( &uv_fs_event_start, GetRaw(), [](uv_fs_event_t* handle, const char* filename, int events, int status) { @@ -65,4 +65,4 @@ std::string FsEvent::GetPath() { return std::string{}; } -} // namespace wpi::uv +} // namespace wpi::net::uv diff --git a/wpinet/src/main/native/cpp/uv/GetAddrInfo.cpp b/wpinet/src/main/native/cpp/uv/GetAddrInfo.cpp index 002d970c44..588ab48e35 100644 --- a/wpinet/src/main/native/cpp/uv/GetAddrInfo.cpp +++ b/wpinet/src/main/native/cpp/uv/GetAddrInfo.cpp @@ -11,7 +11,7 @@ #include "wpi/net/uv/Loop.hpp" #include "wpi/util/SmallString.hpp" -namespace wpi::uv { +namespace wpi::net::uv { GetAddrInfoReq::GetAddrInfoReq() { error = [this](Error err) { GetLoop().error(err); }; @@ -23,8 +23,8 @@ void GetAddrInfo(Loop& loop, const std::shared_ptr& req, if (loop.IsClosing()) { return; } - SmallString<128> nodeStr{node}; - SmallString<128> serviceStr{service}; + wpi::util::SmallString<128> nodeStr{node}; + wpi::util::SmallString<128> serviceStr{service}; int err = uv_getaddrinfo( loop.GetRaw(), req->GetRaw(), [](uv_getaddrinfo_t* req, int status, addrinfo* res) { @@ -55,4 +55,4 @@ void GetAddrInfo(Loop& loop, std::function callback, GetAddrInfo(loop, req, node, service, hints); } -} // namespace wpi::uv +} // namespace wpi::net::uv diff --git a/wpinet/src/main/native/cpp/uv/GetNameInfo.cpp b/wpinet/src/main/native/cpp/uv/GetNameInfo.cpp index d123e509e1..91d9998b7c 100644 --- a/wpinet/src/main/native/cpp/uv/GetNameInfo.cpp +++ b/wpinet/src/main/native/cpp/uv/GetNameInfo.cpp @@ -11,7 +11,7 @@ #include "wpi/net/uv/Loop.hpp" #include "wpi/net/uv/util.hpp" -namespace wpi::uv { +namespace wpi::net::uv { GetNameInfoReq::GetNameInfoReq() { error = [this](Error err) { GetLoop().error(err); }; @@ -98,4 +98,4 @@ void GetNameInfo6(Loop& loop, } } -} // namespace wpi::uv +} // namespace wpi::net::uv diff --git a/wpinet/src/main/native/cpp/uv/Handle.cpp b/wpinet/src/main/native/cpp/uv/Handle.cpp index 4b20a20819..b32b9c7612 100644 --- a/wpinet/src/main/native/cpp/uv/Handle.cpp +++ b/wpinet/src/main/native/cpp/uv/Handle.cpp @@ -4,7 +4,7 @@ #include "wpi/net/uv/Handle.hpp" -using namespace wpi::uv; +using namespace wpi::net::uv; Handle::~Handle() noexcept { if (!m_closed && m_uv_handle->type != UV_UNKNOWN_HANDLE) { diff --git a/wpinet/src/main/native/cpp/uv/Idle.cpp b/wpinet/src/main/native/cpp/uv/Idle.cpp index 027145f0b2..3a409f090e 100644 --- a/wpinet/src/main/native/cpp/uv/Idle.cpp +++ b/wpinet/src/main/native/cpp/uv/Idle.cpp @@ -8,7 +8,7 @@ #include "wpi/net/uv/Loop.hpp" -namespace wpi::uv { +namespace wpi::net::uv { std::shared_ptr Idle::Create(Loop& loop) { if (loop.IsClosing()) { @@ -34,4 +34,4 @@ void Idle::Start() { }); } -} // namespace wpi::uv +} // namespace wpi::net::uv diff --git a/wpinet/src/main/native/cpp/uv/Loop.cpp b/wpinet/src/main/native/cpp/uv/Loop.cpp index 0e68e2704e..111fd40f86 100644 --- a/wpinet/src/main/native/cpp/uv/Loop.cpp +++ b/wpinet/src/main/native/cpp/uv/Loop.cpp @@ -6,7 +6,7 @@ #include -using namespace wpi::uv; +using namespace wpi::net::uv; Loop::Loop(const private_init&) noexcept { #ifndef _WIN32 @@ -53,12 +53,12 @@ void Loop::Close() { } } -void Loop::Walk(function_ref callback) { +void Loop::Walk(wpi::util::function_ref callback) { uv_walk( m_loop, [](uv_handle_t* handle, void* func) { auto& h = *static_cast(handle->data); - auto& f = *static_cast*>(func); + auto& f = *static_cast*>(func); f(h); }, &callback); diff --git a/wpinet/src/main/native/cpp/uv/NameToAddr.cpp b/wpinet/src/main/native/cpp/uv/NameToAddr.cpp index 304e3eca5e..faa0eee2f3 100644 --- a/wpinet/src/main/native/cpp/uv/NameToAddr.cpp +++ b/wpinet/src/main/native/cpp/uv/NameToAddr.cpp @@ -8,7 +8,7 @@ #include "wpi/util/SmallString.hpp" -namespace wpi::uv { +namespace wpi::net::uv { int NameToAddr(std::string_view ip, unsigned int port, sockaddr_in* addr) { if (ip.empty()) { @@ -18,7 +18,7 @@ int NameToAddr(std::string_view ip, unsigned int port, sockaddr_in* addr) { addr->sin_port = htons(port); return 0; } else { - SmallString<128> ipBuf{ip}; + wpi::util::SmallString<128> ipBuf{ip}; return uv_ip4_addr(ipBuf.c_str(), port, addr); } } @@ -31,7 +31,7 @@ int NameToAddr(std::string_view ip, unsigned int port, sockaddr_in6* addr) { addr->sin6_port = htons(port); return 0; } else { - SmallString<128> ipBuf{ip}; + wpi::util::SmallString<128> ipBuf{ip}; return uv_ip6_addr(ipBuf.c_str(), port, addr); } } @@ -41,7 +41,7 @@ int NameToAddr(std::string_view ip, in_addr* addr) { addr->s_addr = INADDR_ANY; return 0; } else { - SmallString<128> ipBuf{ip}; + wpi::util::SmallString<128> ipBuf{ip}; return uv_inet_pton(AF_INET, ipBuf.c_str(), addr); } } @@ -51,9 +51,9 @@ int NameToAddr(std::string_view ip, in6_addr* addr) { *addr = in6addr_any; return 0; } else { - SmallString<128> ipBuf{ip}; + wpi::util::SmallString<128> ipBuf{ip}; return uv_inet_pton(AF_INET6, ipBuf.c_str(), addr); } } -} // namespace wpi::uv +} // namespace wpi::net::uv diff --git a/wpinet/src/main/native/cpp/uv/NetworkStream.cpp b/wpinet/src/main/native/cpp/uv/NetworkStream.cpp index 1e4c217fa3..d3c989f1f1 100644 --- a/wpinet/src/main/native/cpp/uv/NetworkStream.cpp +++ b/wpinet/src/main/native/cpp/uv/NetworkStream.cpp @@ -7,7 +7,7 @@ #include #include -namespace wpi::uv { +namespace wpi::net::uv { ConnectReq::ConnectReq() { error = [this](Error err) { GetStream().error(err); }; @@ -33,4 +33,4 @@ void NetworkStream::Listen(std::function callback, int backlog) { Listen(backlog); } -} // namespace wpi::uv +} // namespace wpi::net::uv diff --git a/wpinet/src/main/native/cpp/uv/Pipe.cpp b/wpinet/src/main/native/cpp/uv/Pipe.cpp index 9f809a5c4d..03f4a6a983 100644 --- a/wpinet/src/main/native/cpp/uv/Pipe.cpp +++ b/wpinet/src/main/native/cpp/uv/Pipe.cpp @@ -12,7 +12,7 @@ #include "wpi/util/SmallString.hpp" -namespace wpi::uv { +namespace wpi::net::uv { std::shared_ptr Pipe::Create(Loop& loop, bool ipc) { if (loop.IsClosing()) { @@ -70,7 +70,7 @@ Pipe* Pipe::DoAccept() { } void Pipe::Bind(std::string_view name) { - SmallString<128> nameBuf{name}; + wpi::util::SmallString<128> nameBuf{name}; Invoke(&uv_pipe_bind, GetRaw(), nameBuf.c_str()); } @@ -79,7 +79,7 @@ void Pipe::Connect(std::string_view name, if (IsLoopClosing()) { return; } - SmallString<128> nameBuf{name}; + wpi::util::SmallString<128> nameBuf{name}; uv_pipe_connect(req->GetRaw(), GetRaw(), nameBuf.c_str(), [](uv_connect_t* req, int status) { auto& h = *static_cast(req->data); @@ -145,4 +145,4 @@ std::string Pipe::GetPeer() { return std::string{}; } -} // namespace wpi::uv +} // namespace wpi::net::uv diff --git a/wpinet/src/main/native/cpp/uv/Poll.cpp b/wpinet/src/main/native/cpp/uv/Poll.cpp index 748fc4e434..bee073537f 100644 --- a/wpinet/src/main/native/cpp/uv/Poll.cpp +++ b/wpinet/src/main/native/cpp/uv/Poll.cpp @@ -10,7 +10,7 @@ #include "wpi/net/uv/Loop.hpp" -namespace wpi::uv { +namespace wpi::net::uv { std::shared_ptr Poll::Create(Loop& loop, int fd) { if (loop.IsClosing()) { @@ -105,4 +105,4 @@ void Poll::Start(int events) { }); } -} // namespace wpi::uv +} // namespace wpi::net::uv diff --git a/wpinet/src/main/native/cpp/uv/Prepare.cpp b/wpinet/src/main/native/cpp/uv/Prepare.cpp index f1849a2bd6..91d5a98ae9 100644 --- a/wpinet/src/main/native/cpp/uv/Prepare.cpp +++ b/wpinet/src/main/native/cpp/uv/Prepare.cpp @@ -8,7 +8,7 @@ #include "wpi/net/uv/Loop.hpp" -namespace wpi::uv { +namespace wpi::net::uv { std::shared_ptr Prepare::Create(Loop& loop) { if (loop.IsClosing()) { @@ -34,4 +34,4 @@ void Prepare::Start() { }); } -} // namespace wpi::uv +} // namespace wpi::net::uv diff --git a/wpinet/src/main/native/cpp/uv/Process.cpp b/wpinet/src/main/native/cpp/uv/Process.cpp index d067491885..26242a33d9 100644 --- a/wpinet/src/main/native/cpp/uv/Process.cpp +++ b/wpinet/src/main/native/cpp/uv/Process.cpp @@ -10,7 +10,7 @@ #include "wpi/net/uv/Pipe.hpp" #include "wpi/util/SmallString.hpp" -namespace wpi::uv { +namespace wpi::net::uv { std::shared_ptr Process::SpawnArray(Loop& loop, std::string_view file, std::span options) { @@ -26,22 +26,22 @@ std::shared_ptr Process::SpawnArray(Loop& loop, std::string_view file, h.exited(status, signal); }; - SmallString<128> fileBuf{file}; + wpi::util::SmallString<128> fileBuf{file}; coptions.file = fileBuf.c_str(); coptions.cwd = nullptr; coptions.flags = 0; coptions.uid = 0; coptions.gid = 0; - SmallVector argsBuf; - SmallVector envBuf; + wpi::util::SmallVector argsBuf; + wpi::util::SmallVector envBuf; struct StdioContainer : public uv_stdio_container_t { StdioContainer() { flags = UV_IGNORE; data.fd = 0; } }; - SmallVector stdioBuf; + wpi::util::SmallVector stdioBuf; for (auto&& o : options) { switch (o.m_type) { @@ -136,4 +136,4 @@ std::shared_ptr Process::SpawnArray(Loop& loop, std::string_view file, return h; } -} // namespace wpi::uv +} // namespace wpi::net::uv diff --git a/wpinet/src/main/native/cpp/uv/Signal.cpp b/wpinet/src/main/native/cpp/uv/Signal.cpp index bb5fbae7a6..82b562b650 100644 --- a/wpinet/src/main/native/cpp/uv/Signal.cpp +++ b/wpinet/src/main/native/cpp/uv/Signal.cpp @@ -8,7 +8,7 @@ #include "wpi/net/uv/Loop.hpp" -namespace wpi::uv { +namespace wpi::net::uv { std::shared_ptr Signal::Create(Loop& loop) { if (loop.IsClosing()) { @@ -37,4 +37,4 @@ void Signal::Start(int signum) { signum); } -} // namespace wpi::uv +} // namespace wpi::net::uv diff --git a/wpinet/src/main/native/cpp/uv/Stream.cpp b/wpinet/src/main/native/cpp/uv/Stream.cpp index e018bd8afd..6f90a651a2 100644 --- a/wpinet/src/main/native/cpp/uv/Stream.cpp +++ b/wpinet/src/main/native/cpp/uv/Stream.cpp @@ -13,8 +13,8 @@ #include "wpi/util/SmallVector.hpp" #include "wpi/util/raw_ostream.hpp" -using namespace wpi; -using namespace wpi::uv; +using namespace wpi::net; +using namespace wpi::net::uv; namespace { class CallbackWriteReq : public WriteReq { @@ -27,11 +27,11 @@ class CallbackWriteReq : public WriteReq { } private: - SmallVector m_bufs; + wpi::util::SmallVector m_bufs; }; } // namespace -namespace wpi::uv { +namespace wpi::net::uv { ShutdownReq::ShutdownReq() { error = [this](Error err) { GetStream().error(err); }; @@ -95,7 +95,7 @@ void Stream::StartRead() { static std::string BufsToString(std::span bufs) { std::string str; - wpi::raw_string_ostream stros{str}; + wpi::util::raw_string_ostream stros{str}; size_t count = 0; for (auto buf : bufs) { for (auto ch : buf.bytes()) { @@ -177,4 +177,4 @@ int Stream::TryWrite2(std::span bufs, Stream& send) { return val; } -} // namespace wpi::uv +} // namespace wpi::net::uv diff --git a/wpinet/src/main/native/cpp/uv/Tcp.cpp b/wpinet/src/main/native/cpp/uv/Tcp.cpp index 1f13080247..9c2ce8acc6 100644 --- a/wpinet/src/main/native/cpp/uv/Tcp.cpp +++ b/wpinet/src/main/native/cpp/uv/Tcp.cpp @@ -11,7 +11,7 @@ #include "wpi/net/uv/util.hpp" -namespace wpi::uv { +namespace wpi::net::uv { std::shared_ptr Tcp::Create(Loop& loop, unsigned int flags) { if (loop.IsClosing()) { @@ -190,4 +190,4 @@ void Tcp::CloseReset() { } } -} // namespace wpi::uv +} // namespace wpi::net::uv diff --git a/wpinet/src/main/native/cpp/uv/Timer.cpp b/wpinet/src/main/native/cpp/uv/Timer.cpp index 7f7d326cbf..b90a039535 100644 --- a/wpinet/src/main/native/cpp/uv/Timer.cpp +++ b/wpinet/src/main/native/cpp/uv/Timer.cpp @@ -10,7 +10,7 @@ #include "wpi/net/uv/Loop.hpp" -namespace wpi::uv { +namespace wpi::net::uv { std::shared_ptr Timer::Create(Loop& loop) { if (loop.IsClosing()) { @@ -51,4 +51,4 @@ void Timer::Start(Time timeout, Time repeat) { timeout.count(), repeat.count()); } -} // namespace wpi::uv +} // namespace wpi::net::uv diff --git a/wpinet/src/main/native/cpp/uv/Tty.cpp b/wpinet/src/main/native/cpp/uv/Tty.cpp index 5337fa14a8..34e4c4b1f9 100644 --- a/wpinet/src/main/native/cpp/uv/Tty.cpp +++ b/wpinet/src/main/native/cpp/uv/Tty.cpp @@ -8,7 +8,7 @@ #include "wpi/net/uv/Loop.hpp" -namespace wpi::uv { +namespace wpi::net::uv { std::shared_ptr Tty::Create(Loop& loop, uv_file fd, bool readable) { if (loop.IsClosing()) { @@ -24,4 +24,4 @@ std::shared_ptr Tty::Create(Loop& loop, uv_file fd, bool readable) { return h; } -} // namespace wpi::uv +} // namespace wpi::net::uv diff --git a/wpinet/src/main/native/cpp/uv/Udp.cpp b/wpinet/src/main/native/cpp/uv/Udp.cpp index 0ff3880dcb..1e14d5a801 100644 --- a/wpinet/src/main/native/cpp/uv/Udp.cpp +++ b/wpinet/src/main/native/cpp/uv/Udp.cpp @@ -15,8 +15,8 @@ namespace { -using namespace wpi; -using namespace wpi::uv; +using namespace wpi::net; +using namespace wpi::net::uv; class CallbackUdpSendReq : public UdpSendReq { public: @@ -28,12 +28,12 @@ class CallbackUdpSendReq : public UdpSendReq { } private: - SmallVector m_bufs; + wpi::util::SmallVector m_bufs; }; } // namespace -namespace wpi::uv { +namespace wpi::net::uv { UdpSendReq::UdpSendReq() { error = [this](Error err) { GetUdp().error(err); }; @@ -116,8 +116,8 @@ sockaddr_storage Udp::GetSock() { void Udp::SetMembership(std::string_view multicastAddr, std::string_view interfaceAddr, uv_membership membership) { - SmallString<128> multicastAddrBuf{multicastAddr}; - SmallString<128> interfaceAddrBuf{interfaceAddr}; + wpi::util::SmallString<128> multicastAddrBuf{multicastAddr}; + wpi::util::SmallString<128> interfaceAddrBuf{interfaceAddr}; Invoke(&uv_udp_set_membership, GetRaw(), multicastAddrBuf.c_str(), interfaceAddrBuf.c_str(), membership); } @@ -126,15 +126,15 @@ void Udp::SetSourceMembership(std::string_view multicastAddr, std::string_view interfaceAddr, std::string_view sourceAddr, uv_membership membership) { - SmallString<128> multicastAddrBuf{multicastAddr}; - SmallString<128> interfaceAddrBuf{interfaceAddr}; - SmallString<128> sourceAddrBuf{sourceAddr}; + wpi::util::SmallString<128> multicastAddrBuf{multicastAddr}; + wpi::util::SmallString<128> interfaceAddrBuf{interfaceAddr}; + wpi::util::SmallString<128> sourceAddrBuf{sourceAddr}; Invoke(&uv_udp_set_source_membership, GetRaw(), multicastAddrBuf.c_str(), interfaceAddrBuf.c_str(), sourceAddrBuf.c_str(), membership); } void Udp::SetMulticastInterface(std::string_view interfaceAddr) { - SmallString<128> interfaceAddrBuf{interfaceAddr}; + wpi::util::SmallString<128> interfaceAddrBuf{interfaceAddr}; Invoke(&uv_udp_set_multicast_interface, GetRaw(), interfaceAddrBuf.c_str()); } @@ -213,4 +213,4 @@ void Udp::StartRecv() { }); } -} // namespace wpi::uv +} // namespace wpi::net::uv diff --git a/wpinet/src/main/native/cpp/uv/Work.cpp b/wpinet/src/main/native/cpp/uv/Work.cpp index 4e81c1ecff..2325307282 100644 --- a/wpinet/src/main/native/cpp/uv/Work.cpp +++ b/wpinet/src/main/native/cpp/uv/Work.cpp @@ -10,7 +10,7 @@ #include "wpi/net/uv/Loop.hpp" -namespace wpi::uv { +namespace wpi::net::uv { WorkReq::WorkReq() { error = [this](Error err) { GetLoop().error(err); }; @@ -57,4 +57,4 @@ void QueueWork(Loop& loop, std::function work, QueueWork(loop, req); } -} // namespace wpi::uv +} // namespace wpi::net::uv diff --git a/wpinet/src/main/native/include/wpi/net/DsClient.hpp b/wpinet/src/main/native/include/wpi/net/DsClient.hpp index 19b71e9b80..a96be18cc6 100644 --- a/wpinet/src/main/native/include/wpi/net/DsClient.hpp +++ b/wpinet/src/main/native/include/wpi/net/DsClient.hpp @@ -10,7 +10,7 @@ #include "wpi/util/Signal.h" -namespace wpi { +namespace wpi::net { class Logger; @@ -24,32 +24,32 @@ class DsClient : public std::enable_shared_from_this { struct private_init {}; public: - static std::shared_ptr Create(wpi::uv::Loop& loop, - wpi::Logger& logger) { + static std::shared_ptr Create(wpi::net::uv::Loop& loop, + wpi::util::Logger& logger) { return std::make_shared(loop, logger, private_init{}); } - DsClient(wpi::uv::Loop& loop, wpi::Logger& logger, const private_init&); + DsClient(wpi::net::uv::Loop& loop, wpi::util::Logger& logger, const private_init&); ~DsClient(); DsClient(const DsClient&) = delete; DsClient& operator=(const DsClient&) = delete; void Close(); - sig::Signal setIp; - sig::Signal<> clearIp; + wpi::util::sig::Signal setIp; + wpi::util::sig::Signal<> clearIp; private: void Connect(); void HandleIncoming(std::string_view in); void ParseJson(); - wpi::Logger& m_logger; + wpi::util::Logger& m_logger; - std::shared_ptr m_tcp; - std::shared_ptr m_timer; + std::shared_ptr m_tcp; + std::shared_ptr m_timer; std::string m_json; }; -} // namespace wpi +} // namespace wpi::net diff --git a/wpinet/src/main/native/include/wpi/net/EventLoopRunner.hpp b/wpinet/src/main/native/include/wpi/net/EventLoopRunner.hpp index 22f2be54d5..efdad6b3b6 100644 --- a/wpinet/src/main/native/include/wpi/net/EventLoopRunner.hpp +++ b/wpinet/src/main/native/include/wpi/net/EventLoopRunner.hpp @@ -11,7 +11,7 @@ #include "wpi/net/uv/Loop.hpp" #include "wpi/util/SafeThread.hpp" -namespace wpi { +namespace wpi::net { /** * Executes an event loop on a separate thread. @@ -54,9 +54,9 @@ class EventLoopRunner { private: class Thread; - SafeThreadOwner m_owner; + wpi::util::SafeThreadOwner m_owner; }; -} // namespace wpi +} // namespace wpi::net #endif // WPINET_WPINET_SRC_MAIN_NATIVE_INCLUDE_WPI_NET_EVENTLOOPRUNNER_HPP_ diff --git a/wpinet/src/main/native/include/wpi/net/HttpParser.hpp b/wpinet/src/main/native/include/wpi/net/HttpParser.hpp index 6f2d14b28c..0a2473ffd1 100644 --- a/wpinet/src/main/native/include/wpi/net/HttpParser.hpp +++ b/wpinet/src/main/native/include/wpi/net/HttpParser.hpp @@ -13,7 +13,7 @@ #include "wpi/util/Signal.h" #include "wpi/util/SmallString.hpp" -namespace wpi { +namespace wpi::net { /** * HTTP protocol parser. Performs incremental parsing with callbacks for each @@ -143,14 +143,14 @@ class HttpParser { /** * Message begin callback. */ - sig::Signal<> messageBegin; + wpi::util::sig::Signal<> messageBegin; /** * URL callback. * * The parameter to the callback is the complete URL string. */ - sig::Signal url; + wpi::util::sig::Signal url; /** * Status callback. @@ -158,14 +158,14 @@ class HttpParser { * The parameter to the callback is the complete status string. * GetStatusCode() can be used to get the numeric status code. */ - sig::Signal status; + wpi::util::sig::Signal status; /** * Header field callback. * * The parameters to the callback are the field name and field value. */ - sig::Signal header; + wpi::util::sig::Signal header; /** * Headers complete callback. @@ -175,7 +175,7 @@ class HttpParser { * connection. If you are the server, respond with the "Connection: close" * header. If you are the client, close the connection. */ - sig::Signal headersComplete; + wpi::util::sig::Signal headersComplete; /** * Body data callback. @@ -185,7 +185,7 @@ class HttpParser { * multiple times arbitrarily (e.g. it's possible that it may be called with * just a few characters at a time). */ - sig::Signal body; + wpi::util::sig::Signal body; /** * Headers complete callback. @@ -195,19 +195,19 @@ class HttpParser { * connection. If you are the server, respond with the "Connection: close" * header. If you are the client, close the connection. */ - sig::Signal messageComplete; + wpi::util::sig::Signal messageComplete; /** * Chunk header callback. * * The parameter to the callback is the chunk size. */ - sig::Signal chunkHeader; + wpi::util::sig::Signal chunkHeader; /** * Chunk complete callback. */ - sig::Signal<> chunkComplete; + wpi::util::sig::Signal<> chunkComplete; private: http_parser m_parser; @@ -215,13 +215,13 @@ class HttpParser { size_t m_maxLength = 1024; enum { kStart, kUrl, kStatus, kField, kValue } m_state = kStart; - SmallString<128> m_urlBuf; - SmallString<32> m_fieldBuf; - SmallString<128> m_valueBuf; + wpi::util::SmallString<128> m_urlBuf; + wpi::util::SmallString<32> m_fieldBuf; + wpi::util::SmallString<128> m_valueBuf; bool m_aborted = false; }; -} // namespace wpi +} // namespace wpi::net #endif // WPINET_WPINET_SRC_MAIN_NATIVE_INCLUDE_WPI_NET_HTTPPARSER_HPP_ diff --git a/wpinet/src/main/native/include/wpi/net/HttpServerConnection.hpp b/wpinet/src/main/native/include/wpi/net/HttpServerConnection.hpp index 44f3c8ed90..fca6f23ac7 100644 --- a/wpinet/src/main/native/include/wpi/net/HttpServerConnection.hpp +++ b/wpinet/src/main/native/include/wpi/net/HttpServerConnection.hpp @@ -12,7 +12,7 @@ #include "wpi/net/HttpParser.hpp" #include "wpi/net/uv/Stream.hpp" -namespace wpi { +namespace wpi::net { class raw_ostream; @@ -49,7 +49,7 @@ class HttpServerConnection { * * @param os response stream */ - virtual void BuildCommonHeaders(raw_ostream& os); + virtual void BuildCommonHeaders(wpi::util::raw_ostream& os); /** * Build HTTP response header, along with other header information like @@ -63,7 +63,7 @@ class HttpServerConnection { * be set to false. * @param extra Extra HTTP headers to send, including final "\r\n" */ - virtual void BuildHeader(raw_ostream& os, int code, std::string_view codeText, + virtual void BuildHeader(wpi::util::raw_ostream& os, int code, std::string_view codeText, std::string_view contentType, uint64_t contentLength, std::string_view extra = {}); @@ -138,15 +138,15 @@ class HttpServerConnection { uv::Stream& m_stream; /** The header reader connection. */ - sig::ScopedConnection m_dataConn; + wpi::util::sig::ScopedConnection m_dataConn; /** The end stream connection. */ - sig::ScopedConnection m_endConn; + wpi::util::sig::ScopedConnection m_endConn; /** The message complete connection. */ - sig::Connection m_messageCompleteConn; + wpi::util::sig::Connection m_messageCompleteConn; }; -} // namespace wpi +} // namespace wpi::net #endif // WPINET_WPINET_SRC_MAIN_NATIVE_INCLUDE_WPI_NET_HTTPSERVERCONNECTION_HPP_ diff --git a/wpinet/src/main/native/include/wpi/net/HttpUtil.hpp b/wpinet/src/main/native/include/wpi/net/HttpUtil.hpp index d56b80f400..a9f4b80fe4 100644 --- a/wpinet/src/main/native/include/wpi/net/HttpUtil.hpp +++ b/wpinet/src/main/native/include/wpi/net/HttpUtil.hpp @@ -22,26 +22,26 @@ #include "wpi/util/StringMap.hpp" #include "wpi/util/raw_istream.hpp" -namespace wpi { +namespace wpi::net { // Unescape a %xx-encoded URI. // @param buf Buffer for output // @param error Set to true if an error occurred // @return Escaped string -std::string_view UnescapeURI(std::string_view str, SmallVectorImpl& buf, +std::string_view UnescapeURI(std::string_view str, wpi::util::SmallVectorImpl& buf, bool* error); // Escape a string with %xx-encoding. // @param buf Buffer for output // @param spacePlus If true, encodes spaces to '+' rather than "%20" // @return Escaped string -std::string_view EscapeURI(std::string_view str, SmallVectorImpl& buf, +std::string_view EscapeURI(std::string_view str, wpi::util::SmallVectorImpl& buf, bool spacePlus = true); // Escape a string for HTML output. // @param buf Buffer for output // @return Escaped string -std::string_view EscapeHTML(std::string_view str, SmallVectorImpl& buf); +std::string_view EscapeHTML(std::string_view str, wpi::util::SmallVectorImpl& buf); // Parse a set of HTTP headers. Saves just the Content-Type and Content-Length // fields. @@ -49,8 +49,8 @@ std::string_view EscapeHTML(std::string_view str, SmallVectorImpl& buf); // @param contentType If not null, Content-Type contents are saved here. // @param contentLength If not null, Content-Length contents are saved here. // @return False if error occurred in input stream -bool ParseHttpHeaders(raw_istream& is, SmallVectorImpl* contentType, - SmallVectorImpl* contentLength); +bool ParseHttpHeaders(wpi::util::raw_istream& is, wpi::util::SmallVectorImpl* contentType, + wpi::util::SmallVectorImpl* contentLength); // Look for a MIME multi-part boundary. On return, the input stream will // be located at the character following the boundary (usually "\r\n"). @@ -59,7 +59,7 @@ bool ParseHttpHeaders(raw_istream& is, SmallVectorImpl* contentType, // @param saveBuf If not null, all scanned characters up to but not including // the boundary are saved to this string // @return False if error occurred on input stream, true if boundary found. -bool FindMultipartBoundary(wpi::raw_istream& is, std::string_view boundary, +bool FindMultipartBoundary(wpi::util::raw_istream& is, std::string_view boundary, std::string* saveBuf); /** @@ -93,10 +93,10 @@ class HttpQueryMap { * name is not present in the query map. */ std::optional Get(std::string_view name, - SmallVectorImpl& buf) const; + wpi::util::SmallVectorImpl& buf) const; private: - StringMap m_elems; + wpi::util::StringMap m_elems; }; class HttpPathRef; @@ -224,8 +224,8 @@ class HttpPath { HttpPathRef drop_front(size_t n) const; private: - SmallString<128> m_pathBuf; - SmallVector m_pathEnds; + wpi::util::SmallString<128> m_pathBuf; + wpi::util::SmallVector m_pathEnds; }; /** @@ -322,7 +322,7 @@ class HttpRequest { template HttpRequest(const HttpLocation& loc, const T& extraParams) : host{loc.host}, port{loc.port} { - SmallVector, 4> params; + wpi::util::SmallVector, 4> params; for (const auto& p : loc.params) { params.emplace_back(std::pair{GetFirst(p), GetSecond(p)}); } @@ -345,10 +345,10 @@ class HttpRequest { SetAuth(loc); } - SmallString<128> host; + wpi::util::SmallString<128> host; int port; std::string auth; - SmallString<128> path; + wpi::util::SmallString<128> path; private: void SetAuth(const HttpLocation& loc); @@ -356,7 +356,7 @@ class HttpRequest { template void SetPath(std::string_view path_, const T& params) { // Build location including query string - raw_svector_ostream pathOs{path}; + wpi::util::raw_svector_ostream pathOs{path}; pathOs << path_; bool first = true; for (const auto& param : params) { @@ -366,7 +366,7 @@ class HttpRequest { } else { pathOs << '&'; } - SmallString<64> escapeBuf; + wpi::util::SmallString<64> escapeBuf; pathOs << EscapeURI(GetFirst(param), escapeBuf, false); if (!GetSecond(param).empty()) { pathOs << '=' << EscapeURI(GetSecond(param), escapeBuf, false); @@ -390,18 +390,18 @@ class HttpRequest { class HttpConnection { public: - HttpConnection(std::unique_ptr stream_, int timeout) + HttpConnection(std::unique_ptr stream_, int timeout) : stream{std::move(stream_)}, is{*stream, timeout}, os{*stream, true} {} bool Handshake(const HttpRequest& request, std::string* warnMsg); - std::unique_ptr stream; - wpi::raw_socket_istream is; - wpi::raw_socket_ostream os; + std::unique_ptr stream; + wpi::net::raw_socket_istream is; + wpi::net::raw_socket_ostream os; // Valid after Handshake() is successful - SmallString<64> contentType; - SmallString<64> contentLength; + wpi::util::SmallString<64> contentType; + wpi::util::SmallString<64> contentLength; explicit operator bool() const { return stream && !is.has_error(); } }; @@ -436,7 +436,7 @@ class HttpMultipartScanner { } private: - SmallString<64> m_boundaryWith, m_boundaryWithout; + wpi::util::SmallString<64> m_boundaryWith, m_boundaryWithout; // Internal state enum State { kBoundary, kPadding, kDone }; @@ -454,6 +454,6 @@ inline HttpPathRef HttpPath::drop_front(size_t n) const { return HttpPathRef(*this, n); } -} // namespace wpi +} // namespace wpi::net #endif // WPINET_WPINET_SRC_MAIN_NATIVE_INCLUDE_WPI_NET_HTTPUTIL_HPP_ diff --git a/wpinet/src/main/native/include/wpi/net/HttpWebSocketServerConnection.hpp b/wpinet/src/main/native/include/wpi/net/HttpWebSocketServerConnection.hpp index 511a05337d..1310473bf5 100644 --- a/wpinet/src/main/native/include/wpi/net/HttpWebSocketServerConnection.hpp +++ b/wpinet/src/main/native/include/wpi/net/HttpWebSocketServerConnection.hpp @@ -17,7 +17,7 @@ #include "wpi/net/uv/Stream.hpp" #include "wpi/util/SmallVector.hpp" -namespace wpi { +namespace wpi::net { /** * A server-side HTTP connection that also accepts WebSocket upgrades. @@ -43,7 +43,7 @@ class HttpWebSocketServerConnection // Handle upgrade event m_helper.upgrade.connect([this] { // Negotiate sub-protocol - SmallVector protocols{m_protocols.begin(), + wpi::util::SmallVector protocols{m_protocols.begin(), m_protocols.end()}; std::string_view protocol = m_helper.MatchProtocol(protocols).second; @@ -118,9 +118,9 @@ class HttpWebSocketServerConnection private: WebSocketServerHelper m_helper; - SmallVector m_protocols; + wpi::util::SmallVector m_protocols; }; -} // namespace wpi +} // namespace wpi::net #endif // WPINET_WPINET_SRC_MAIN_NATIVE_INCLUDE_WPI_NET_HTTPWEBSOCKETSERVERCONNECTION_HPP_ diff --git a/wpinet/src/main/native/include/wpi/net/MimeTypes.hpp b/wpinet/src/main/native/include/wpi/net/MimeTypes.hpp index 8bf1844ab0..032e9ab9d8 100644 --- a/wpinet/src/main/native/include/wpi/net/MimeTypes.hpp +++ b/wpinet/src/main/native/include/wpi/net/MimeTypes.hpp @@ -7,10 +7,10 @@ #include -namespace wpi { +namespace wpi::net { std::string_view MimeTypeFromPath(std::string_view path); -} // namespace wpi +} // namespace wpi::net #endif // WPINET_WPINET_SRC_MAIN_NATIVE_INCLUDE_WPI_NET_MIMETYPES_HPP_ diff --git a/wpinet/src/main/native/include/wpi/net/MulticastServiceAnnouncer.h b/wpinet/src/main/native/include/wpi/net/MulticastServiceAnnouncer.h index ee1ede2fa7..3b2c56a7b9 100644 --- a/wpinet/src/main/native/include/wpi/net/MulticastServiceAnnouncer.h +++ b/wpinet/src/main/native/include/wpi/net/MulticastServiceAnnouncer.h @@ -12,7 +12,7 @@ #include #include #include -namespace wpi { +namespace wpi::net { class MulticastServiceAnnouncer { public: /** @@ -66,7 +66,7 @@ class MulticastServiceAnnouncer { private: std::unique_ptr pImpl; }; -} // namespace wpi +} // namespace wpi::net extern "C" { #endif diff --git a/wpinet/src/main/native/include/wpi/net/MulticastServiceResolver.h b/wpinet/src/main/native/include/wpi/net/MulticastServiceResolver.h index edf15acc10..883b107bf1 100644 --- a/wpinet/src/main/native/include/wpi/net/MulticastServiceResolver.h +++ b/wpinet/src/main/native/include/wpi/net/MulticastServiceResolver.h @@ -15,7 +15,7 @@ #include #include "wpi/util/mutex.hpp" -namespace wpi { +namespace wpi::net { class MulticastServiceResolver { public: explicit MulticastServiceResolver(std::string_view serviceType); @@ -95,14 +95,14 @@ class MulticastServiceResolver { event.Set(); } } - wpi::Event event{true}; + wpi::util::Event event{true}; std::vector queue; - wpi::mutex mutex; + wpi::util::mutex mutex; std::function copyCallback; std::function moveCallback; std::unique_ptr pImpl; }; -} // namespace wpi +} // namespace wpi::net #endif #ifdef __cplusplus diff --git a/wpinet/src/main/native/include/wpi/net/NetworkAcceptor.hpp b/wpinet/src/main/native/include/wpi/net/NetworkAcceptor.hpp index 714bdab931..50ad6e87ed 100644 --- a/wpinet/src/main/native/include/wpi/net/NetworkAcceptor.hpp +++ b/wpinet/src/main/native/include/wpi/net/NetworkAcceptor.hpp @@ -9,7 +9,7 @@ #include "wpi/net/NetworkStream.hpp" -namespace wpi { +namespace wpi::net { class NetworkAcceptor { public: @@ -24,6 +24,6 @@ class NetworkAcceptor { NetworkAcceptor& operator=(const NetworkAcceptor&) = delete; }; -} // namespace wpi +} // namespace wpi::net #endif // WPINET_WPINET_SRC_MAIN_NATIVE_INCLUDE_WPI_NET_NETWORKACCEPTOR_HPP_ diff --git a/wpinet/src/main/native/include/wpi/net/NetworkStream.hpp b/wpinet/src/main/native/include/wpi/net/NetworkStream.hpp index 00a414372f..c62de14642 100644 --- a/wpinet/src/main/native/include/wpi/net/NetworkStream.hpp +++ b/wpinet/src/main/native/include/wpi/net/NetworkStream.hpp @@ -8,7 +8,7 @@ #include #include -namespace wpi { +namespace wpi::net { class NetworkStream { public: @@ -39,6 +39,6 @@ class NetworkStream { NetworkStream& operator=(const NetworkStream&) = delete; }; -} // namespace wpi +} // namespace wpi::net #endif // WPINET_WPINET_SRC_MAIN_NATIVE_INCLUDE_WPI_NET_NETWORKSTREAM_HPP_ diff --git a/wpinet/src/main/native/include/wpi/net/ParallelTcpConnector.hpp b/wpinet/src/main/native/include/wpi/net/ParallelTcpConnector.hpp index 9f06c33f36..713c890fc3 100644 --- a/wpinet/src/main/native/include/wpi/net/ParallelTcpConnector.hpp +++ b/wpinet/src/main/native/include/wpi/net/ParallelTcpConnector.hpp @@ -15,7 +15,7 @@ #include "wpi/net/uv/Timer.hpp" -namespace wpi { +namespace wpi::net { class Logger; @@ -59,8 +59,8 @@ class ParallelTcpConnector * @return Parallel connector */ static std::shared_ptr Create( - wpi::uv::Loop& loop, wpi::uv::Timer::Time reconnectRate, - wpi::Logger& logger, std::function connected, + wpi::net::uv::Loop& loop, wpi::net::uv::Timer::Time reconnectRate, + wpi::util::Logger& logger, std::function connected, bool ipv4Only = false) { if (loop.IsClosing()) { return nullptr; @@ -70,9 +70,9 @@ class ParallelTcpConnector ipv4Only, private_init{}); } - ParallelTcpConnector(wpi::uv::Loop& loop, wpi::uv::Timer::Time reconnectRate, - wpi::Logger& logger, - std::function connected, + ParallelTcpConnector(wpi::net::uv::Loop& loop, wpi::net::uv::Timer::Time reconnectRate, + wpi::util::Logger& logger, + std::function connected, bool ipv4Only, const private_init&); ~ParallelTcpConnector(); @@ -105,24 +105,24 @@ class ParallelTcpConnector * * @param tcp connection passed to connected callback */ - void Succeeded(wpi::uv::Tcp& tcp); + void Succeeded(wpi::net::uv::Tcp& tcp); private: bool IsConnected() const { return m_isConnected || m_servers.empty(); } void Connect(); - void CancelAll(wpi::uv::Tcp* except = nullptr); + void CancelAll(wpi::net::uv::Tcp* except = nullptr); - wpi::uv::Loop& m_loop; - wpi::Logger& m_logger; - wpi::uv::Timer::Time m_reconnectRate; + wpi::net::uv::Loop& m_loop; + wpi::util::Logger& m_logger; + wpi::net::uv::Timer::Time m_reconnectRate; bool m_ipv4Only; - std::function m_connected; - std::shared_ptr m_reconnectTimer; + std::function m_connected; + std::shared_ptr m_reconnectTimer; std::vector> m_servers; - std::vector> m_resolvers; - std::vector>> + std::vector> m_resolvers; + std::vector>> m_attempts; bool m_isConnected{false}; }; -} // namespace wpi +} // namespace wpi::net diff --git a/wpinet/src/main/native/include/wpi/net/PortForwarder.hpp b/wpinet/src/main/native/include/wpi/net/PortForwarder.hpp index 0bd30cb47b..6e5bf2c18c 100644 --- a/wpinet/src/main/native/include/wpi/net/PortForwarder.hpp +++ b/wpinet/src/main/native/include/wpi/net/PortForwarder.hpp @@ -10,7 +10,7 @@ #include #include -namespace wpi { +namespace wpi::net { /** * Forward ports to another host. This is primarily useful for accessing @@ -54,6 +54,6 @@ class PortForwarder { std::unique_ptr m_impl; }; -} // namespace wpi +} // namespace wpi::net #endif // WPINET_WPINET_SRC_MAIN_NATIVE_INCLUDE_WPI_NET_PORTFORWARDER_HPP_ diff --git a/wpinet/src/main/native/include/wpi/net/SocketError.hpp b/wpinet/src/main/native/include/wpi/net/SocketError.hpp index d23aea80cc..f102d9fa5f 100644 --- a/wpinet/src/main/native/include/wpi/net/SocketError.hpp +++ b/wpinet/src/main/native/include/wpi/net/SocketError.hpp @@ -7,7 +7,7 @@ #include -namespace wpi { +namespace wpi::net { int SocketErrno(); @@ -17,6 +17,6 @@ inline std::string SocketStrerror() { return SocketStrerror(SocketErrno()); } -} // namespace wpi +} // namespace wpi::net #endif // WPINET_WPINET_SRC_MAIN_NATIVE_INCLUDE_WPI_NET_SOCKETERROR_HPP_ diff --git a/wpinet/src/main/native/include/wpi/net/UDPClient.hpp b/wpinet/src/main/native/include/wpi/net/UDPClient.hpp index 8c139b430a..1c7c2cb445 100644 --- a/wpinet/src/main/native/include/wpi/net/UDPClient.hpp +++ b/wpinet/src/main/native/include/wpi/net/UDPClient.hpp @@ -12,7 +12,7 @@ #include "wpi/util/SmallVector.hpp" #include "wpi/util/mutex.hpp" -namespace wpi { +namespace wpi::net { class Logger; @@ -20,11 +20,11 @@ class UDPClient { int m_lsd; int m_port; std::string m_address; - Logger& m_logger; + wpi::util::Logger& m_logger; public: - explicit UDPClient(Logger& logger); - UDPClient(std::string_view address, Logger& logger); + explicit UDPClient(wpi::util::Logger& logger); + UDPClient(std::string_view address, wpi::util::Logger& logger); UDPClient(const UDPClient& other) = delete; UDPClient(UDPClient&& other); ~UDPClient(); @@ -40,10 +40,10 @@ class UDPClient { int send(std::string_view data, std::string_view server, int port); int receive(uint8_t* data_received, int receive_len); int receive(uint8_t* data_received, int receive_len, - SmallVectorImpl* addr_received, int* port_received); + wpi::util::SmallVectorImpl* addr_received, int* port_received); int set_timeout(double timeout); }; -} // namespace wpi +} // namespace wpi::net #endif // WPINET_WPINET_SRC_MAIN_NATIVE_INCLUDE_WPI_NET_UDPCLIENT_HPP_ diff --git a/wpinet/src/main/native/include/wpi/net/UrlParser.hpp b/wpinet/src/main/native/include/wpi/net/UrlParser.hpp index 5f0faa09da..cf7bd2bc24 100644 --- a/wpinet/src/main/native/include/wpi/net/UrlParser.hpp +++ b/wpinet/src/main/native/include/wpi/net/UrlParser.hpp @@ -10,7 +10,7 @@ #include "wpi/net/http_parser.hpp" #include "wpi/util/StringExtras.hpp" -namespace wpi { +namespace wpi::net { /** * Parses a URL into its constituent components. @@ -53,34 +53,34 @@ class UrlParser { } std::string_view GetSchema() const { - return wpi::substr(m_data, m_url.field_data[UF_SCHEMA].off, + return wpi::util::substr(m_data, m_url.field_data[UF_SCHEMA].off, m_url.field_data[UF_SCHEMA].len); } std::string_view GetHost() const { - return wpi::substr(m_data, m_url.field_data[UF_HOST].off, + return wpi::util::substr(m_data, m_url.field_data[UF_HOST].off, m_url.field_data[UF_HOST].len); } unsigned int GetPort() const { return m_url.port; } std::string_view GetPath() const { - return wpi::substr(m_data, m_url.field_data[UF_PATH].off, + return wpi::util::substr(m_data, m_url.field_data[UF_PATH].off, m_url.field_data[UF_PATH].len); } std::string_view GetQuery() const { - return wpi::substr(m_data, m_url.field_data[UF_QUERY].off, + return wpi::util::substr(m_data, m_url.field_data[UF_QUERY].off, m_url.field_data[UF_QUERY].len); } std::string_view GetFragment() const { - return wpi::substr(m_data, m_url.field_data[UF_FRAGMENT].off, + return wpi::util::substr(m_data, m_url.field_data[UF_FRAGMENT].off, m_url.field_data[UF_FRAGMENT].len); } std::string_view GetUserInfo() const { - return wpi::substr(m_data, m_url.field_data[UF_USERINFO].off, + return wpi::util::substr(m_data, m_url.field_data[UF_USERINFO].off, m_url.field_data[UF_USERINFO].len); } @@ -90,6 +90,6 @@ class UrlParser { http_parser_url m_url; }; -} // namespace wpi +} // namespace wpi::net #endif // WPINET_WPINET_SRC_MAIN_NATIVE_INCLUDE_WPI_NET_URLPARSER_HPP_ diff --git a/wpinet/src/main/native/include/wpi/net/WebServer.hpp b/wpinet/src/main/native/include/wpi/net/WebServer.hpp index 59e066b84c..9e9280c1df 100644 --- a/wpinet/src/main/native/include/wpi/net/WebServer.hpp +++ b/wpinet/src/main/native/include/wpi/net/WebServer.hpp @@ -10,7 +10,7 @@ #include #include -namespace wpi { +namespace wpi::net { /** * A web server using the HTTP protocol. @@ -53,6 +53,6 @@ class WebServer { std::unique_ptr m_impl; }; -} // namespace wpi +} // namespace wpi::net #endif // WPINET_WPINET_SRC_MAIN_NATIVE_INCLUDE_WPI_NET_WEBSERVER_HPP_ diff --git a/wpinet/src/main/native/include/wpi/net/WebSocket.hpp b/wpinet/src/main/native/include/wpi/net/WebSocket.hpp index bd5b33ace9..4cb8250bc8 100644 --- a/wpinet/src/main/native/include/wpi/net/WebSocket.hpp +++ b/wpinet/src/main/native/include/wpi/net/WebSocket.hpp @@ -21,7 +21,7 @@ #include "wpi/util/Signal.h" #include "wpi/util/SmallVector.hpp" -namespace wpi { +namespace wpi::net { namespace uv { class Stream; @@ -466,7 +466,7 @@ class WebSocket : public std::enable_shared_from_this { * Open event. Emitted when the connection is open and ready to communicate. * The parameter is the selected subprotocol. */ - sig::Signal open; + wpi::util::sig::Signal open; /** * Close event. Emitted when the connection is closed. The first parameter @@ -474,32 +474,32 @@ class WebSocket : public std::enable_shared_from_this { * has been closed. The second parameter is a human-readable string * explaining the reason why the connection has been closed. */ - sig::Signal closed; + wpi::util::sig::Signal closed; /** * Text message event. Emitted when a text message is received. * The first parameter is the data, the second parameter is true if the * data is the last fragment of the message. */ - sig::Signal text; + wpi::util::sig::Signal text; /** * Binary message event. Emitted when a binary message is received. * The first parameter is the data, the second parameter is true if the * data is the last fragment of the message. */ - sig::Signal, bool> binary; + wpi::util::sig::Signal, bool> binary; /** * Ping event. Emitted when a ping message is received. A pong message is * automatically sent in response, so this is simply a notification. */ - sig::Signal> ping; + wpi::util::sig::Signal> ping; /** * Pong event. Emitted when a pong message is received. */ - sig::Signal> pong; + wpi::util::sig::Signal> pong; private: // user data @@ -527,10 +527,10 @@ class WebSocket : public std::enable_shared_from_this { // incoming message buffers/state uint64_t m_lastReceivedTime = 0; - SmallVector m_header; + wpi::util::SmallVector m_header; size_t m_headerSize = 0; - SmallVector m_payload; - SmallVector m_controlPayload; + wpi::util::SmallVector m_payload; + wpi::util::SmallVector m_controlPayload; size_t m_frameStart = 0; uint64_t m_frameSize = UINT64_MAX; uint8_t m_fragmentOpcode = 0; @@ -559,6 +559,6 @@ class WebSocket : public std::enable_shared_from_this { const std::function, uv::Error)>& callback); }; -} // namespace wpi +} // namespace wpi::net #endif // WPINET_WPINET_SRC_MAIN_NATIVE_INCLUDE_WPI_NET_WEBSOCKET_HPP_ diff --git a/wpinet/src/main/native/include/wpi/net/WebSocketServer.hpp b/wpinet/src/main/native/include/wpi/net/WebSocketServer.hpp index f873c22a27..6bd82c6697 100644 --- a/wpinet/src/main/native/include/wpi/net/WebSocketServer.hpp +++ b/wpinet/src/main/native/include/wpi/net/WebSocketServer.hpp @@ -19,7 +19,7 @@ #include "wpi/util/SmallString.hpp" #include "wpi/util/SmallVector.hpp" -namespace wpi { +namespace wpi::net { namespace uv { class Stream; @@ -97,14 +97,14 @@ class WebSocketServerHelper { /** * Upgrade event. Call Accept() to accept the upgrade. */ - sig::Signal<> upgrade; + wpi::util::sig::Signal<> upgrade; private: bool m_gotHost = false; bool m_websocket = false; - SmallVector m_protocols; - SmallString<64> m_key; - SmallString<16> m_version; + wpi::util::SmallVector m_protocols; + wpi::util::SmallString<64> m_key; + wpi::util::SmallString<16> m_version; }; /** @@ -169,22 +169,22 @@ class WebSocketServer : public std::enable_shared_from_this { /** * Connected event. First parameter is the URL, second is the websocket. */ - sig::Signal connected; + wpi::util::sig::Signal connected; private: uv::Stream& m_stream; HttpParser m_req{HttpParser::kRequest}; WebSocketServerHelper m_helper; - SmallVector m_protocols; + wpi::util::SmallVector m_protocols; ServerOptions m_options; bool m_aborted = false; - sig::ScopedConnection m_dataConn; - sig::ScopedConnection m_errorConn; - sig::ScopedConnection m_endConn; + wpi::util::sig::ScopedConnection m_dataConn; + wpi::util::sig::ScopedConnection m_errorConn; + wpi::util::sig::ScopedConnection m_endConn; void Abort(uint16_t code, std::string_view reason); }; -} // namespace wpi +} // namespace wpi::net #endif // WPINET_WPINET_SRC_MAIN_NATIVE_INCLUDE_WPI_NET_WEBSOCKETSERVER_HPP_ diff --git a/wpinet/src/main/native/include/wpi/net/WorkerThread.hpp b/wpinet/src/main/native/include/wpi/net/WorkerThread.hpp index 6a4293f774..6432161b29 100644 --- a/wpinet/src/main/native/include/wpi/net/WorkerThread.hpp +++ b/wpinet/src/main/native/include/wpi/net/WorkerThread.hpp @@ -15,7 +15,7 @@ #include "wpi/util/SafeThread.hpp" #include "wpi/util/future.hpp" -namespace wpi { +namespace wpi::net { namespace detail { @@ -89,14 +89,14 @@ struct WorkerThreadRequest { }; template -class WorkerThreadThread : public SafeThread { +class WorkerThreadThread : public wpi::util::SafeThread { public: using Request = WorkerThreadRequest; void Main() override; std::vector m_requests; - PromiseFactory m_promises; + wpi::util::PromiseFactory m_promises; detail::WorkerThreadAsync m_async; }; @@ -228,7 +228,7 @@ class WorkerThread final { * @param u Arguments to work function */ template - future QueueWork(WorkFunction work, U&&... u) { + wpi::util::future QueueWork(WorkFunction work, U&&... u) { if (auto thr = m_owner.GetThread()) { // create the future uint64_t req = thr->m_promises.CreateRequest(); @@ -245,7 +245,7 @@ class WorkerThread final { } // XXX: is this the right thing to do? - return future(); + return wpi::util::future(); } /** @@ -277,9 +277,9 @@ class WorkerThread final { } private: - SafeThreadOwner m_owner; + wpi::util::SafeThreadOwner m_owner; }; -} // namespace wpi +} // namespace wpi::net #endif // WPINET_WPINET_SRC_MAIN_NATIVE_INCLUDE_WPI_NET_WORKERTHREAD_HPP_ diff --git a/wpinet/src/main/native/include/wpi/net/hostname.hpp b/wpinet/src/main/native/include/wpi/net/hostname.hpp index 30b4ae6773..2dc6b8e628 100644 --- a/wpinet/src/main/native/include/wpi/net/hostname.hpp +++ b/wpinet/src/main/native/include/wpi/net/hostname.hpp @@ -8,12 +8,12 @@ #include #include -namespace wpi { +namespace wpi::net { template class SmallVectorImpl; std::string GetHostname(); -std::string_view GetHostname(SmallVectorImpl& name); -} // namespace wpi +std::string_view GetHostname(wpi::util::SmallVectorImpl& name); +} // namespace wpi::net #endif // WPINET_WPINET_SRC_MAIN_NATIVE_INCLUDE_WPI_NET_HOSTNAME_HPP_ diff --git a/wpinet/src/main/native/include/wpi/net/http_parser.hpp b/wpinet/src/main/native/include/wpi/net/http_parser.hpp index 3993a4fc27..2da9d9c16f 100644 --- a/wpinet/src/main/native/include/wpi/net/http_parser.hpp +++ b/wpinet/src/main/native/include/wpi/net/http_parser.hpp @@ -47,7 +47,7 @@ # define HTTP_MAX_HEADER_SIZE (80*1024) #endif -namespace wpi { +namespace wpi::net { struct http_parser; struct http_parser_settings; @@ -273,7 +273,7 @@ enum http_errno { /* Get an http_errno value from an http_parser */ -#define HTTP_PARSER_ERRNO(p) ((::wpi::http_errno) (p)->http_errno) +#define HTTP_PARSER_ERRNO(p) ((::wpi::net::http_errno) (p)->http_errno) struct http_parser { @@ -416,6 +416,6 @@ void http_parser_pause(http_parser *parser, int paused); /* Checks if this is the final chunk of the body. */ int http_body_is_final(const http_parser *parser); -} // namespace wpi +} // namespace wpi::net #endif diff --git a/wpinet/src/main/native/include/wpi/net/raw_socket_istream.hpp b/wpinet/src/main/native/include/wpi/net/raw_socket_istream.hpp index 0866b402ef..f61ab8470f 100644 --- a/wpinet/src/main/native/include/wpi/net/raw_socket_istream.hpp +++ b/wpinet/src/main/native/include/wpi/net/raw_socket_istream.hpp @@ -7,11 +7,11 @@ #include "wpi/util/raw_istream.hpp" -namespace wpi { +namespace wpi::net { class NetworkStream; -class raw_socket_istream : public raw_istream { +class raw_socket_istream : public wpi::util::raw_istream { public: explicit raw_socket_istream(NetworkStream& stream, int timeout = 0) : m_stream(stream), m_timeout(timeout) {} @@ -26,6 +26,6 @@ class raw_socket_istream : public raw_istream { int m_timeout; }; -} // namespace wpi +} // namespace wpi::net #endif // WPINET_WPINET_SRC_MAIN_NATIVE_INCLUDE_WPI_NET_RAW_SOCKET_ISTREAM_HPP_ diff --git a/wpinet/src/main/native/include/wpi/net/raw_socket_ostream.hpp b/wpinet/src/main/native/include/wpi/net/raw_socket_ostream.hpp index bd013fc1d4..b95bc1d794 100644 --- a/wpinet/src/main/native/include/wpi/net/raw_socket_ostream.hpp +++ b/wpinet/src/main/native/include/wpi/net/raw_socket_ostream.hpp @@ -7,11 +7,11 @@ #include "wpi/util/raw_ostream.hpp" -namespace wpi { +namespace wpi::net { class NetworkStream; -class raw_socket_ostream : public raw_ostream { +class raw_socket_ostream : public wpi::util::raw_ostream { public: raw_socket_ostream(NetworkStream& stream, bool shouldClose) : m_stream(stream), m_shouldClose(shouldClose) {} @@ -34,6 +34,6 @@ class raw_socket_ostream : public raw_ostream { bool m_shouldClose; }; -} // namespace wpi +} // namespace wpi::net #endif // WPINET_WPINET_SRC_MAIN_NATIVE_INCLUDE_WPI_NET_RAW_SOCKET_OSTREAM_HPP_ diff --git a/wpinet/src/main/native/include/wpi/net/raw_uv_ostream.hpp b/wpinet/src/main/native/include/wpi/net/raw_uv_ostream.hpp index 44818e0474..14bfcd55cf 100644 --- a/wpinet/src/main/native/include/wpi/net/raw_uv_ostream.hpp +++ b/wpinet/src/main/native/include/wpi/net/raw_uv_ostream.hpp @@ -13,14 +13,14 @@ #include "wpi/util/SmallVector.hpp" #include "wpi/util/raw_ostream.hpp" -namespace wpi { +namespace wpi::net { /** - * raw_ostream style output to a SmallVector of uv::Buffer buffers. Fixed-size + * wpi::util::raw_ostream style output to a wpi::util::SmallVector of uv::Buffer buffers. Fixed-size * buffers are allocated and appended as necessary to fit the data being output. - * The SmallVector need not be empty at start. + * The wpi::util::SmallVector need not be empty at start. */ -class raw_uv_ostream : public raw_ostream { +class raw_uv_ostream : public wpi::util::raw_ostream { public: /** * Construct a new raw_uv_ostream. @@ -28,7 +28,7 @@ class raw_uv_ostream : public raw_ostream { * @param allocSize Size to allocate for each buffer; allocation will be * performed using Buffer::Allocate(). */ - raw_uv_ostream(SmallVectorImpl& bufs, size_t allocSize) + raw_uv_ostream(wpi::util::SmallVectorImpl& bufs, size_t allocSize) : m_bufs(bufs), m_alloc([=] { return uv::Buffer::Allocate(allocSize); }) { SetUnbuffered(); } @@ -38,7 +38,7 @@ class raw_uv_ostream : public raw_ostream { * @param bufs Buffers vector. NOT cleared on construction. * @param alloc Allocator. */ - raw_uv_ostream(SmallVectorImpl& bufs, + raw_uv_ostream(wpi::util::SmallVectorImpl& bufs, std::function alloc) : m_bufs(bufs), m_alloc(std::move(alloc)) { SetUnbuffered(); @@ -62,13 +62,13 @@ class raw_uv_ostream : public raw_ostream { void write_impl(const char* data, size_t len) override; uint64_t current_pos() const override; - SmallVectorImpl& m_bufs; + wpi::util::SmallVectorImpl& m_bufs; std::function m_alloc; // How much allocated space is left in the current buffer. size_t m_left = 0; }; -} // namespace wpi +} // namespace wpi::net #endif // WPINET_WPINET_SRC_MAIN_NATIVE_INCLUDE_WPI_NET_RAW_UV_OSTREAM_HPP_ diff --git a/wpinet/src/main/native/include/wpi/net/uv/Async.hpp b/wpinet/src/main/native/include/wpi/net/uv/Async.hpp index 619975c481..ca4130667d 100644 --- a/wpinet/src/main/native/include/wpi/net/uv/Async.hpp +++ b/wpinet/src/main/native/include/wpi/net/uv/Async.hpp @@ -18,7 +18,7 @@ #include "wpi/util/Signal.h" #include "wpi/util/mutex.hpp" -namespace wpi::uv { +namespace wpi::net::uv { /** * Async handle. @@ -121,10 +121,10 @@ class Async final : public HandleImpl, uv_async_t> { /** * Signal generated (on event loop thread) when the async event occurs. */ - sig::Signal wakeup; + wpi::util::sig::Signal wakeup; private: - wpi::mutex m_mutex; + wpi::util::mutex m_mutex; std::vector> m_data; std::weak_ptr m_loop; }; @@ -190,12 +190,12 @@ class Async<> final : public HandleImpl, uv_async_t> { /** * Signal generated (on event loop thread) when the async event occurs. */ - sig::Signal<> wakeup; + wpi::util::sig::Signal<> wakeup; private: std::weak_ptr m_loop; }; -} // namespace wpi::uv +} // namespace wpi::net::uv #endif // WPINET_WPINET_SRC_MAIN_NATIVE_INCLUDE_WPI_NET_UV_ASYNC_HPP_ diff --git a/wpinet/src/main/native/include/wpi/net/uv/AsyncFunction.hpp b/wpinet/src/main/native/include/wpi/net/uv/AsyncFunction.hpp index 9ee8818d74..961a4de4d5 100644 --- a/wpinet/src/main/native/include/wpi/net/uv/AsyncFunction.hpp +++ b/wpinet/src/main/native/include/wpi/net/uv/AsyncFunction.hpp @@ -21,7 +21,7 @@ #include "wpi/util/future.hpp" #include "wpi/util/mutex.hpp" -namespace wpi::uv { +namespace wpi::net::uv { template class AsyncFunction; @@ -38,7 +38,7 @@ class AsyncFunction final public: AsyncFunction(const std::shared_ptr& loop, - std::function, T...)> func, const private_init&) + std::function, T...)> func, const private_init&) : wakeup{std::move(func)}, m_loop{loop} {} ~AsyncFunction() noexcept override { if (auto loop = m_loop.lock()) { @@ -58,7 +58,7 @@ class AsyncFunction final * wakeup function, a default-constructed value is "returned". */ static std::shared_ptr Create( - Loop& loop, std::function, T...)> func = nullptr) { + Loop& loop, std::function, T...)> func = nullptr) { return Create(loop.shared_from_this(), std::move(func)); } @@ -73,7 +73,7 @@ class AsyncFunction final */ static std::shared_ptr Create( const std::shared_ptr& loop, - std::function, T...)> func = nullptr) { + std::function, T...)> func = nullptr) { if (loop->IsClosing()) { return nullptr; } @@ -121,7 +121,7 @@ class AsyncFunction final * destroyed while waiting for a result. */ template - future Call(U&&... u) { + wpi::util::future Call(U&&... u) { // create the future uint64_t req = m_promises.CreateRequest(); @@ -157,22 +157,22 @@ class AsyncFunction final } template - future operator()(U&&... u) { + wpi::util::future operator()(U&&... u) { return Call(std::forward(u)...); } /** * Function called (on event loop thread) when the async is called. */ - std::function, T...)> wakeup; + std::function, T...)> wakeup; private: - wpi::mutex m_mutex; + wpi::util::mutex m_mutex; std::vector>> m_params; - PromiseFactory m_promises; + wpi::util::PromiseFactory m_promises; std::weak_ptr m_loop; }; -} // namespace wpi::uv +} // namespace wpi::net::uv #endif // WPINET_WPINET_SRC_MAIN_NATIVE_INCLUDE_WPI_NET_UV_ASYNCFUNCTION_HPP_ diff --git a/wpinet/src/main/native/include/wpi/net/uv/Buffer.hpp b/wpinet/src/main/native/include/wpi/net/uv/Buffer.hpp index bb187695ab..41437628cd 100644 --- a/wpinet/src/main/native/include/wpi/net/uv/Buffer.hpp +++ b/wpinet/src/main/native/include/wpi/net/uv/Buffer.hpp @@ -15,7 +15,7 @@ #include "wpi/util/SmallVector.hpp" -namespace wpi::uv { +namespace wpi::net::uv { /** * Data buffer. Convenience wrapper around uv_buf_t. @@ -167,10 +167,10 @@ class SimpleBufferPool { size_t Remaining() const { return m_pool.size(); } private: - SmallVector m_pool; + wpi::util::SmallVector m_pool; size_t m_size; // NOLINT }; -} // namespace wpi::uv +} // namespace wpi::net::uv #endif // WPINET_WPINET_SRC_MAIN_NATIVE_INCLUDE_WPI_NET_UV_BUFFER_HPP_ diff --git a/wpinet/src/main/native/include/wpi/net/uv/Check.hpp b/wpinet/src/main/native/include/wpi/net/uv/Check.hpp index 0144079b90..04c247eebd 100644 --- a/wpinet/src/main/native/include/wpi/net/uv/Check.hpp +++ b/wpinet/src/main/native/include/wpi/net/uv/Check.hpp @@ -12,7 +12,7 @@ #include "wpi/net/uv/Handle.hpp" #include "wpi/util/Signal.h" -namespace wpi::uv { +namespace wpi::net::uv { class Loop; @@ -57,9 +57,9 @@ class Check final : public HandleImpl { /** * Signal generated once per loop iteration after polling for I/O. */ - sig::Signal<> check; + wpi::util::sig::Signal<> check; }; -} // namespace wpi::uv +} // namespace wpi::net::uv #endif // WPINET_WPINET_SRC_MAIN_NATIVE_INCLUDE_WPI_NET_UV_CHECK_HPP_ diff --git a/wpinet/src/main/native/include/wpi/net/uv/Error.hpp b/wpinet/src/main/native/include/wpi/net/uv/Error.hpp index 51216a0257..fc79763391 100644 --- a/wpinet/src/main/native/include/wpi/net/uv/Error.hpp +++ b/wpinet/src/main/native/include/wpi/net/uv/Error.hpp @@ -7,7 +7,7 @@ #include -namespace wpi::uv { +namespace wpi::net::uv { /** * Error code. @@ -41,6 +41,6 @@ class Error { int m_err{0}; }; -} // namespace wpi::uv +} // namespace wpi::net::uv #endif // WPINET_WPINET_SRC_MAIN_NATIVE_INCLUDE_WPI_NET_UV_ERROR_HPP_ diff --git a/wpinet/src/main/native/include/wpi/net/uv/FsEvent.hpp b/wpinet/src/main/native/include/wpi/net/uv/FsEvent.hpp index b5ae73deb5..b480c5ba79 100644 --- a/wpinet/src/main/native/include/wpi/net/uv/FsEvent.hpp +++ b/wpinet/src/main/native/include/wpi/net/uv/FsEvent.hpp @@ -14,7 +14,7 @@ #include "wpi/net/uv/Handle.hpp" #include "wpi/util/Signal.h" -namespace wpi::uv { +namespace wpi::net::uv { class Loop; @@ -71,9 +71,9 @@ class FsEvent final : public HandleImpl { * relative to that directory). The second parameter is an ORed mask of * UV_RENAME and UV_CHANGE. */ - sig::Signal fsEvent; + wpi::util::sig::Signal fsEvent; }; -} // namespace wpi::uv +} // namespace wpi::net::uv #endif // WPINET_WPINET_SRC_MAIN_NATIVE_INCLUDE_WPI_NET_UV_FSEVENT_HPP_ diff --git a/wpinet/src/main/native/include/wpi/net/uv/GetAddrInfo.hpp b/wpinet/src/main/native/include/wpi/net/uv/GetAddrInfo.hpp index dbd44e33e3..3c8c20496b 100644 --- a/wpinet/src/main/native/include/wpi/net/uv/GetAddrInfo.hpp +++ b/wpinet/src/main/native/include/wpi/net/uv/GetAddrInfo.hpp @@ -16,7 +16,7 @@ #include "wpi/net/uv/Request.hpp" #include "wpi/util/Signal.h" -namespace wpi::uv { +namespace wpi::net::uv { class Loop; @@ -34,7 +34,7 @@ class GetAddrInfoReq : public RequestImpl { * Resolved lookup signal. * Parameter is resolved address info. */ - sig::Signal resolved; + wpi::util::sig::Signal resolved; }; /** @@ -115,6 +115,6 @@ inline void GetAddrInfo(const std::shared_ptr& loop, GetAddrInfo(*loop, std::move(callback), node, service, hints); } -} // namespace wpi::uv +} // namespace wpi::net::uv #endif // WPINET_WPINET_SRC_MAIN_NATIVE_INCLUDE_WPI_NET_UV_GETADDRINFO_HPP_ diff --git a/wpinet/src/main/native/include/wpi/net/uv/GetNameInfo.hpp b/wpinet/src/main/native/include/wpi/net/uv/GetNameInfo.hpp index 46a1499010..56101ca504 100644 --- a/wpinet/src/main/native/include/wpi/net/uv/GetNameInfo.hpp +++ b/wpinet/src/main/native/include/wpi/net/uv/GetNameInfo.hpp @@ -15,7 +15,7 @@ #include "wpi/net/uv/Request.hpp" #include "wpi/util/Signal.h" -namespace wpi::uv { +namespace wpi::net::uv { class Loop; @@ -33,7 +33,7 @@ class GetNameInfoReq : public RequestImpl { * Resolved lookup signal. * Parameters are hostname and service. */ - sig::Signal resolved; + wpi::util::sig::Signal resolved; }; /** @@ -222,6 +222,6 @@ inline void GetNameInfo6(const std::shared_ptr& loop, return GetNameInfo6(*loop, std::move(callback), ip, port, flags); } -} // namespace wpi::uv +} // namespace wpi::net::uv #endif // WPINET_WPINET_SRC_MAIN_NATIVE_INCLUDE_WPI_NET_UV_GETNAMEINFO_HPP_ diff --git a/wpinet/src/main/native/include/wpi/net/uv/Handle.hpp b/wpinet/src/main/native/include/wpi/net/uv/Handle.hpp index fbc3d95631..9ea645e0e4 100644 --- a/wpinet/src/main/native/include/wpi/net/uv/Handle.hpp +++ b/wpinet/src/main/native/include/wpi/net/uv/Handle.hpp @@ -18,11 +18,11 @@ #include "wpi/net/uv/Loop.hpp" #include "wpi/util/Signal.h" -namespace wpi { +namespace wpi::net { class Logger; -} // namespace wpi +} // namespace wpi::net -namespace wpi::uv { +namespace wpi::net::uv { /** * Handle. @@ -226,23 +226,23 @@ class Handle : public std::enable_shared_from_this { * Sets logger. * @param logger Logger */ - void SetLogger(Logger* logger) { m_logger = logger; } + void SetLogger(wpi::util::Logger* logger) { m_logger = logger; } /** * Gets logger. * @return Logger, or nullptr if none set */ - Logger* GetLogger() const { return m_logger; } + wpi::util::Logger* GetLogger() const { return m_logger; } /** * Error signal */ - sig::Signal error; + wpi::util::sig::Signal error; /** * Closed signal */ - sig::Signal<> closed; + wpi::util::sig::Signal<> closed; /** * Report an error. @@ -279,7 +279,7 @@ class Handle : public std::enable_shared_from_this { std::function m_allocBuf{&Buffer::Allocate}; std::function m_freeBuf{&DefaultFreeBuf}; std::shared_ptr m_data; - Logger* m_logger = nullptr; + wpi::util::Logger* m_logger = nullptr; }; /** @@ -309,6 +309,6 @@ class HandleImpl : public Handle { HandleImpl() : Handle{static_cast(std::malloc(sizeof(U)))} {} }; -} // namespace wpi::uv +} // namespace wpi::net::uv #endif // WPINET_WPINET_SRC_MAIN_NATIVE_INCLUDE_WPI_NET_UV_HANDLE_HPP_ diff --git a/wpinet/src/main/native/include/wpi/net/uv/Idle.hpp b/wpinet/src/main/native/include/wpi/net/uv/Idle.hpp index d4a6c79d0f..2a216d4fe0 100644 --- a/wpinet/src/main/native/include/wpi/net/uv/Idle.hpp +++ b/wpinet/src/main/native/include/wpi/net/uv/Idle.hpp @@ -12,7 +12,7 @@ #include "wpi/net/uv/Handle.hpp" #include "wpi/util/Signal.h" -namespace wpi::uv { +namespace wpi::net::uv { class Loop; @@ -66,9 +66,9 @@ class Idle final : public HandleImpl { /** * Signal generated once per loop iteration prior to Prepare signals. */ - sig::Signal<> idle; + wpi::util::sig::Signal<> idle; }; -} // namespace wpi::uv +} // namespace wpi::net::uv #endif // WPINET_WPINET_SRC_MAIN_NATIVE_INCLUDE_WPI_NET_UV_IDLE_HPP_ diff --git a/wpinet/src/main/native/include/wpi/net/uv/Loop.hpp b/wpinet/src/main/native/include/wpi/net/uv/Loop.hpp index bce2a7e5cd..66b4645192 100644 --- a/wpinet/src/main/native/include/wpi/net/uv/Loop.hpp +++ b/wpinet/src/main/native/include/wpi/net/uv/Loop.hpp @@ -18,7 +18,7 @@ #include "wpi/util/Signal.h" #include "wpi/util/function_ref.hpp" -namespace wpi::uv { +namespace wpi::net::uv { class Handle; @@ -186,7 +186,7 @@ class Loop final : public std::enable_shared_from_this { * * @param callback A function to be invoked once for each active handle. */ - void Walk(function_ref callback); + void Walk(wpi::util::function_ref callback); /** * Reinitialize any kernel state necessary in the child process after @@ -247,7 +247,7 @@ class Loop final : public std::enable_shared_from_this { /** * Error signal */ - sig::Signal error; + wpi::util::sig::Signal error; /** * Reports error. @@ -263,6 +263,6 @@ class Loop final : public std::enable_shared_from_this { bool m_closing = false; }; -} // namespace wpi::uv +} // namespace wpi::net::uv #endif // WPINET_WPINET_SRC_MAIN_NATIVE_INCLUDE_WPI_NET_UV_LOOP_HPP_ diff --git a/wpinet/src/main/native/include/wpi/net/uv/NetworkStream.hpp b/wpinet/src/main/native/include/wpi/net/uv/NetworkStream.hpp index 720caabd6c..790ef5797c 100644 --- a/wpinet/src/main/native/include/wpi/net/uv/NetworkStream.hpp +++ b/wpinet/src/main/native/include/wpi/net/uv/NetworkStream.hpp @@ -14,7 +14,7 @@ #include "wpi/net/uv/Stream.hpp" #include "wpi/util/Signal.h" -namespace wpi::uv { +namespace wpi::net::uv { class NetworkStream; @@ -32,7 +32,7 @@ class ConnectReq : public RequestImpl { /** * Connection completed signal. */ - sig::Signal<> connected; + wpi::util::sig::Signal<> connected; }; /** @@ -115,7 +115,7 @@ class NetworkStream : public Stream { /** * Signal generated when an incoming connection is received. */ - sig::Signal<> connection; + wpi::util::sig::Signal<> connection; protected: explicit NetworkStream(uv_stream_t* uv_stream) : Stream{uv_stream} {} @@ -148,6 +148,6 @@ class NetworkStreamImpl : public NetworkStream { : NetworkStream{static_cast(std::malloc(sizeof(U)))} {} }; -} // namespace wpi::uv +} // namespace wpi::net::uv #endif // WPINET_WPINET_SRC_MAIN_NATIVE_INCLUDE_WPI_NET_UV_NETWORKSTREAM_HPP_ diff --git a/wpinet/src/main/native/include/wpi/net/uv/Pipe.hpp b/wpinet/src/main/native/include/wpi/net/uv/Pipe.hpp index be5543ca02..dc9590ff02 100644 --- a/wpinet/src/main/native/include/wpi/net/uv/Pipe.hpp +++ b/wpinet/src/main/native/include/wpi/net/uv/Pipe.hpp @@ -14,7 +14,7 @@ #include "wpi/net/uv/NetworkStream.hpp" -namespace wpi::uv { +namespace wpi::net::uv { class Loop; class PipeConnectReq; @@ -203,6 +203,6 @@ class PipeConnectReq : public ConnectReq { } }; -} // namespace wpi::uv +} // namespace wpi::net::uv #endif // WPINET_WPINET_SRC_MAIN_NATIVE_INCLUDE_WPI_NET_UV_PIPE_HPP_ diff --git a/wpinet/src/main/native/include/wpi/net/uv/Poll.hpp b/wpinet/src/main/native/include/wpi/net/uv/Poll.hpp index db95635e45..0c648046ef 100644 --- a/wpinet/src/main/native/include/wpi/net/uv/Poll.hpp +++ b/wpinet/src/main/native/include/wpi/net/uv/Poll.hpp @@ -13,7 +13,7 @@ #include "wpi/net/uv/Handle.hpp" #include "wpi/util/Signal.h" -namespace wpi::uv { +namespace wpi::net::uv { class Loop; @@ -105,7 +105,7 @@ class Poll final : public HandleImpl { /** * Signal generated when a poll event occurs. */ - sig::Signal pollEvent; + wpi::util::sig::Signal pollEvent; private: struct ReuseData { @@ -117,6 +117,6 @@ class Poll final : public HandleImpl { std::unique_ptr m_reuseData; }; -} // namespace wpi::uv +} // namespace wpi::net::uv #endif // WPINET_WPINET_SRC_MAIN_NATIVE_INCLUDE_WPI_NET_UV_POLL_HPP_ diff --git a/wpinet/src/main/native/include/wpi/net/uv/Prepare.hpp b/wpinet/src/main/native/include/wpi/net/uv/Prepare.hpp index d0864260ee..c41e47e7c3 100644 --- a/wpinet/src/main/native/include/wpi/net/uv/Prepare.hpp +++ b/wpinet/src/main/native/include/wpi/net/uv/Prepare.hpp @@ -12,7 +12,7 @@ #include "wpi/net/uv/Handle.hpp" #include "wpi/util/Signal.h" -namespace wpi::uv { +namespace wpi::net::uv { class Loop; @@ -57,9 +57,9 @@ class Prepare final : public HandleImpl { /** * Signal generated once per loop iteration prior to polling for I/O. */ - sig::Signal<> prepare; + wpi::util::sig::Signal<> prepare; }; -} // namespace wpi::uv +} // namespace wpi::net::uv #endif // WPINET_WPINET_SRC_MAIN_NATIVE_INCLUDE_WPI_NET_UV_PREPARE_HPP_ diff --git a/wpinet/src/main/native/include/wpi/net/uv/Process.hpp b/wpinet/src/main/native/include/wpi/net/uv/Process.hpp index 15d6cbf621..341631076a 100644 --- a/wpinet/src/main/native/include/wpi/net/uv/Process.hpp +++ b/wpinet/src/main/native/include/wpi/net/uv/Process.hpp @@ -17,7 +17,7 @@ #include "wpi/util/Signal.h" #include "wpi/util/SmallVector.hpp" -namespace wpi::uv { +namespace wpi::net::uv { class Loop; class Pipe; @@ -70,7 +70,7 @@ class Process final : public HandleImpl { m_data.str = m_strData.c_str(); } - /*implicit*/ Option(const SmallVectorImpl& arg) // NOLINT + /*implicit*/ Option(const wpi::util::SmallVectorImpl& arg) // NOLINT : m_strData(arg.data(), arg.size()) { m_data.str = m_strData.c_str(); } @@ -302,9 +302,9 @@ class Process final : public HandleImpl { * Signal generated when the process exits. The parameters are the exit * status and the signal that caused the process to terminate, if any. */ - sig::Signal exited; + wpi::util::sig::Signal exited; }; -} // namespace wpi::uv +} // namespace wpi::net::uv #endif // WPINET_WPINET_SRC_MAIN_NATIVE_INCLUDE_WPI_NET_UV_PROCESS_HPP_ diff --git a/wpinet/src/main/native/include/wpi/net/uv/Request.hpp b/wpinet/src/main/native/include/wpi/net/uv/Request.hpp index fe6d1f0867..3c720f1d2d 100644 --- a/wpinet/src/main/native/include/wpi/net/uv/Request.hpp +++ b/wpinet/src/main/native/include/wpi/net/uv/Request.hpp @@ -13,7 +13,7 @@ #include "wpi/net/uv/Error.hpp" -namespace wpi::uv { +namespace wpi::net::uv { /** * Request. Requests are not moveable or copyable. @@ -166,6 +166,6 @@ class RequestImpl : public Request { U m_uv_req; }; -} // namespace wpi::uv +} // namespace wpi::net::uv #endif // WPINET_WPINET_SRC_MAIN_NATIVE_INCLUDE_WPI_NET_UV_REQUEST_HPP_ diff --git a/wpinet/src/main/native/include/wpi/net/uv/Signal.hpp b/wpinet/src/main/native/include/wpi/net/uv/Signal.hpp index 98deaec801..47981282c3 100644 --- a/wpinet/src/main/native/include/wpi/net/uv/Signal.hpp +++ b/wpinet/src/main/native/include/wpi/net/uv/Signal.hpp @@ -12,7 +12,7 @@ #include "wpi/net/uv/Handle.hpp" #include "wpi/util/Signal.h" -namespace wpi::uv { +namespace wpi::net::uv { class Loop; @@ -71,9 +71,9 @@ class Signal final : public HandleImpl { /** * Signal generated when a signal occurs. */ - sig::Signal signal; + wpi::util::sig::Signal signal; }; -} // namespace wpi::uv +} // namespace wpi::net::uv #endif // WPINET_WPINET_SRC_MAIN_NATIVE_INCLUDE_WPI_NET_UV_SIGNAL_HPP_ diff --git a/wpinet/src/main/native/include/wpi/net/uv/Stream.hpp b/wpinet/src/main/native/include/wpi/net/uv/Stream.hpp index 3def693db8..86058aa690 100644 --- a/wpinet/src/main/native/include/wpi/net/uv/Stream.hpp +++ b/wpinet/src/main/native/include/wpi/net/uv/Stream.hpp @@ -19,7 +19,7 @@ #include "wpi/net/uv/Request.hpp" #include "wpi/util/Signal.h" -namespace wpi::uv { +namespace wpi::net::uv { class Stream; @@ -37,7 +37,7 @@ class ShutdownReq : public RequestImpl { /** * Shutdown completed signal. */ - sig::Signal<> complete; + wpi::util::sig::Signal<> complete; }; /** @@ -55,7 +55,7 @@ class WriteReq : public RequestImpl { * Write completed signal. This is called even if an error occurred. * @param err error value */ - sig::Signal finish; + wpi::util::sig::Signal finish; }; /** @@ -293,12 +293,12 @@ class Stream : public Handle { /** * Signal generated when data was read on a stream. */ - sig::Signal data; + wpi::util::sig::Signal data; /** * Signal generated when no more read data is available. */ - sig::Signal<> end; + wpi::util::sig::Signal<> end; protected: explicit Stream(uv_stream_t* uv_stream) @@ -329,6 +329,6 @@ class StreamImpl : public Stream { StreamImpl() : Stream{static_cast(std::malloc(sizeof(U)))} {} }; -} // namespace wpi::uv +} // namespace wpi::net::uv #endif // WPINET_WPINET_SRC_MAIN_NATIVE_INCLUDE_WPI_NET_UV_STREAM_HPP_ diff --git a/wpinet/src/main/native/include/wpi/net/uv/Tcp.hpp b/wpinet/src/main/native/include/wpi/net/uv/Tcp.hpp index f68b184452..459c8b84dc 100644 --- a/wpinet/src/main/native/include/wpi/net/uv/Tcp.hpp +++ b/wpinet/src/main/native/include/wpi/net/uv/Tcp.hpp @@ -15,7 +15,7 @@ #include "wpi/net/uv/NetworkStream.hpp" -namespace wpi::uv { +namespace wpi::net::uv { class Loop; class TcpConnectReq; @@ -366,6 +366,6 @@ class TcpConnectReq : public ConnectReq { } }; -} // namespace wpi::uv +} // namespace wpi::net::uv #endif // WPINET_WPINET_SRC_MAIN_NATIVE_INCLUDE_WPI_NET_UV_TCP_HPP_ diff --git a/wpinet/src/main/native/include/wpi/net/uv/Timer.hpp b/wpinet/src/main/native/include/wpi/net/uv/Timer.hpp index 6e39043455..5f3b1caa2e 100644 --- a/wpinet/src/main/native/include/wpi/net/uv/Timer.hpp +++ b/wpinet/src/main/native/include/wpi/net/uv/Timer.hpp @@ -15,7 +15,7 @@ #include "wpi/net/uv/Handle.hpp" #include "wpi/util/Signal.h" -namespace wpi::uv { +namespace wpi::net::uv { class Loop; @@ -136,9 +136,9 @@ class Timer final : public HandleImpl { /** * Signal generated when the timeout event occurs. */ - sig::Signal<> timeout; + wpi::util::sig::Signal<> timeout; }; -} // namespace wpi::uv +} // namespace wpi::net::uv #endif // WPINET_WPINET_SRC_MAIN_NATIVE_INCLUDE_WPI_NET_UV_TIMER_HPP_ diff --git a/wpinet/src/main/native/include/wpi/net/uv/Tty.hpp b/wpinet/src/main/native/include/wpi/net/uv/Tty.hpp index 06a21bf3c1..89ebeb68c8 100644 --- a/wpinet/src/main/native/include/wpi/net/uv/Tty.hpp +++ b/wpinet/src/main/native/include/wpi/net/uv/Tty.hpp @@ -12,7 +12,7 @@ #include "wpi/net/uv/Stream.hpp" -namespace wpi::uv { +namespace wpi::net::uv { class Loop; class Tty; @@ -80,6 +80,6 @@ class Tty final : public StreamImpl { } }; -} // namespace wpi::uv +} // namespace wpi::net::uv #endif // WPINET_WPINET_SRC_MAIN_NATIVE_INCLUDE_WPI_NET_UV_TTY_HPP_ diff --git a/wpinet/src/main/native/include/wpi/net/uv/Udp.hpp b/wpinet/src/main/native/include/wpi/net/uv/Udp.hpp index 6a7b32e08b..8185ec44dd 100644 --- a/wpinet/src/main/native/include/wpi/net/uv/Udp.hpp +++ b/wpinet/src/main/native/include/wpi/net/uv/Udp.hpp @@ -17,7 +17,7 @@ #include "wpi/net/uv/Request.hpp" #include "wpi/util/Signal.h" -namespace wpi::uv { +namespace wpi::net::uv { class Loop; class Udp; @@ -35,7 +35,7 @@ class UdpSendReq : public RequestImpl { * Send completed signal. This is called even if an error occurred. * @param err error value */ - sig::Signal complete; + wpi::util::sig::Signal complete; }; /** @@ -390,9 +390,9 @@ class Udp final : public HandleImpl { * Signal generated for each incoming datagram. Parameters are the buffer, * the number of bytes received, the address of the sender, and flags. */ - sig::Signal received; + wpi::util::sig::Signal received; }; -} // namespace wpi::uv +} // namespace wpi::net::uv #endif // WPINET_WPINET_SRC_MAIN_NATIVE_INCLUDE_WPI_NET_UV_UDP_HPP_ diff --git a/wpinet/src/main/native/include/wpi/net/uv/Work.hpp b/wpinet/src/main/native/include/wpi/net/uv/Work.hpp index 645bc220ff..258cc92f6c 100644 --- a/wpinet/src/main/native/include/wpi/net/uv/Work.hpp +++ b/wpinet/src/main/native/include/wpi/net/uv/Work.hpp @@ -14,7 +14,7 @@ #include "wpi/net/uv/Request.hpp" #include "wpi/util/Signal.h" -namespace wpi::uv { +namespace wpi::net::uv { class Loop; @@ -31,13 +31,13 @@ class WorkReq : public RequestImpl { /** * Function(s) that will be run on the thread pool. */ - sig::Signal<> work; + wpi::util::sig::Signal<> work; /** * Function(s) that will be run on the loop thread after the work on the * thread pool has been completed by the work callback. */ - sig::Signal<> afterWork; + wpi::util::sig::Signal<> afterWork; }; /** @@ -88,6 +88,6 @@ inline void QueueWork(const std::shared_ptr& loop, QueueWork(*loop, std::move(work), std::move(afterWork)); } -} // namespace wpi::uv +} // namespace wpi::net::uv #endif // WPINET_WPINET_SRC_MAIN_NATIVE_INCLUDE_WPI_NET_UV_WORK_HPP_ diff --git a/wpinet/src/main/native/include/wpi/net/uv/util.hpp b/wpinet/src/main/native/include/wpi/net/uv/util.hpp index 08cc844928..fa9b86f2f3 100644 --- a/wpinet/src/main/native/include/wpi/net/uv/util.hpp +++ b/wpinet/src/main/native/include/wpi/net/uv/util.hpp @@ -14,7 +14,7 @@ #pragma comment(lib, "Ws2_32.lib") #endif -namespace wpi::uv { +namespace wpi::net::uv { namespace detail { template @@ -153,6 +153,6 @@ int NameToAddr(std::string_view ip, in_addr* addr); */ int NameToAddr(std::string_view ip, in6_addr* addr); -} // namespace wpi::uv +} // namespace wpi::net::uv #endif // WPINET_WPINET_SRC_MAIN_NATIVE_INCLUDE_WPI_NET_UV_UTIL_HPP_ diff --git a/wpinet/src/main/native/linux/AvahiClient.cpp b/wpinet/src/main/native/linux/AvahiClient.cpp index e039f6f200..10c91200c9 100644 --- a/wpinet/src/main/native/linux/AvahiClient.cpp +++ b/wpinet/src/main/native/linux/AvahiClient.cpp @@ -10,7 +10,7 @@ #include "dlfcn.h" -using namespace wpi; +using namespace wpi::net; #define AvahiFunctionLoad(snake_name) \ do { \ @@ -73,7 +73,7 @@ AvahiFunctionTable& AvahiFunctionTable::Get() { return table; } -static wpi::mutex ThreadLoopLock; +static wpi::util::mutex ThreadLoopLock; static std::weak_ptr ThreadLoop; std::shared_ptr AvahiThread::Get() { diff --git a/wpinet/src/main/native/linux/AvahiClient.hpp b/wpinet/src/main/native/linux/AvahiClient.hpp index 1ed93a8b58..ede5276411 100644 --- a/wpinet/src/main/native/linux/AvahiClient.hpp +++ b/wpinet/src/main/native/linux/AvahiClient.hpp @@ -223,7 +223,7 @@ enum { AVAHI_ERR_MAX = -54 }; -namespace wpi { +namespace wpi::net { class AvahiFunctionTable { public: #define AvahiFunction(CapName, RetType, Parameters) \ @@ -319,4 +319,4 @@ class AvahiThread { AvahiFunctionTable& table = AvahiFunctionTable::Get(); }; -} // namespace wpi +} // namespace wpi::net diff --git a/wpinet/src/main/native/linux/MulticastServiceAnnouncer.cpp b/wpinet/src/main/native/linux/MulticastServiceAnnouncer.cpp index 9d944c11fa..8ebd9d7fdb 100644 --- a/wpinet/src/main/native/linux/MulticastServiceAnnouncer.cpp +++ b/wpinet/src/main/native/linux/MulticastServiceAnnouncer.cpp @@ -14,7 +14,7 @@ #include "AvahiClient.hpp" #include "wpi/util/mutex.hpp" -using namespace wpi; +using namespace wpi::net; struct MulticastServiceAnnouncer::Impl { AvahiFunctionTable& table = AvahiFunctionTable::Get(); diff --git a/wpinet/src/main/native/linux/MulticastServiceResolver.cpp b/wpinet/src/main/native/linux/MulticastServiceResolver.cpp index dfe921fb5f..0b6bb7b879 100644 --- a/wpinet/src/main/native/linux/MulticastServiceResolver.cpp +++ b/wpinet/src/main/native/linux/MulticastServiceResolver.cpp @@ -15,7 +15,7 @@ #include "wpi/util/StringExtras.hpp" #include "wpi/util/mutex.hpp" -using namespace wpi; +using namespace wpi::net; struct MulticastServiceResolver::Impl { AvahiFunctionTable& table = AvahiFunctionTable::Get(); @@ -88,12 +88,12 @@ static void ResolveCallback(AvahiServiceResolver* r, AvahiIfIndex interface, // Todo make this just do key continue; } - std::string_view key = wpi::substr(value, 0, splitIndex); + std::string_view key = wpi::util::substr(value, 0, splitIndex); value = - wpi::substr(value, splitIndex + 1, value.size() - splitIndex - 1); + wpi::util::substr(value, splitIndex + 1, value.size() - splitIndex - 1); data.txt.emplace_back(std::pair{key, value}); } - wpi::SmallString<256> outputHostName; + wpi::util::SmallString<256> outputHostName; char label[256]; do { impl->table.unescape_label(&host_name, label, sizeof(label)); diff --git a/wpinet/src/main/native/macOS/MulticastServiceAnnouncer.cpp b/wpinet/src/main/native/macOS/MulticastServiceAnnouncer.cpp index 043dae19fd..a7526f9975 100644 --- a/wpinet/src/main/native/macOS/MulticastServiceAnnouncer.cpp +++ b/wpinet/src/main/native/macOS/MulticastServiceAnnouncer.cpp @@ -13,7 +13,7 @@ #include "dns_sd.h" #include "wpi/util/SmallString.hpp" -using namespace wpi; +using namespace wpi::net; struct MulticastServiceAnnouncer::Impl { std::string serviceName; @@ -57,7 +57,7 @@ MulticastServiceAnnouncer::MulticastServiceAnnouncer( pImpl->serviceType = serviceType; pImpl->port = port; - wpi::SmallString<64> key; + wpi::util::SmallString<64> key; for (auto&& i : txt) { key.clear(); diff --git a/wpinet/src/main/native/macOS/MulticastServiceResolver.cpp b/wpinet/src/main/native/macOS/MulticastServiceResolver.cpp index 2b668a6478..3c676721be 100644 --- a/wpinet/src/main/native/macOS/MulticastServiceResolver.cpp +++ b/wpinet/src/main/native/macOS/MulticastServiceResolver.cpp @@ -20,7 +20,7 @@ #include "dns_sd.h" #include "wpi/util/SmallVector.hpp" -using namespace wpi; +using namespace wpi::net; struct DnsResolveState { DnsResolveState(MulticastServiceResolver::Impl* impl, @@ -214,17 +214,17 @@ void MulticastServiceResolver::Stop() { if (!pImpl->serviceRef) { return; } - wpi::SmallVector cleanupEvents; + wpi::util::SmallVector cleanupEvents; for (auto&& i : pImpl->ResolveStates) { cleanupEvents.push_back( pImpl->thread->RemoveServiceRefOutsideThread(i->ResolveRef)); } cleanupEvents.push_back( pImpl->thread->RemoveServiceRefOutsideThread(pImpl->serviceRef)); - wpi::SmallVector signaledBuf; + wpi::util::SmallVector signaledBuf; signaledBuf.resize(cleanupEvents.size()); while (!cleanupEvents.empty()) { - auto signaled = wpi::WaitForObjects(cleanupEvents, signaledBuf); + auto signaled = wpi::util::WaitForObjects(cleanupEvents, signaledBuf); for (auto&& s : signaled) { cleanupEvents.erase( std::find(cleanupEvents.begin(), cleanupEvents.end(), s)); diff --git a/wpinet/src/main/native/macOS/ResolverThread.cpp b/wpinet/src/main/native/macOS/ResolverThread.cpp index a5ac1e1c4d..d275441081 100644 --- a/wpinet/src/main/native/macOS/ResolverThread.cpp +++ b/wpinet/src/main/native/macOS/ResolverThread.cpp @@ -13,7 +13,7 @@ #include "wpi/util/mutex.hpp" -using namespace wpi; +using namespace wpi::net; ResolverThread::ResolverThread(const private_init&) {} @@ -62,7 +62,7 @@ bool ResolverThread::CleanupRefs() { std::find_if(serviceRefs.begin(), serviceRefs.end(), [=](auto& a) { return a.first == r.first; })); DNSServiceRefDeallocate(r.first); - wpi::SetEvent(r.second); + wpi::util::SetEvent(r.second); } serviceRefsToRemove.clear(); return serviceRefs.empty(); @@ -102,7 +102,7 @@ void ResolverThread::ThreadMain() { } } -static wpi::mutex ThreadLoopLock; +static wpi::util::mutex ThreadLoopLock; static std::weak_ptr ThreadLoop; std::shared_ptr ResolverThread::Get() { diff --git a/wpinet/src/main/native/macOS/ResolverThread.hpp b/wpinet/src/main/native/macOS/ResolverThread.hpp index d141854d6c..d03e495e4e 100644 --- a/wpinet/src/main/native/macOS/ResolverThread.hpp +++ b/wpinet/src/main/native/macOS/ResolverThread.hpp @@ -19,7 +19,7 @@ #include "wpi/util/Synchronization.h" #include "wpi/util/mutex.hpp" -namespace wpi { +namespace wpi::net { class ResolverThread { private: struct private_init {}; @@ -38,12 +38,12 @@ class ResolverThread { void ThreadMain(); bool CleanupRefs(); - wpi::mutex serviceRefMutex; + wpi::util::mutex serviceRefMutex; std::vector> serviceRefsToRemove; std::vector> serviceRefs; std::thread thread; std::atomic_bool running; }; -} // namespace wpi +} // namespace wpi::net #endif // defined(__APPLE__) diff --git a/wpinet/src/main/native/thirdparty/tcpsockets/cpp/TCPAcceptor.cpp b/wpinet/src/main/native/thirdparty/tcpsockets/cpp/TCPAcceptor.cpp index 743a9aaef2..c7ecdb8f3e 100644 --- a/wpinet/src/main/native/thirdparty/tcpsockets/cpp/TCPAcceptor.cpp +++ b/wpinet/src/main/native/thirdparty/tcpsockets/cpp/TCPAcceptor.cpp @@ -43,9 +43,9 @@ #include "wpi/net/SocketError.hpp" -using namespace wpi; +using namespace wpi::net; -TCPAcceptor::TCPAcceptor(int port, std::string_view address, Logger& logger) +TCPAcceptor::TCPAcceptor(int port, std::string_view address, wpi::util::Logger& logger) : m_lsd(0), m_port(port), m_address(address), @@ -89,7 +89,7 @@ int TCPAcceptor::start() { address.sin_family = PF_INET; if (m_address.size() > 0) { #ifdef _WIN32 - SmallString<128> addr_copy(m_address); + wpi::util::SmallString<128> addr_copy(m_address); addr_copy.push_back('\0'); int res = InetPton(PF_INET, addr_copy.data(), &(address.sin_addr)); #else @@ -143,7 +143,7 @@ void TCPAcceptor::shutdown() { std::memset(&address, 0, sizeof(address)); address.sin_family = PF_INET; - SmallString<128> addr_copy; + wpi::util::SmallString<128> addr_copy; if (m_address.size() > 0) addr_copy = m_address; else diff --git a/wpinet/src/main/native/thirdparty/tcpsockets/cpp/TCPConnector.cpp b/wpinet/src/main/native/thirdparty/tcpsockets/cpp/TCPConnector.cpp index db17dfd37b..73d55c0dde 100644 --- a/wpinet/src/main/native/thirdparty/tcpsockets/cpp/TCPConnector.cpp +++ b/wpinet/src/main/native/thirdparty/tcpsockets/cpp/TCPConnector.cpp @@ -46,7 +46,7 @@ #include "wpi/net/SocketError.hpp" #include "wpi/net/TCPStream.h" -using namespace wpi; +using namespace wpi::net; static int ResolveHostName(const char* hostname, struct in_addr* addr) { struct addrinfo hints; @@ -71,7 +71,7 @@ static int ResolveHostName(const char* hostname, struct in_addr* addr) { } std::unique_ptr TCPConnector::connect(const char* server, - int port, Logger& logger, + int port, wpi::util::Logger& logger, int timeout) { #ifdef _WIN32 struct WSAHelper { @@ -90,7 +90,7 @@ std::unique_ptr TCPConnector::connect(const char* server, address.sin_family = AF_INET; if (ResolveHostName(server, &(address.sin_addr)) != 0) { #ifdef _WIN32 - SmallString<128> addr_copy(server); + wpi::util::SmallString<128> addr_copy(server); addr_copy.push_back('\0'); int res = InetPton(PF_INET, addr_copy.data(), &(address.sin_addr)); #else diff --git a/wpinet/src/main/native/thirdparty/tcpsockets/cpp/TCPConnector_parallel.cpp b/wpinet/src/main/native/thirdparty/tcpsockets/cpp/TCPConnector_parallel.cpp index 94ab2079a7..c7c91cfe85 100644 --- a/wpinet/src/main/native/thirdparty/tcpsockets/cpp/TCPConnector_parallel.cpp +++ b/wpinet/src/main/native/thirdparty/tcpsockets/cpp/TCPConnector_parallel.cpp @@ -13,10 +13,10 @@ #include "wpi/util/condition_variable.hpp" #include "wpi/util/mutex.hpp" -using namespace wpi; +using namespace wpi::net; std::unique_ptr TCPConnector::connect_parallel( - std::span> servers, Logger& logger, + std::span> servers, wpi::util::Logger& logger, int timeout) { if (servers.empty()) { return nullptr; @@ -24,8 +24,8 @@ std::unique_ptr TCPConnector::connect_parallel( // structure to make sure we don't start duplicate workers struct GlobalState { - wpi::mutex mtx; - SmallSet, 16> active; + wpi::util::mutex mtx; + wpi::util::SmallSet, 16> active; }; static auto global = std::make_shared(); auto this_id = std::this_thread::get_id(); @@ -33,8 +33,8 @@ std::unique_ptr TCPConnector::connect_parallel( // structure shared between threads and this function struct Result { - wpi::mutex mtx; - wpi::condition_variable cv; + wpi::util::mutex mtx; + wpi::util::condition_variable cv; std::unique_ptr stream; std::atomic count{0}; std::atomic done{false}; @@ -42,7 +42,7 @@ std::unique_ptr TCPConnector::connect_parallel( auto result = std::make_shared(); // start worker threads; this is I/O bound so we don't limit to # of procs - Logger* plogger = &logger; + wpi::util::Logger* plogger = &logger; unsigned int num_workers = 0; for (const auto& server : servers) { std::pair server_copy{std::string{server.first}, diff --git a/wpinet/src/main/native/thirdparty/tcpsockets/cpp/TCPStream.cpp b/wpinet/src/main/native/thirdparty/tcpsockets/cpp/TCPStream.cpp index 082b2a7a54..e8c10ea029 100644 --- a/wpinet/src/main/native/thirdparty/tcpsockets/cpp/TCPStream.cpp +++ b/wpinet/src/main/native/thirdparty/tcpsockets/cpp/TCPStream.cpp @@ -38,7 +38,7 @@ #include "wpi/util/StringExtras.hpp" -using namespace wpi; +using namespace wpi::net; TCPStream::TCPStream(int sd, sockaddr_in* address) : m_sd(sd), m_blocking(true) { @@ -87,7 +87,7 @@ size_t TCPStream::send(const char* buffer, size_t len, Error* err) { } if (!result) { char Buffer[128]; - wpi::format_to_n_c_str(Buffer, sizeof(Buffer), + wpi::util::format_to_n_c_str(Buffer, sizeof(Buffer), "Send() failed: WSA error={}\n", WSAGetLastError()); OutputDebugStringA(Buffer); diff --git a/wpinet/src/main/native/thirdparty/tcpsockets/include/wpi/net/TCPAcceptor.h b/wpinet/src/main/native/thirdparty/tcpsockets/include/wpi/net/TCPAcceptor.h index d1fe60eaa7..7cad7d2a43 100644 --- a/wpinet/src/main/native/thirdparty/tcpsockets/include/wpi/net/TCPAcceptor.h +++ b/wpinet/src/main/native/thirdparty/tcpsockets/include/wpi/net/TCPAcceptor.h @@ -32,7 +32,7 @@ #include "wpi/net/NetworkAcceptor.hpp" #include "wpi/net/TCPStream.h" -namespace wpi { +namespace wpi::net { class Logger; @@ -42,10 +42,10 @@ class TCPAcceptor : public NetworkAcceptor { std::string m_address; bool m_listening; std::atomic_bool m_shutdown; - Logger& m_logger; + wpi::util::Logger& m_logger; public: - TCPAcceptor(int port, std::string_view address, Logger& logger); + TCPAcceptor(int port, std::string_view address, wpi::util::Logger& logger); ~TCPAcceptor() override; int start() override; @@ -53,6 +53,6 @@ class TCPAcceptor : public NetworkAcceptor { std::unique_ptr accept() override; }; -} // namespace wpi +} // namespace wpi::net #endif // WPINET_TCPACCEPTOR_H_ diff --git a/wpinet/src/main/native/thirdparty/tcpsockets/include/wpi/net/TCPConnector.h b/wpinet/src/main/native/thirdparty/tcpsockets/include/wpi/net/TCPConnector.h index 5dc09c8b37..1a3e094cc1 100644 --- a/wpinet/src/main/native/thirdparty/tcpsockets/include/wpi/net/TCPConnector.h +++ b/wpinet/src/main/native/thirdparty/tcpsockets/include/wpi/net/TCPConnector.h @@ -30,20 +30,20 @@ #include "wpi/net/NetworkStream.hpp" -namespace wpi { +namespace wpi::net { class Logger; class TCPConnector { public: static std::unique_ptr connect(const char* server, int port, - Logger& logger, + wpi::util::Logger& logger, int timeout = 0); static std::unique_ptr connect_parallel( - std::span> servers, Logger& logger, + std::span> servers, wpi::util::Logger& logger, int timeout = 0); }; -} // namespace wpi +} // namespace wpi::net #endif // WPINET_TCPCONNECTOR_H_ diff --git a/wpinet/src/main/native/thirdparty/tcpsockets/include/wpi/net/TCPStream.h b/wpinet/src/main/native/thirdparty/tcpsockets/include/wpi/net/TCPStream.h index d8959bfe54..43e37af31a 100644 --- a/wpinet/src/main/native/thirdparty/tcpsockets/include/wpi/net/TCPStream.h +++ b/wpinet/src/main/native/thirdparty/tcpsockets/include/wpi/net/TCPStream.h @@ -32,7 +32,7 @@ struct sockaddr_in; -namespace wpi { +namespace wpi::net { class TCPStream : public NetworkStream { int m_sd; @@ -67,6 +67,6 @@ class TCPStream : public NetworkStream { TCPStream() = delete; }; -} // namespace wpi +} // namespace wpi::net #endif // WPINET_TCPSTREAM_H_ diff --git a/wpinet/src/main/native/windows/DynamicDns.cpp b/wpinet/src/main/native/windows/DynamicDns.cpp index cf9458d00c..6bad3dfad3 100644 --- a/wpinet/src/main/native/windows/DynamicDns.cpp +++ b/wpinet/src/main/native/windows/DynamicDns.cpp @@ -4,7 +4,7 @@ #include "DynamicDns.hpp" -using namespace wpi; +using namespace wpi::net; DynamicDns& DynamicDns::GetDynamicDns() { static DynamicDns dns; diff --git a/wpinet/src/main/native/windows/DynamicDns.hpp b/wpinet/src/main/native/windows/DynamicDns.hpp index c8bee04a5a..0caf328ef3 100644 --- a/wpinet/src/main/native/windows/DynamicDns.hpp +++ b/wpinet/src/main/native/windows/DynamicDns.hpp @@ -12,7 +12,7 @@ #include -namespace wpi { +namespace wpi::net { class DynamicDns { public: using DnsServiceFreeInstanceFunc = @@ -56,4 +56,4 @@ class DynamicDns { private: DynamicDns(); }; -} // namespace wpi +} // namespace wpi::net diff --git a/wpinet/src/main/native/windows/MulticastServiceAnnouncer.cpp b/wpinet/src/main/native/windows/MulticastServiceAnnouncer.cpp index ecdf1d7c87..e7db046596 100644 --- a/wpinet/src/main/native/windows/MulticastServiceAnnouncer.cpp +++ b/wpinet/src/main/native/windows/MulticastServiceAnnouncer.cpp @@ -20,10 +20,10 @@ #include "wpi/util/SmallVector.hpp" #include "wpi/util/StringExtras.hpp" -using namespace wpi; +using namespace wpi::net; struct ImplBase { - wpi::DynamicDns& dynamicDns = wpi::DynamicDns::GetDynamicDns(); + wpi::net::DynamicDns& dynamicDns = wpi::net::DynamicDns::GetDynamicDns(); PDNS_SERVICE_INSTANCE serviceInstance = nullptr; HANDLE event = nullptr; }; @@ -53,16 +53,16 @@ MulticastServiceAnnouncer::Impl::Impl(std::string_view serviceName, this->port = port; - wpi::SmallVector wideStorage; - std::string hostName = wpi::GetHostname() + ".local"; + wpi::util::SmallVector wideStorage; + std::string hostName = wpi::net::GetHostname() + ".local"; for (auto&& i : txt) { wideStorage.clear(); - wpi::sys::windows::UTF8ToUTF16(i.first, wideStorage); + wpi::util::sys::windows::UTF8ToUTF16(i.first, wideStorage); this->keys.emplace_back( std::wstring{wideStorage.data(), wideStorage.size()}); wideStorage.clear(); - wpi::sys::windows::UTF8ToUTF16(i.second, wideStorage); + wpi::util::sys::windows::UTF8ToUTF16(i.second, wideStorage); this->values.emplace_back( std::wstring{wideStorage.data(), wideStorage.size()}); } @@ -72,21 +72,21 @@ MulticastServiceAnnouncer::Impl::Impl(std::string_view serviceName, this->valuePtrs.emplace_back(this->values[i].c_str()); } - wpi::SmallString<128> storage; + wpi::util::SmallString<128> storage; wideStorage.clear(); - wpi::sys::windows::UTF8ToUTF16(hostName, wideStorage); + wpi::util::sys::windows::UTF8ToUTF16(hostName, wideStorage); this->hostName = std::wstring{wideStorage.data(), wideStorage.size()}; wideStorage.clear(); - if (wpi::ends_with_lower(serviceType, ".local")) { - wpi::sys::windows::UTF8ToUTF16(serviceType, wideStorage); + if (wpi::util::ends_with_lower(serviceType, ".local")) { + wpi::util::sys::windows::UTF8ToUTF16(serviceType, wideStorage); } else { storage.clear(); storage.append(serviceType); storage.append(".local"); - wpi::sys::windows::UTF8ToUTF16(storage.str(), wideStorage); + wpi::util::sys::windows::UTF8ToUTF16(storage.str(), wideStorage); } this->serviceType = std::wstring{wideStorage.data(), wideStorage.size()}; @@ -95,11 +95,11 @@ MulticastServiceAnnouncer::Impl::Impl(std::string_view serviceName, storage.append(serviceName); storage.append("."); storage.append(serviceType); - if (!wpi::ends_with_lower(serviceType, ".local")) { + if (!wpi::util::ends_with_lower(serviceType, ".local")) { storage.append(".local"); } - wpi::sys::windows::UTF8ToUTF16(storage.str(), wideStorage); + wpi::util::sys::windows::UTF8ToUTF16(storage.str(), wideStorage); this->serviceInstanceName = std::wstring{wideStorage.data(), wideStorage.size()}; } diff --git a/wpinet/src/main/native/windows/MulticastServiceResolver.cpp b/wpinet/src/main/native/windows/MulticastServiceResolver.cpp index 8826e3fa43..ee1b5972db 100644 --- a/wpinet/src/main/native/windows/MulticastServiceResolver.cpp +++ b/wpinet/src/main/native/windows/MulticastServiceResolver.cpp @@ -20,10 +20,10 @@ #pragma comment(lib, "dnsapi") -using namespace wpi; +using namespace wpi::net; struct MulticastServiceResolver::Impl { - wpi::DynamicDns& dynamicDns = wpi::DynamicDns::GetDynamicDns(); + wpi::net::DynamicDns& dynamicDns = wpi::net::DynamicDns::GetDynamicDns(); std::wstring serviceType; DNS_SERVICE_CANCEL serviceCancel{nullptr}; @@ -43,15 +43,15 @@ MulticastServiceResolver::MulticastServiceResolver( return; } - wpi::SmallVector wideStorage; + wpi::util::SmallVector wideStorage; - if (wpi::ends_with_lower(serviceType, ".local")) { - wpi::sys::windows::UTF8ToUTF16(serviceType, wideStorage); + if (wpi::util::ends_with_lower(serviceType, ".local")) { + wpi::util::sys::windows::UTF8ToUTF16(serviceType, wideStorage); } else { - wpi::SmallString<128> storage; + wpi::util::SmallString<128> storage; storage.append(serviceType); storage.append(".local"); - wpi::sys::windows::UTF8ToUTF16(storage.str(), wideStorage); + wpi::util::sys::windows::UTF8ToUTF16(storage.str(), wideStorage); } pImpl->serviceType = std::wstring{wideStorage.data(), wideStorage.size()}; } @@ -92,10 +92,10 @@ static _Function_class_(DNS_QUERY_COMPLETION_ROUTINE) VOID WINAPI MulticastServiceResolver::Impl* impl = reinterpret_cast(pQueryContext); - wpi::SmallVector PtrRecords; - wpi::SmallVector SrvRecords; - wpi::SmallVector TxtRecords; - wpi::SmallVector ARecords; + wpi::util::SmallVector PtrRecords; + wpi::util::SmallVector SrvRecords; + wpi::util::SmallVector TxtRecords; + wpi::util::SmallVector ARecords; { DNS_RECORDW* current = pQueryResults->pQueryRecords; @@ -140,7 +140,7 @@ static _Function_class_(DNS_QUERY_COMPLETION_ROUTINE) VOID WINAPI if (std::wstring_view{A->pName} == std::wstring_view{foundSrv->Data.Srv.pNameTarget}) { MulticastServiceResolver::ServiceData data; - wpi::SmallString<128> storage; + wpi::util::SmallString<128> storage; for (DNS_RECORDW* Txt : TxtRecords) { if (std::wstring_view{Txt->pName} == nameHost) { for (DWORD i = 0; i < Txt->Data.Txt.dwStringCount; i++) { @@ -151,41 +151,41 @@ static _Function_class_(DNS_QUERY_COMPLETION_ROUTINE) VOID WINAPI continue; } storage.clear(); - std::span wideStr{ - reinterpret_cast(wideView.data()), + std::span wideStr{ + reinterpret_cast(wideView.data()), splitIndex}; - wpi::convertUTF16ToUTF8String(wideStr, storage); + wpi::util::convertUTF16ToUTF8String(wideStr, storage); auto& pair = data.txt.emplace_back(std::pair{ std::string{storage}, {}}); storage.clear(); - wideStr = std::span{ - reinterpret_cast(wideView.data() + + wideStr = std::span{ + reinterpret_cast(wideView.data() + splitIndex + 1), wideView.size() - splitIndex - 1}; - wpi::convertUTF16ToUTF8String(wideStr, storage); + wpi::util::convertUTF16ToUTF8String(wideStr, storage); pair.second = std::string{storage}; } } } storage.clear(); - std::span wideHostName{ - reinterpret_cast(A->pName), wcslen(A->pName)}; - wpi::convertUTF16ToUTF8String(wideHostName, storage); + std::span wideHostName{ + reinterpret_cast(A->pName), wcslen(A->pName)}; + wpi::util::convertUTF16ToUTF8String(wideHostName, storage); storage.append("."); data.hostName = std::string{storage}; storage.clear(); int len = nameHost.find(impl->serviceType.c_str()); - std::span wideServiceName{ - reinterpret_cast(nameHost.data()), + std::span wideServiceName{ + reinterpret_cast(nameHost.data()), nameHost.size()}; if (len != nameHost.npos) { wideServiceName = wideServiceName.subspan(0, len - 1); } - wpi::convertUTF16ToUTF8String(wideServiceName, storage); + wpi::util::convertUTF16ToUTF8String(wideServiceName, storage); data.serviceName = std::string{storage}; data.port = ntohs(foundSrv->Data.Srv.wPort); diff --git a/wpinet/src/main/python/semiwrap/PortForwarder.yml b/wpinet/src/main/python/semiwrap/PortForwarder.yml index 64e172eae9..6c80be7140 100644 --- a/wpinet/src/main/python/semiwrap/PortForwarder.yml +++ b/wpinet/src/main/python/semiwrap/PortForwarder.yml @@ -1,5 +1,5 @@ classes: - wpi::PortForwarder: + wpi::net::PortForwarder: nodelete: true methods: GetInstance: diff --git a/wpinet/src/main/python/semiwrap/WebServer.yml b/wpinet/src/main/python/semiwrap/WebServer.yml index 61ac088751..192ae17913 100644 --- a/wpinet/src/main/python/semiwrap/WebServer.yml +++ b/wpinet/src/main/python/semiwrap/WebServer.yml @@ -1,5 +1,5 @@ classes: - wpi::WebServer: + wpi::net::WebServer: nodelete: true methods: GetInstance: diff --git a/wpinet/src/netconsoleServer/native/cpp/main.cpp b/wpinet/src/netconsoleServer/native/cpp/main.cpp index 42f4065bfc..44a26c0fb6 100644 --- a/wpinet/src/netconsoleServer/native/cpp/main.cpp +++ b/wpinet/src/netconsoleServer/native/cpp/main.cpp @@ -29,12 +29,12 @@ #include "wpi/util/print.hpp" #include "wpi/util/timestamp.h" -namespace uv = wpi::uv; +namespace uv = wpi::net::uv; -static uint64_t startTime = wpi::Now(); +static uint64_t startTime = wpi::util::Now(); static bool NewlineBuffer(std::string& rem, uv::Buffer& buf, size_t len, - wpi::SmallVectorImpl& bufs, bool tcp, + wpi::util::SmallVectorImpl& bufs, bool tcp, uint16_t tcpSeq) { // scan for last newline std::string_view str(buf.base, len); @@ -46,12 +46,12 @@ static bool NewlineBuffer(std::string& rem, uv::Buffer& buf, size_t len, } // build output - wpi::raw_uv_ostream out(bufs, 4096); - std::string_view toCopy = wpi::slice(str, 0, idx + 1); + wpi::net::raw_uv_ostream out(bufs, 4096); + std::string_view toCopy = wpi::util::slice(str, 0, idx + 1); if (tcp) { // Header is 2 byte len, 1 byte type, 4 byte timestamp, 2 byte sequence num uint32_t ts = - std::bit_cast((wpi::Now() - startTime) * 1.0e-6); + std::bit_cast((wpi::util::Now() - startTime) * 1.0e-6); uint16_t len = rem.size() + toCopy.size() + 1 + 4 + 2; const uint8_t header[] = {static_cast((len >> 8) & 0xff), static_cast(len & 0xff), @@ -67,7 +67,7 @@ static bool NewlineBuffer(std::string& rem, uv::Buffer& buf, size_t len, out << rem << toCopy; // reset remainder - rem = wpi::slice(str, idx + 1, std::string_view::npos); + rem = wpi::util::slice(str, idx + 1, std::string_view::npos); return true; } @@ -89,7 +89,7 @@ static void CopyUdp(uv::Stream& in, std::shared_ptr out, [rem = std::make_shared(), outPtr = out.get(), addr]( uv::Buffer& buf, size_t len) { // build buffers - wpi::SmallVector bufs; + wpi::util::SmallVector bufs; if (!NewlineBuffer(*rem, buf, len, bufs, false, 0)) { return; } @@ -113,7 +113,7 @@ static void CopyTcp(uv::Stream& in, std::shared_ptr out) { [data = std::make_shared(), outPtr = out.get()]( uv::Buffer& buf, size_t len) { // build buffers - wpi::SmallVector bufs; + wpi::util::SmallVector bufs; if (!NewlineBuffer(data->rem, buf, len, bufs, true, data->seq++)) { return; } @@ -155,7 +155,7 @@ int main(int argc, char* argv[]) { useUdp = true; broadcastUdp = true; } else { - wpi::print(stderr, "unrecognized command line option {}\n", + wpi::util::print(stderr, "unrecognized command line option {}\n", argv[programArgc]); err = true; } @@ -176,7 +176,7 @@ int main(int argc, char* argv[]) { auto loop = uv::Loop::Create(); loop->error.connect( - [](uv::Error err) { wpi::print(stderr, "uv ERROR: {}\n", err.str()); }); + [](uv::Error err) { wpi::util::print(stderr, "uv ERROR: {}\n", err.str()); }); // create pipes to communicate with child auto stdinPipe = uv::Pipe::Create(loop); @@ -223,7 +223,7 @@ int main(int argc, char* argv[]) { } // close on error - tcp->error.connect([s = tcp.get()](wpi::uv::Error err) { s->Close(); }); + tcp->error.connect([s = tcp.get()](wpi::net::uv::Error err) { s->Close(); }); // tee stdout and stderr CopyTcp(*stdoutPipe, tcp); @@ -235,7 +235,7 @@ int main(int argc, char* argv[]) { } // build process options - wpi::SmallVector options; + wpi::util::SmallVector options; // hook up pipes to child options.emplace_back( diff --git a/wpinet/src/netconsoleTee/native/cpp/main.cpp b/wpinet/src/netconsoleTee/native/cpp/main.cpp index 54fd6078fe..359d23233d 100644 --- a/wpinet/src/netconsoleTee/native/cpp/main.cpp +++ b/wpinet/src/netconsoleTee/native/cpp/main.cpp @@ -20,12 +20,12 @@ #include "wpi/util/print.hpp" #include "wpi/util/timestamp.h" -namespace uv = wpi::uv; +namespace uv = wpi::net::uv; -static uint64_t startTime = wpi::Now(); +static uint64_t startTime = wpi::util::Now(); static bool NewlineBuffer(std::string& rem, uv::Buffer& buf, size_t len, - wpi::SmallVectorImpl& bufs, bool tcp, + wpi::util::SmallVectorImpl& bufs, bool tcp, uint16_t tcpSeq) { // scan for last newline std::string_view str(buf.base, len); @@ -37,12 +37,12 @@ static bool NewlineBuffer(std::string& rem, uv::Buffer& buf, size_t len, } // build output - wpi::raw_uv_ostream out(bufs, 4096); - std::string_view toCopy = wpi::slice(str, 0, idx + 1); + wpi::net::raw_uv_ostream out(bufs, 4096); + std::string_view toCopy = wpi::util::slice(str, 0, idx + 1); if (tcp) { // Header is 2 byte len, 1 byte type, 4 byte timestamp, 2 byte sequence num uint32_t ts = - std::bit_cast((wpi::Now() - startTime) * 1.0e-6); + std::bit_cast((wpi::util::Now() - startTime) * 1.0e-6); uint16_t len = rem.size() + toCopy.size() + 1 + 4 + 2; const uint8_t header[] = {static_cast((len >> 8) & 0xff), static_cast(len & 0xff), @@ -58,7 +58,7 @@ static bool NewlineBuffer(std::string& rem, uv::Buffer& buf, size_t len, out << rem << toCopy; // reset remainder - rem = wpi::slice(str, idx + 1, std::string_view::npos); + rem = wpi::util::slice(str, idx + 1, std::string_view::npos); return true; } @@ -80,7 +80,7 @@ static void CopyUdp(uv::Stream& in, std::shared_ptr out, int port, [rem = std::make_shared(), outPtr = out.get(), addr]( uv::Buffer& buf, size_t len) { // build buffers - wpi::SmallVector bufs; + wpi::util::SmallVector bufs; if (!NewlineBuffer(*rem, buf, len, bufs, false, 0)) { return; } @@ -104,7 +104,7 @@ static void CopyTcp(uv::Stream& in, std::shared_ptr out) { [data = std::make_shared(), outPtr = out.get()]( uv::Buffer& buf, size_t len) { // build buffers - wpi::SmallVector bufs; + wpi::util::SmallVector bufs; if (!NewlineBuffer(data->rem, buf, len, bufs, true, data->seq++)) { return; } @@ -150,14 +150,14 @@ int main(int argc, char* argv[]) { ++arg; std::optional portValue; if (arg >= argc || argv[arg][0] == '-' || - !(portValue = wpi::parse_integer(argv[arg], 10))) { + !(portValue = wpi::util::parse_integer(argv[arg], 10))) { std::fputs("-p must be followed by port number\n", stderr); err = true; } else if (portValue) { port = portValue.value(); } } else { - wpi::print(stderr, "unrecognized command line option {}\n", argv[arg]); + wpi::util::print(stderr, "unrecognized command line option {}\n", argv[arg]); err = true; } ++arg; @@ -176,7 +176,7 @@ int main(int argc, char* argv[]) { auto loop = uv::Loop::Create(); loop->error.connect( - [](uv::Error err) { wpi::print(stderr, "uv ERROR: {}\n", err.str()); }); + [](uv::Error err) { wpi::util::print(stderr, "uv ERROR: {}\n", err.str()); }); // create ttys auto stdinTty = uv::Tty::Create(loop, 0, true); @@ -213,7 +213,7 @@ int main(int argc, char* argv[]) { } // close on error - tcp->error.connect([s = tcp.get()](wpi::uv::Error err) { s->Close(); }); + tcp->error.connect([s = tcp.get()](wpi::net::uv::Error err) { s->Close(); }); // tee CopyTcp(*stdinTty, tcp); diff --git a/wpinet/src/test/native/cpp/HttpParserTest.cpp b/wpinet/src/test/native/cpp/HttpParserTest.cpp index 793ea5f386..fd83339bf9 100644 --- a/wpinet/src/test/native/cpp/HttpParserTest.cpp +++ b/wpinet/src/test/native/cpp/HttpParserTest.cpp @@ -6,7 +6,7 @@ #include -namespace wpi { +namespace wpi::net { TEST(HttpParserTest, UrlMethodHeadersComplete) { HttpParser p{HttpParser::kRequest}; @@ -203,4 +203,4 @@ TEST(HttpParserTest, Reset) { ASSERT_FALSE(p.HasError()); } -} // namespace wpi +} // namespace wpi::net diff --git a/wpinet/src/test/native/cpp/HttpUtilTest.cpp b/wpinet/src/test/native/cpp/HttpUtilTest.cpp index a8fdacc2bf..28335362d5 100644 --- a/wpinet/src/test/native/cpp/HttpUtilTest.cpp +++ b/wpinet/src/test/native/cpp/HttpUtilTest.cpp @@ -6,7 +6,7 @@ #include -namespace wpi { +namespace wpi::net { TEST(HttpMultipartScannerTest, ExecuteExact) { HttpMultipartScanner scanner("foo"); @@ -99,4 +99,4 @@ TEST(HttpMultipartScannerTest, SeqNoDashesNoDashes) { EXPECT_TRUE(scanner.IsDone()); } -} // namespace wpi +} // namespace wpi::net diff --git a/wpinet/src/test/native/cpp/HttpWebSocketServerConnectionTest.cpp b/wpinet/src/test/native/cpp/HttpWebSocketServerConnectionTest.cpp index 46ae45c907..64f555a142 100644 --- a/wpinet/src/test/native/cpp/HttpWebSocketServerConnectionTest.cpp +++ b/wpinet/src/test/native/cpp/HttpWebSocketServerConnectionTest.cpp @@ -8,7 +8,7 @@ #include -namespace wpi { +namespace wpi::net { class HttpWebSocketServerConnectionTest : public HttpWebSocketServerConnection { @@ -24,4 +24,4 @@ class HttpWebSocketServerConnectionTest int gotUpgrade = 0; }; -} // namespace wpi +} // namespace wpi::net diff --git a/wpinet/src/test/native/cpp/MulticastTest.cpp b/wpinet/src/test/native/cpp/MulticastTest.cpp index 78c4474166..96935200d9 100644 --- a/wpinet/src/test/native/cpp/MulticastTest.cpp +++ b/wpinet/src/test/native/cpp/MulticastTest.cpp @@ -19,8 +19,8 @@ TEST(MulticastServiceAnnouncerTest, EmptyText) { const std::string_view serviceName = "TestServiceNoText"; const std::string_view serviceType = "_wpinotxt"; const int port = std::rand(); - wpi::MulticastServiceAnnouncer announcer(serviceName, serviceType, port); - wpi::MulticastServiceResolver resolver(serviceType); + wpi::net::MulticastServiceAnnouncer announcer(serviceName, serviceType, port); + wpi::net::MulticastServiceResolver resolver(serviceType); if (announcer.HasImplementation() && resolver.HasImplementation()) { announcer.Start(); @@ -39,8 +39,8 @@ TEST(MulticastServiceAnnouncerTest, SingleText) { const int port = std::rand(); std::array, 1> txt = { std::pair{"hello", "world"}}; - wpi::MulticastServiceAnnouncer announcer(serviceName, serviceType, port, txt); - wpi::MulticastServiceResolver resolver(serviceType); + wpi::net::MulticastServiceAnnouncer announcer(serviceName, serviceType, port, txt); + wpi::net::MulticastServiceResolver resolver(serviceType); if (announcer.HasImplementation() && resolver.HasImplementation()) { announcer.Start(); diff --git a/wpinet/src/test/native/cpp/WebSocketClientTest.cpp b/wpinet/src/test/native/cpp/WebSocketClientTest.cpp index 1f231058ce..8fec345806 100644 --- a/wpinet/src/test/native/cpp/WebSocketClientTest.cpp +++ b/wpinet/src/test/native/cpp/WebSocketClientTest.cpp @@ -17,7 +17,7 @@ #include "wpi/util/StringExtras.hpp" #include "wpi/util/sha1.hpp" -namespace wpi { +namespace wpi::net { class WebSocketClientTest : public WebSocketTest { public: @@ -25,29 +25,29 @@ class WebSocketClientTest : public WebSocketTest { // Bare bones server req.header.connect([this](std::string_view name, std::string_view value) { // save key (required for valid response) - if (equals_lower(name, "sec-websocket-key")) { + if (wpi::util::equals_lower(name, "sec-websocket-key")) { clientKey = value; } }); req.headersComplete.connect([this](bool) { // send response - SmallVector bufs; + wpi::util::SmallVector bufs; raw_uv_ostream os{bufs, 4096}; os << "HTTP/1.1 101 Switching Protocols\r\n"; os << "Upgrade: websocket\r\n"; os << "Connection: Upgrade\r\n"; // accept hash - SHA1 hash; + wpi::util::SHA1 hash; hash.Update(clientKey); hash.Update("258EAFA5-E914-47DA-95CA-C5AB0DC85B11"); if (mockBadAccept) { hash.Update("1"); } - SmallString<64> hashBuf; - SmallString<64> acceptBuf; + wpi::util::SmallString<64> hashBuf; + wpi::util::SmallString<64> acceptBuf; os << "Sec-WebSocket-Accept: " - << Base64Encode(hash.RawFinal(hashBuf), acceptBuf) << "\r\n"; + << wpi::util::Base64Encode(hash.RawFinal(hashBuf), acceptBuf) << "\r\n"; if (!mockProtocol.empty()) { os << "Sec-WebSocket-Protocol: " << mockProtocol << "\r\n"; @@ -92,7 +92,7 @@ class WebSocketClientTest : public WebSocketTest { std::vector wireData; std::shared_ptr conn; HttpParser req{HttpParser::kRequest}; - SmallString<64> clientKey; + wpi::util::SmallString<64> clientKey; std::string mockProtocol; bool serverHeadersDone = false; std::function connected; @@ -321,4 +321,4 @@ TEST_P(WebSocketClientDataTest, ReceiveMasked) { ASSERT_EQ(gotCallback, 1); } -} // namespace wpi +} // namespace wpi::net diff --git a/wpinet/src/test/native/cpp/WebSocketIntegrationTest.cpp b/wpinet/src/test/native/cpp/WebSocketIntegrationTest.cpp index 238a950b85..d9bba03905 100644 --- a/wpinet/src/test/native/cpp/WebSocketIntegrationTest.cpp +++ b/wpinet/src/test/native/cpp/WebSocketIntegrationTest.cpp @@ -9,7 +9,7 @@ #include "WebSocketTest.hpp" #include "wpi/util/SmallString.hpp" -namespace wpi { +namespace wpi::net { class WebSocketIntegrationTest : public WebSocketTest {}; @@ -199,4 +199,4 @@ TEST_F(WebSocketIntegrationTest, ServerSendPing) { ASSERT_EQ(gotData, 2); } -} // namespace wpi +} // namespace wpi::net diff --git a/wpinet/src/test/native/cpp/WebSocketSerializerTest.cpp b/wpinet/src/test/native/cpp/WebSocketSerializerTest.cpp index 2fad23b827..b956a6a6e8 100644 --- a/wpinet/src/test/native/cpp/WebSocketSerializerTest.cpp +++ b/wpinet/src/test/native/cpp/WebSocketSerializerTest.cpp @@ -26,17 +26,17 @@ using ::testing::Field; using ::testing::Pointee; using ::testing::Return; -namespace wpi::uv { +namespace wpi::net::uv { inline bool operator==(const Buffer& lhs, const Buffer& rhs) { return lhs.len == rhs.len && std::equal(lhs.base, lhs.base + lhs.len, rhs.base); } inline void PrintTo(const Buffer& buf, ::std::ostream* os) { - ::wpi::PrintTo(buf.bytes(), os); + ::wpi::util::PrintTo(buf.bytes(), os); } -} // namespace wpi::uv +} // namespace wpi::net::uv -namespace wpi { +namespace wpi::net { inline bool operator==(const WebSocket::Frame& lhs, const WebSocket::Frame& rhs) { return lhs.opcode == rhs.opcode && @@ -44,11 +44,11 @@ inline bool operator==(const WebSocket::Frame& lhs, } inline void PrintTo(const WebSocket::Frame& frame, ::std::ostream* os) { *os << frame.opcode << ": "; - ::wpi::PrintTo(frame.data, os); + ::wpi::util::PrintTo(frame.data, os); } -} // namespace wpi +} // namespace wpi::net -namespace wpi::detail { +namespace wpi::net::detail { class MockWebSocketWriteReq : public std::enable_shared_from_this, @@ -72,7 +72,7 @@ class MockStream { (std::span bufs, const std::shared_ptr& req)); - Logger* GetLogger() const { return nullptr; } + wpi::util::Logger* GetLogger() const { return nullptr; } }; class WebSocketWriteReqTest : public ::testing::Test { @@ -103,7 +103,7 @@ TEST_F(WebSocketWriteReqTest, ContinueDone) { } TEST_F(WebSocketWriteReqTest, ContinueTryWriteComplete) { - EXPECT_CALL(stream, TryWrite(wpi::SpanEq(req->m_frames.m_bufs))) + EXPECT_CALL(stream, TryWrite(wpi::util::SpanEq(req->m_frames.m_bufs))) .WillOnce(Return(9)); ASSERT_EQ(req->Continue(stream, req), 0); } @@ -114,7 +114,7 @@ TEST_F(WebSocketWriteReqTest, ContinueTryWriteNoProgress) { // Write should get called for all of next frame - make forward progress uv::Buffer remBufs[2] = {uv::Buffer{m_buf0}, uv::Buffer{m_buf1}}; EXPECT_CALL(stream, - DoWrite(wpi::SpanEq(std::span(remBufs)), _)); + DoWrite(wpi::util::SpanEq(std::span(remBufs)), _)); ASSERT_EQ(req->Continue(stream, req), 1); } @@ -130,7 +130,7 @@ TEST_F(WebSocketWriteReqTest, ContinueTryWritePartialMidFrameMidBuf1) { // Write should get called for remainder of buf 0 and all of buf 1 uv::Buffer remBufs[2] = {uv::Buffer{&m_buf0[2], 1}, uv::Buffer{m_buf1}}; EXPECT_CALL(stream, - DoWrite(wpi::SpanEq(std::span(remBufs)), _)); + DoWrite(wpi::util::SpanEq(std::span(remBufs)), _)); ASSERT_EQ(req->Continue(stream, req), 1); } @@ -140,7 +140,7 @@ TEST_F(WebSocketWriteReqTest, ContinueTryWritePartialMidFrameBufBoundary) { // Write should get called for all of buf 1 uv::Buffer remBufs[1] = {uv::Buffer{m_buf1}}; EXPECT_CALL(stream, - DoWrite(wpi::SpanEq(std::span(remBufs)), _)); + DoWrite(wpi::util::SpanEq(std::span(remBufs)), _)); ASSERT_EQ(req->Continue(stream, req), 1); } @@ -150,7 +150,7 @@ TEST_F(WebSocketWriteReqTest, ContinueTryWritePartialMidFrameMidBuf2) { // Write should get called for remainder of buf 1 uv::Buffer remBufs[1] = {uv::Buffer{&m_buf1[1], 1}}; EXPECT_CALL(stream, - DoWrite(wpi::SpanEq(std::span(remBufs)), _)); + DoWrite(wpi::util::SpanEq(std::span(remBufs)), _)); ASSERT_EQ(req->Continue(stream, req), 1); } @@ -160,7 +160,7 @@ TEST_F(WebSocketWriteReqTest, ContinueTryWritePartialFrameBoundary) { // Write should get called for all of next frame uv::Buffer remBufs[1] = {uv::Buffer{m_buf2}}; EXPECT_CALL(stream, - DoWrite(wpi::SpanEq(std::span(remBufs)), _)); + DoWrite(wpi::util::SpanEq(std::span(remBufs)), _)); ASSERT_EQ(req->Continue(stream, req), 1); } @@ -170,7 +170,7 @@ TEST_F(WebSocketWriteReqTest, ContinueTryWritePartialMidFrameMidBuf3) { // Write should get called for remainder of buf 2 uv::Buffer remBufs[1] = {uv::Buffer{&m_buf2[1], 3}}; EXPECT_CALL(stream, - DoWrite(wpi::SpanEq(std::span(remBufs)), _)); + DoWrite(wpi::util::SpanEq(std::span(remBufs)), _)); ASSERT_EQ(req->Continue(stream, req), 1); } @@ -243,10 +243,10 @@ void WebSocketTrySendTest::CheckTrySendFrames( [&](auto bufs, auto err) { ++callbackCalled; ASSERT_THAT(bufs, - SpanEq(std::span(expectCbBufs))); + wpi::util::SpanEq(std::span(expectCbBufs))); ASSERT_EQ(err.code(), expectErr); }), - SpanEq(expectRet)); + wpi::util::SpanEq(expectRet)); } TEST_F(WebSocketTrySendTest, ServerComplete) { @@ -288,13 +288,13 @@ TEST_F(WebSocketTrySendTest, ServerPartialMidFrameMidBuf0) { m_bufs[1]}; std::array contBufs{m_frameHeaders[1], m_bufs[2]}; std::array contFrameOffs{static_cast(m_serialized[1].size())}; - EXPECT_CALL(stream, DoWrite(wpi::SpanEq(remBufs), _)); + EXPECT_CALL(stream, DoWrite(wpi::util::SpanEq(remBufs), _)); CheckTrySendFrames({}, std::span{m_frames}.subspan(2)); ASSERT_EQ(makeReqCalled, 1); - ASSERT_THAT(req->m_frames.m_bufs, SpanEq(contBufs)); + ASSERT_THAT(req->m_frames.m_bufs, wpi::util::SpanEq(contBufs)); ASSERT_EQ(req->m_continueBufPos, 0u); ASSERT_EQ(req->m_continueFramePos, 0u); - ASSERT_THAT(req->m_continueFrameOffs, SpanEq(contFrameOffs)); + ASSERT_THAT(req->m_continueFrameOffs, wpi::util::SpanEq(contFrameOffs)); ASSERT_EQ(callbackCalled, 0); } @@ -306,10 +306,10 @@ TEST_F(WebSocketTrySendTest, ServerPartialMidFrameBufBoundary) { // return will be frame 2 only std::array remBufs{m_bufs[1]}; std::array contBufs{m_frameHeaders[1], m_bufs[2]}; - EXPECT_CALL(stream, DoWrite(wpi::SpanEq(remBufs), _)); + EXPECT_CALL(stream, DoWrite(wpi::util::SpanEq(remBufs), _)); CheckTrySendFrames({}, std::span{m_frames}.subspan(2)); ASSERT_EQ(makeReqCalled, 1); - ASSERT_THAT(req->m_frames.m_bufs, SpanEq(contBufs)); + ASSERT_THAT(req->m_frames.m_bufs, wpi::util::SpanEq(contBufs)); ASSERT_EQ(callbackCalled, 0); } @@ -321,10 +321,10 @@ TEST_F(WebSocketTrySendTest, ServerPartialMidFrameMidBuf1) { // return will be frame 2 only std::array remBufs{std::span{m_buf1data}.subspan(1)}; std::array contBufs{m_frameHeaders[1], m_bufs[2]}; - EXPECT_CALL(stream, DoWrite(wpi::SpanEq(remBufs), _)); + EXPECT_CALL(stream, DoWrite(wpi::util::SpanEq(remBufs), _)); CheckTrySendFrames({}, std::span{m_frames}.subspan(2)); ASSERT_EQ(makeReqCalled, 1); - ASSERT_THAT(req->m_frames.m_bufs, SpanEq(contBufs)); + ASSERT_THAT(req->m_frames.m_bufs, wpi::util::SpanEq(contBufs)); ASSERT_EQ(callbackCalled, 0); } @@ -336,7 +336,7 @@ TEST_F(WebSocketTrySendTest, ServerPartialFrameBoundary) { // no continuation // return will be frame 2 only std::array remBufs{m_bufs[2]}; - EXPECT_CALL(stream, DoWrite(wpi::SpanEq(remBufs), _)); + EXPECT_CALL(stream, DoWrite(wpi::util::SpanEq(remBufs), _)); CheckTrySendFrames({}, std::span{m_frames}.subspan(2)); ASSERT_EQ(makeReqCalled, 1); ASSERT_TRUE(req->m_frames.m_bufs.empty()); @@ -350,7 +350,7 @@ TEST_F(WebSocketTrySendTest, ServerPartialMidFrameMidBuf2) { // Write should get called for remainder of buf 2; no continuation // return will be frame 2 only std::array remBufs{std::span{m_buf2data}.subspan(1)}; - EXPECT_CALL(stream, DoWrite(wpi::SpanEq(remBufs), _)); + EXPECT_CALL(stream, DoWrite(wpi::util::SpanEq(remBufs), _)); CheckTrySendFrames({}, std::span{m_frames}.subspan(2)); ASSERT_EQ(makeReqCalled, 1); ASSERT_TRUE(req->m_frames.m_bufs.empty()); @@ -375,7 +375,7 @@ TEST_F(WebSocketTrySendTest, ServerPartialLastFrame) { m_frameHeaders[2].len + 10)); // Write called for remainder of buf 3; no continuation std::array remBufs{std::span{m_buf3data}.subspan(1)}; - EXPECT_CALL(stream, DoWrite(wpi::SpanEq(remBufs), _)); + EXPECT_CALL(stream, DoWrite(wpi::util::SpanEq(remBufs), _)); CheckTrySendFrames({}, {}); ASSERT_EQ(makeReqCalled, 1); ASSERT_TRUE(req->m_frames.m_bufs.empty()); @@ -400,7 +400,7 @@ TEST_F(WebSocketTrySendTest, Big) { for (size_t i = 6; i < bufs.size(); ++i) { remBufs.emplace_back(bufs[i]); } - EXPECT_CALL(stream, DoWrite(wpi::SpanEq(remBufs), _)); + EXPECT_CALL(stream, DoWrite(wpi::util::SpanEq(remBufs), _)); ASSERT_TRUE( TrySendFrames( @@ -420,4 +420,4 @@ TEST_F(WebSocketTrySendTest, Big) { ASSERT_EQ(callbackCalled, 0); } -} // namespace wpi::detail +} // namespace wpi::net::detail diff --git a/wpinet/src/test/native/cpp/WebSocketServerTest.cpp b/wpinet/src/test/native/cpp/WebSocketServerTest.cpp index 526f3f4576..141f8752e9 100644 --- a/wpinet/src/test/native/cpp/WebSocketServerTest.cpp +++ b/wpinet/src/test/native/cpp/WebSocketServerTest.cpp @@ -14,7 +14,7 @@ #include "wpi/util/SmallString.hpp" #include "wpi/util/sha1.hpp" -namespace wpi { +namespace wpi::net { class WebSocketServerTest : public WebSocketTest { public: @@ -793,4 +793,4 @@ TEST_P(WebSocketServerDataTest, ReceiveUnmasked) { ASSERT_EQ(gotCallback, 1); } -} // namespace wpi +} // namespace wpi::net diff --git a/wpinet/src/test/native/cpp/WebSocketTest.cpp b/wpinet/src/test/native/cpp/WebSocketTest.cpp index f8f6584672..38e5976eb2 100644 --- a/wpinet/src/test/native/cpp/WebSocketTest.cpp +++ b/wpinet/src/test/native/cpp/WebSocketTest.cpp @@ -12,7 +12,7 @@ #include "wpi/net/HttpParser.hpp" #include "wpi/util/StringExtras.hpp" -namespace wpi { +namespace wpi::net { #ifdef _WIN32 const char* WebSocketTest::pipeName = "\\\\.\\pipe\\websocket-unit-test"; @@ -111,18 +111,18 @@ TEST_F(WebSocketTest, CreateClientBasic) { HttpParser req{HttpParser::kRequest}; req.url.connect([](std::string_view url) { ASSERT_EQ(url, "/test"); }); req.header.connect([&](std::string_view name, std::string_view value) { - if (equals_lower(name, "host")) { + if (wpi::util::equals_lower(name, "host")) { ASSERT_EQ(value, pipeName); ++gotHost; - } else if (equals_lower(name, "upgrade")) { + } else if (wpi::util::equals_lower(name, "upgrade")) { ASSERT_EQ(value, "websocket"); ++gotUpgrade; - } else if (equals_lower(name, "connection")) { + } else if (wpi::util::equals_lower(name, "connection")) { ASSERT_EQ(value, "Upgrade"); ++gotConnection; - } else if (equals_lower(name, "sec-websocket-key")) { + } else if (wpi::util::equals_lower(name, "sec-websocket-key")) { ++gotKey; - } else if (equals_lower(name, "sec-websocket-version")) { + } else if (wpi::util::equals_lower(name, "sec-websocket-version")) { ASSERT_EQ(value, "13"); ++gotVersion; } else { @@ -163,10 +163,10 @@ TEST_F(WebSocketTest, CreateClientExtraHeaders) { int gotExtra2 = 0; HttpParser req{HttpParser::kRequest}; req.header.connect([&](std::string_view name, std::string_view value) { - if (equals(name, "Extra1")) { + if (wpi::util::equals(name, "Extra1")) { ASSERT_EQ(value, "Data1"); ++gotExtra1; - } else if (equals(name, "Extra2")) { + } else if (wpi::util::equals(name, "Extra2")) { ASSERT_EQ(value, "Data2"); ++gotExtra2; } @@ -186,7 +186,7 @@ TEST_F(WebSocketTest, CreateClientExtraHeaders) { }); clientPipe->Connect(pipeName, [&]() { WebSocket::ClientOptions options; - SmallVector, 4> extraHeaders; + wpi::util::SmallVector, 4> extraHeaders; extraHeaders.emplace_back("Extra1", "Data1"); extraHeaders.emplace_back("Extra2", "Data2"); options.extraHeaders = extraHeaders; @@ -239,13 +239,13 @@ TEST_F(WebSocketTest, CreateServerBasic) { ASSERT_EQ(resp.GetStatusCode(), 101u) << "status: " << status; }); resp.header.connect([&](std::string_view name, std::string_view value) { - if (equals_lower(name, "upgrade")) { + if (wpi::util::equals_lower(name, "upgrade")) { ASSERT_EQ(value, "websocket"); ++gotUpgrade; - } else if (equals_lower(name, "connection")) { + } else if (wpi::util::equals_lower(name, "connection")) { ASSERT_EQ(value, "Upgrade"); ++gotConnection; - } else if (equals_lower(name, "sec-websocket-accept")) { + } else if (wpi::util::equals_lower(name, "sec-websocket-accept")) { ASSERT_EQ(value, "s3pPLMBiTxaQ9kYGzzhZRbK+xOo="); ++gotAccept; } else { @@ -291,7 +291,7 @@ TEST_F(WebSocketTest, CreateServerProtocol) { HttpParser resp{HttpParser::kResponse}; resp.header.connect([&](std::string_view name, std::string_view value) { - if (equals_lower(name, "sec-websocket-protocol")) { + if (wpi::util::equals_lower(name, "sec-websocket-protocol")) { ++gotProtocol; ASSERT_EQ(value, "myProtocol"); } @@ -337,10 +337,10 @@ TEST_F(WebSocketTest, CreateServerBadVersion) { ASSERT_EQ(resp.GetStatusCode(), 426u) << "status: " << status; }); resp.header.connect([&](std::string_view name, std::string_view value) { - if (equals_lower(name, "sec-websocket-version")) { + if (wpi::util::equals_lower(name, "sec-websocket-version")) { ++gotVersion; ASSERT_EQ(value, "13"); - } else if (equals_lower(name, "upgrade")) { + } else if (wpi::util::equals_lower(name, "upgrade")) { ++gotUpgrade; ASSERT_EQ(value, "WebSocket"); } else { @@ -378,4 +378,4 @@ TEST_F(WebSocketTest, CreateServerBadVersion) { ASSERT_EQ(gotUpgrade, 1); } -} // namespace wpi +} // namespace wpi::net diff --git a/wpinet/src/test/native/cpp/WebSocketTest.hpp b/wpinet/src/test/native/cpp/WebSocketTest.hpp index bf4aa52297..9d7f98e45d 100644 --- a/wpinet/src/test/native/cpp/WebSocketTest.hpp +++ b/wpinet/src/test/native/cpp/WebSocketTest.hpp @@ -15,7 +15,7 @@ #include "wpi/net/uv/Pipe.hpp" #include "wpi/net/uv/Timer.hpp" -namespace wpi { +namespace wpi::net { class WebSocketTest : public ::testing::Test { public: @@ -68,4 +68,4 @@ class WebSocketTest : public ::testing::Test { std::shared_ptr serverPipe; }; -} // namespace wpi +} // namespace wpi::net diff --git a/wpinet/src/test/native/cpp/WorkerThreadTest.cpp b/wpinet/src/test/native/cpp/WorkerThreadTest.cpp index 4f134f00a4..ea65f0b5d6 100644 --- a/wpinet/src/test/native/cpp/WorkerThreadTest.cpp +++ b/wpinet/src/test/native/cpp/WorkerThreadTest.cpp @@ -13,11 +13,11 @@ #include "wpi/util/condition_variable.hpp" #include "wpi/util/mutex.hpp" -namespace wpi { +namespace wpi::net { TEST(WorkerThreadTest, Future) { WorkerThread worker; - future f = + wpi::util::future f = worker.QueueWork([](bool v) -> int { return v ? 1 : 2; }, true); ASSERT_EQ(f.get(), 1); } @@ -25,7 +25,7 @@ TEST(WorkerThreadTest, Future) { TEST(WorkerThreadTest, FutureVoid) { int callbacks = 0; WorkerThread worker; - future f = worker.QueueWork( + wpi::util::future f = worker.QueueWork( [&](int v) { ++callbacks; ASSERT_EQ(v, 3); @@ -82,4 +82,4 @@ TEST(WorkerThreadTest, LoopVoid) { ASSERT_EQ(callbacks, 1); } -} // namespace wpi +} // namespace wpi::net diff --git a/wpinet/src/test/native/cpp/hostname.cpp b/wpinet/src/test/native/cpp/hostname.cpp index 8a678fa64a..feb24ce2a4 100644 --- a/wpinet/src/test/native/cpp/hostname.cpp +++ b/wpinet/src/test/native/cpp/hostname.cpp @@ -9,16 +9,16 @@ #include "wpi/util/SmallString.hpp" #include "wpi/util/SmallVector.hpp" -namespace wpi { +namespace wpi::net { TEST(HostNameTest, HostNameNotEmpty) { ASSERT_NE(GetHostname(), ""); } TEST(HostNameTest, HostNameNotEmptySmallVector) { - SmallVector name; + wpi::util::SmallVector name; ASSERT_NE(GetHostname(name), ""); } TEST(HostNameTest, HostNameEq) { - SmallVector nameBuf; + wpi::util::SmallVector nameBuf; ASSERT_EQ(GetHostname(nameBuf), GetHostname()); } -} // namespace wpi +} // namespace wpi::net diff --git a/wpinet/src/test/native/cpp/raw_uv_stream_test.cpp b/wpinet/src/test/native/cpp/raw_uv_stream_test.cpp index 13a3cd133d..bdfae8b364 100644 --- a/wpinet/src/test/native/cpp/raw_uv_stream_test.cpp +++ b/wpinet/src/test/native/cpp/raw_uv_stream_test.cpp @@ -6,10 +6,10 @@ #include -namespace wpi { +namespace wpi::net { TEST(RawUvStreamTest, BasicWrite) { - SmallVector bufs; + wpi::util::SmallVector bufs; raw_uv_ostream os(bufs, 1024); os << "12"; os << "34"; @@ -26,7 +26,7 @@ TEST(RawUvStreamTest, BasicWrite) { } TEST(RawUvStreamTest, BoundaryWrite) { - SmallVector bufs; + wpi::util::SmallVector bufs; raw_uv_ostream os(bufs, 4); ASSERT_EQ(bufs.size(), 0u); os << "12"; @@ -42,7 +42,7 @@ TEST(RawUvStreamTest, BoundaryWrite) { } TEST(RawUvStreamTest, LargeWrite) { - SmallVector bufs; + wpi::util::SmallVector bufs; raw_uv_ostream os(bufs, 4); os << "123456"; ASSERT_EQ(bufs.size(), 2u); @@ -55,7 +55,7 @@ TEST(RawUvStreamTest, LargeWrite) { } TEST(RawUvStreamTest, PrevDataWrite) { - SmallVector bufs; + wpi::util::SmallVector bufs; bufs.emplace_back(uv::Buffer::Allocate(1024)); raw_uv_ostream os(bufs, 1024); os << "1234"; @@ -68,4 +68,4 @@ TEST(RawUvStreamTest, PrevDataWrite) { } } -} // namespace wpi +} // namespace wpi::net diff --git a/wpinet/src/test/native/cpp/uv/UvAsyncFunctionTest.cpp b/wpinet/src/test/native/cpp/uv/UvAsyncFunctionTest.cpp index ca20fdbee7..e51387dbc4 100644 --- a/wpinet/src/test/native/cpp/uv/UvAsyncFunctionTest.cpp +++ b/wpinet/src/test/native/cpp/uv/UvAsyncFunctionTest.cpp @@ -13,7 +13,7 @@ #include "wpi/net/uv/Loop.hpp" #include "wpi/net/uv/Prepare.hpp" -namespace wpi::uv { +namespace wpi::net::uv { TEST(UvAsyncFunctionTest, Basic) { int prepare_cb_called = 0; @@ -44,7 +44,7 @@ TEST(UvAsyncFunctionTest, Basic) { async->error.connect([](Error) { FAIL(); }); async->closed.connect([&] { close_cb_called++; }); - async->wakeup = [&](promise out, int v) { + async->wakeup = [&](wpi::util::promise out, int v) { ++async_cb_called[v]; if (v == 1) { async->Close(); @@ -82,7 +82,7 @@ TEST(UvAsyncFunctionTest, Ref) { }); prepare->Start(); - async->wakeup = [&](promise out, int v, int& r) { + async->wakeup = [&](wpi::util::promise out, int v, int& r) { r = v; async->Close(); prepare->Close(); @@ -121,7 +121,7 @@ TEST(UvAsyncFunctionTest, Movable) { }); prepare->Start(); - async->wakeup = [&](promise> out, + async->wakeup = [&](wpi::util::promise> out, std::unique_ptr v) { async->Close(); prepare->Close(); @@ -153,7 +153,7 @@ TEST(UvAsyncFunctionTest, CallIgnoreResult) { }); prepare->Start(); - async->wakeup = [&](promise> out, + async->wakeup = [&](wpi::util::promise> out, std::unique_ptr v) { async->Close(); prepare->Close(); @@ -184,7 +184,7 @@ TEST(UvAsyncFunctionTest, VoidCall) { }); prepare->Start(); - async->wakeup = [&](promise out) { + async->wakeup = [&](wpi::util::promise out) { async->Close(); prepare->Close(); out.set_value(); @@ -216,7 +216,7 @@ TEST(UvAsyncFunctionTest, WaitFor) { }); prepare->Start(); - async->wakeup = [&](promise out) { + async->wakeup = [&](wpi::util::promise out) { async->Close(); prepare->Close(); std::this_thread::sleep_for(std::chrono::milliseconds(100)); @@ -249,7 +249,7 @@ TEST(UvAsyncFunctionTest, VoidWaitFor) { }); prepare->Start(); - async->wakeup = [&](promise out) { + async->wakeup = [&](wpi::util::promise out) { async->Close(); prepare->Close(); std::this_thread::sleep_for(std::chrono::milliseconds(100)); @@ -263,4 +263,4 @@ TEST(UvAsyncFunctionTest, VoidWaitFor) { } } -} // namespace wpi::uv +} // namespace wpi::net::uv diff --git a/wpinet/src/test/native/cpp/uv/UvAsyncTest.cpp b/wpinet/src/test/native/cpp/uv/UvAsyncTest.cpp index babbfc637b..57a82f7eaa 100644 --- a/wpinet/src/test/native/cpp/uv/UvAsyncTest.cpp +++ b/wpinet/src/test/native/cpp/uv/UvAsyncTest.cpp @@ -35,14 +35,14 @@ #include "wpi/net/uv/Prepare.hpp" #include "wpi/util/mutex.hpp" -namespace wpi::uv { +namespace wpi::net::uv { TEST(UvAsyncTest, CallbackOnly) { std::atomic_int async_cb_called{0}; int prepare_cb_called = 0; int close_cb_called = 0; - wpi::mutex mutex; + wpi::util::mutex mutex; mutex.lock(); std::thread theThread; @@ -183,4 +183,4 @@ TEST(UvAsyncTest, DataRef) { } } -} // namespace wpi::uv +} // namespace wpi::net::uv diff --git a/wpinet/src/test/native/cpp/uv/UvBufferTest.cpp b/wpinet/src/test/native/cpp/uv/UvBufferTest.cpp index f9801a8bf7..10860edee5 100644 --- a/wpinet/src/test/native/cpp/uv/UvBufferTest.cpp +++ b/wpinet/src/test/native/cpp/uv/UvBufferTest.cpp @@ -6,7 +6,7 @@ #include -namespace wpi::uv { +namespace wpi::net::uv { TEST(UvSimpleBufferPoolTest, ConstructDefault) { SimpleBufferPool<> pool; @@ -45,4 +45,4 @@ TEST(UvSimpleBufferPoolTest, ClearRemaining) { ASSERT_EQ(pool.Remaining(), 0u); } -} // namespace wpi::uv +} // namespace wpi::net::uv diff --git a/wpinet/src/test/native/cpp/uv/UvGetAddrInfoTest.cpp b/wpinet/src/test/native/cpp/uv/UvGetAddrInfoTest.cpp index ef392e9c0a..8553664264 100644 --- a/wpinet/src/test/native/cpp/uv/UvGetAddrInfoTest.cpp +++ b/wpinet/src/test/native/cpp/uv/UvGetAddrInfoTest.cpp @@ -31,7 +31,7 @@ #define CONCURRENT_COUNT 10 -namespace wpi::uv { +namespace wpi::net::uv { TEST(UvGetAddrInfoTest, BothNull) { int fail_cb_called = 0; @@ -103,4 +103,4 @@ TEST(UvGetAddrInfoTest, Concurrent) { } #endif -} // namespace wpi::uv +} // namespace wpi::net::uv diff --git a/wpinet/src/test/native/cpp/uv/UvGetNameInfoTest.cpp b/wpinet/src/test/native/cpp/uv/UvGetNameInfoTest.cpp index 63aefa5d8a..c9e0d51e11 100644 --- a/wpinet/src/test/native/cpp/uv/UvGetNameInfoTest.cpp +++ b/wpinet/src/test/native/cpp/uv/UvGetNameInfoTest.cpp @@ -29,7 +29,7 @@ #include "wpi/net/uv/Loop.hpp" -namespace wpi::uv { +namespace wpi::net::uv { TEST(UvGetNameInfoTest, BasicIp4) { int getnameinfo_cbs = 0; @@ -71,4 +71,4 @@ TEST(UvGetNameInfoTest, BasicIp6) { ASSERT_EQ(getnameinfo_cbs, 1); } -} // namespace wpi::uv +} // namespace wpi::net::uv diff --git a/wpinet/src/test/native/cpp/uv/UvLoopWalkTest.cpp b/wpinet/src/test/native/cpp/uv/UvLoopWalkTest.cpp index 8cd32e5a7e..98b58c4864 100644 --- a/wpinet/src/test/native/cpp/uv/UvLoopWalkTest.cpp +++ b/wpinet/src/test/native/cpp/uv/UvLoopWalkTest.cpp @@ -29,7 +29,7 @@ #include "wpi/net/uv/Timer.hpp" -namespace wpi::uv { +namespace wpi::net::uv { TEST(UvLoopTest, Walk) { int seen_timer_handle = 0; @@ -66,4 +66,4 @@ TEST(UvLoopTest, Walk) { ASSERT_EQ(seen_timer_handle, 0); } -} // namespace wpi::uv +} // namespace wpi::net::uv diff --git a/wpinet/src/test/native/cpp/uv/UvTimerTest.cpp b/wpinet/src/test/native/cpp/uv/UvTimerTest.cpp index b18857f66a..be1de6589d 100644 --- a/wpinet/src/test/native/cpp/uv/UvTimerTest.cpp +++ b/wpinet/src/test/native/cpp/uv/UvTimerTest.cpp @@ -6,7 +6,7 @@ #include -namespace wpi::uv { +namespace wpi::net::uv { TEST(UvTimerTest, StartAndStop) { auto loop = Loop::Create(); @@ -66,4 +66,4 @@ TEST(UvTimerTest, Repeat) { loop->Run(); // forces close callback to run } -} // namespace wpi::uv +} // namespace wpi::net::uv diff --git a/wpiutil/src/dev/native/cpp/main.cpp b/wpiutil/src/dev/native/cpp/main.cpp index 74f17fbfea..e5b9d37af1 100644 --- a/wpiutil/src/dev/native/cpp/main.cpp +++ b/wpiutil/src/dev/native/cpp/main.cpp @@ -6,6 +6,6 @@ #include "wpi/util/print.hpp" int main() { - wpi::SmallString<128> v1("Hello"); - wpi::print("{}\n", v1.str()); + wpi::util::SmallString<128> v1("Hello"); + wpi::util::print("{}\n", v1.str()); } diff --git a/wpiutil/src/main/native/cpp/Base64.cpp b/wpiutil/src/main/native/cpp/Base64.cpp index 43266f2519..ca134c5b4b 100644 --- a/wpiutil/src/main/native/cpp/Base64.cpp +++ b/wpiutil/src/main/native/cpp/Base64.cpp @@ -63,7 +63,7 @@ #include "wpi/util/SmallVector.hpp" #include "wpi/util/raw_ostream.hpp" -namespace wpi { +namespace wpi::util { // aaaack but it's fast and const should make it shared text page. static const unsigned char pr2six[256] = { @@ -216,4 +216,4 @@ std::string_view Base64Encode(std::span plain, return os.str(); } -} // namespace wpi +} // namespace wpi::util diff --git a/wpiutil/src/main/native/cpp/Logger.cpp b/wpiutil/src/main/native/cpp/Logger.cpp index 96e298fbaa..c2568f81a1 100644 --- a/wpiutil/src/main/native/cpp/Logger.cpp +++ b/wpiutil/src/main/native/cpp/Logger.cpp @@ -4,7 +4,7 @@ #include "wpi/util/Logger.hpp" -using namespace wpi; +using namespace wpi::util; void Logger::DoLog(unsigned int level, const char* file, unsigned int line, const char* msg) { diff --git a/wpiutil/src/main/native/cpp/MappedFileRegion.cpp b/wpiutil/src/main/native/cpp/MappedFileRegion.cpp index 88bdc5bd01..e11d5fd01d 100644 --- a/wpiutil/src/main/native/cpp/MappedFileRegion.cpp +++ b/wpiutil/src/main/native/cpp/MappedFileRegion.cpp @@ -31,7 +31,7 @@ #include "wpi/util/WindowsError.hpp" #endif -using namespace wpi; +using namespace wpi::util; MappedFileRegion::MappedFileRegion(fs::file_t f, uint64_t length, uint64_t offset, MapMode mapMode, @@ -47,7 +47,7 @@ MappedFileRegion::MappedFileRegion(fs::file_t f, uint64_t length, f, 0, mapMode == kReadOnly ? PAGE_READONLY : PAGE_READWRITE, length >> 32, length & 0xffffffff, 0); if (fileMappingHandle == nullptr) { - ec = wpi::mapWindowsError(GetLastError()); + ec = wpi::util::mapWindowsError(GetLastError()); return; } @@ -66,7 +66,7 @@ MappedFileRegion::MappedFileRegion(fs::file_t f, uint64_t length, m_mapping = ::MapViewOfFile(fileMappingHandle, dwDesiredAccess, offset >> 32, offset & 0xffffffff, length); if (m_mapping == nullptr) { - ec = wpi::mapWindowsError(GetLastError()); + ec = wpi::util::mapWindowsError(GetLastError()); ::CloseHandle(fileMappingHandle); return; } @@ -79,7 +79,7 @@ MappedFileRegion::MappedFileRegion(fs::file_t f, uint64_t length, ::CloseHandle(fileMappingHandle); if (!::DuplicateHandle(::GetCurrentProcess(), f, ::GetCurrentProcess(), &m_fileHandle, 0, 0, DUPLICATE_SAME_ACCESS)) { - ec = wpi::mapWindowsError(GetLastError()); + ec = wpi::util::mapWindowsError(GetLastError()); ::UnmapViewOfFile(m_mapping); m_mapping = nullptr; return; diff --git a/wpiutil/src/main/native/cpp/RawFrame.cpp b/wpiutil/src/main/native/cpp/RawFrame.cpp index 513db1c07b..2f1a0c41a3 100644 --- a/wpiutil/src/main/native/cpp/RawFrame.cpp +++ b/wpiutil/src/main/native/cpp/RawFrame.cpp @@ -14,7 +14,7 @@ int WPI_AllocateRawFrameData(WPI_RawFrame* frame, size_t requestedSize) { return 0; } WPI_FreeRawFrameData(frame); - frame->data = static_cast(wpi::safe_malloc(requestedSize)); + frame->data = static_cast(wpi::util::safe_malloc(requestedSize)); frame->capacity = requestedSize; frame->size = 0; return 1; diff --git a/wpiutil/src/main/native/cpp/SafeThread.cpp b/wpiutil/src/main/native/cpp/SafeThread.cpp index f288cacf98..f6ae5dff62 100644 --- a/wpiutil/src/main/native/cpp/SafeThread.cpp +++ b/wpiutil/src/main/native/cpp/SafeThread.cpp @@ -8,7 +8,7 @@ #include #include -using namespace wpi; +using namespace wpi::util; // thread start/stop notifications for bindings that need to set up // per-thread state @@ -24,7 +24,7 @@ static std::atomic gSafeThreadRefcount; static std::atomic gOnSafeThreadStart{DefaultOnThreadStart}; static std::atomic gOnSafeThreadEnd{DefaultOnThreadEnd}; -namespace wpi::impl { +namespace wpi::util::impl { void SetSafeThreadNotifiers(OnThreadStartFn OnStart, OnThreadEndFn OnEnd) { if (gSafeThreadRefcount != 0) { throw std::runtime_error( @@ -36,7 +36,7 @@ void SetSafeThreadNotifiers(OnThreadStartFn OnStart, OnThreadEndFn OnEnd) { gOnSafeThreadStart = OnStart ? OnStart : DefaultOnThreadStart; gOnSafeThreadEnd = OnEnd ? OnEnd : DefaultOnThreadEnd; } -} // namespace wpi::impl +} // namespace wpi::util::impl void SafeThread::Stop() { m_active = false; @@ -54,7 +54,7 @@ detail::SafeThreadProxyBase::SafeThreadProxyBase( if (!m_thread) { return; } - m_lock = std::unique_lock(m_thread->m_mutex); + m_lock = std::unique_lock(m_thread->m_mutex); if (!m_thread->m_active) { m_lock.unlock(); m_thread = nullptr; diff --git a/wpiutil/src/main/native/cpp/StackTraceWrap.cpp b/wpiutil/src/main/native/cpp/StackTraceWrap.cpp index 1c2c461b0d..0682da8742 100644 --- a/wpiutil/src/main/native/cpp/StackTraceWrap.cpp +++ b/wpiutil/src/main/native/cpp/StackTraceWrap.cpp @@ -8,12 +8,12 @@ #include "wpi/util/StackTrace.hpp" static std::atomic gStackTraceImpl{ - wpi::GetStackTraceDefault}; + wpi::util::GetStackTraceDefault}; -std::string wpi::GetStackTrace(int offset) { +std::string wpi::util::GetStackTrace(int offset) { return (gStackTraceImpl.load())(offset); } -void wpi::SetGetStackTraceImpl(std::string (*func)(int offset)) { - gStackTraceImpl = func ? func : wpi::GetStackTraceDefault; +void wpi::util::SetGetStackTraceImpl(std::string (*func)(int offset)) { + gStackTraceImpl = func ? func : wpi::util::GetStackTraceDefault; } diff --git a/wpiutil/src/main/native/cpp/Synchronization.cpp b/wpiutil/src/main/native/cpp/Synchronization.cpp index defc48bc25..e301fcbd91 100644 --- a/wpiutil/src/main/native/cpp/Synchronization.cpp +++ b/wpiutil/src/main/native/cpp/Synchronization.cpp @@ -15,7 +15,7 @@ #include "wpi/util/condition_variable.hpp" #include "wpi/util/mutex.hpp" -using namespace wpi; +using namespace wpi::util; // Count of active threads using the handle manager singleton. A negative value // indicates that the manager is being destroyed. When the manager is being @@ -34,7 +34,7 @@ namespace { struct State { int signaled{0}; bool autoReset{false}; - wpi::SmallVector waiters; + wpi::util::SmallVector waiters; }; struct HandleManager { @@ -67,10 +67,10 @@ struct HandleManager { } #endif } - wpi::mutex mutex; - wpi::UidVector eventIds; - wpi::UidVector semaphoreIds; - wpi::DenseMap states; + wpi::util::mutex mutex; + wpi::util::UidVector eventIds; + wpi::util::UidVector semaphoreIds; + wpi::util::DenseMap states; }; class ManagerGuard { @@ -97,7 +97,7 @@ class ManagerGuard { } // namespace -WPI_EventHandle wpi::CreateEvent(bool manualReset, bool initialState) { +WPI_EventHandle wpi::util::CreateEvent(bool manualReset, bool initialState) { ManagerGuard guard; if (!guard) { return {}; @@ -115,7 +115,7 @@ WPI_EventHandle wpi::CreateEvent(bool manualReset, bool initialState) { return handle; } -void wpi::DestroyEvent(WPI_EventHandle handle) { +void wpi::util::DestroyEvent(WPI_EventHandle handle) { if ((handle >> 24) != kHandleTypeEvent) { return; } @@ -131,7 +131,7 @@ void wpi::DestroyEvent(WPI_EventHandle handle) { manager.eventIds.erase(handle & 0xffffff); } -void wpi::SetEvent(WPI_EventHandle handle) { +void wpi::util::SetEvent(WPI_EventHandle handle) { if ((handle >> 24) != kHandleTypeEvent) { return; } @@ -139,7 +139,7 @@ void wpi::SetEvent(WPI_EventHandle handle) { SetSignalObject(handle); } -void wpi::ResetEvent(WPI_EventHandle handle) { +void wpi::util::ResetEvent(WPI_EventHandle handle) { if ((handle >> 24) != kHandleTypeEvent) { return; } @@ -147,7 +147,7 @@ void wpi::ResetEvent(WPI_EventHandle handle) { ResetSignalObject(handle); } -WPI_SemaphoreHandle wpi::CreateSemaphore(int initialCount, int maximumCount) { +WPI_SemaphoreHandle wpi::util::CreateSemaphore(int initialCount, int maximumCount) { ManagerGuard guard; if (!guard) { return {}; @@ -166,7 +166,7 @@ WPI_SemaphoreHandle wpi::CreateSemaphore(int initialCount, int maximumCount) { return handle; } -void wpi::DestroySemaphore(WPI_SemaphoreHandle handle) { +void wpi::util::DestroySemaphore(WPI_SemaphoreHandle handle) { if ((handle >> 24) != kHandleTypeSemaphore) { return; } @@ -182,7 +182,7 @@ void wpi::DestroySemaphore(WPI_SemaphoreHandle handle) { manager.eventIds.erase(handle & 0xffffff); } -bool wpi::ReleaseSemaphore(WPI_SemaphoreHandle handle, int releaseCount, +bool wpi::util::ReleaseSemaphore(WPI_SemaphoreHandle handle, int releaseCount, int* prevCount) { if ((handle >> 24) != kHandleTypeSemaphore) { return false; @@ -217,11 +217,11 @@ bool wpi::ReleaseSemaphore(WPI_SemaphoreHandle handle, int releaseCount, return true; } -bool wpi::WaitForObject(WPI_Handle handle) { +bool wpi::util::WaitForObject(WPI_Handle handle) { return WaitForObject(handle, -1, nullptr); } -bool wpi::WaitForObject(WPI_Handle handle, double timeout, bool* timedOut) { +bool wpi::util::WaitForObject(WPI_Handle handle, double timeout, bool* timedOut) { WPI_Handle signaledValue; auto signaled = WaitForObjects( std::span(&handle, 1), std::span(&signaledValue, 1), timeout, timedOut); @@ -231,12 +231,12 @@ bool wpi::WaitForObject(WPI_Handle handle, double timeout, bool* timedOut) { return (signaled[0] & 0x80000000ul) == 0; } -std::span wpi::WaitForObjects(std::span handles, +std::span wpi::util::WaitForObjects(std::span handles, std::span signaled) { return WaitForObjects(handles, signaled, -1, nullptr); } -std::span wpi::WaitForObjects(std::span handles, +std::span wpi::util::WaitForObjects(std::span handles, std::span signaled, double timeout, bool* timedOut) { ManagerGuard guard; @@ -248,7 +248,7 @@ std::span wpi::WaitForObjects(std::span handles, } auto& manager = guard.GetManager(); std::unique_lock lock{manager.mutex}; - wpi::condition_variable cv; + wpi::util::condition_variable cv; bool addedWaiters = false; bool timedOutVal = false; size_t count = 0; @@ -336,7 +336,7 @@ std::span wpi::WaitForObjects(std::span handles, return signaled.subspan(0, count); } -void wpi::CreateSignalObject(WPI_Handle handle, bool manualReset, +void wpi::util::CreateSignalObject(WPI_Handle handle, bool manualReset, bool initialState) { ManagerGuard guard; if (!guard) { @@ -349,7 +349,7 @@ void wpi::CreateSignalObject(WPI_Handle handle, bool manualReset, state.autoReset = !manualReset; } -void wpi::SetSignalObject(WPI_Handle handle) { +void wpi::util::SetSignalObject(WPI_Handle handle) { ManagerGuard guard; if (!guard) { return; @@ -371,7 +371,7 @@ void wpi::SetSignalObject(WPI_Handle handle) { } } -void wpi::ResetSignalObject(WPI_Handle handle) { +void wpi::util::ResetSignalObject(WPI_Handle handle) { ManagerGuard guard; if (!guard) { return; @@ -384,7 +384,7 @@ void wpi::ResetSignalObject(WPI_Handle handle) { } } -void wpi::DestroySignalObject(WPI_Handle handle) { +void wpi::util::DestroySignalObject(WPI_Handle handle) { ManagerGuard guard; if (!guard) { return; @@ -405,49 +405,49 @@ void wpi::DestroySignalObject(WPI_Handle handle) { extern "C" { WPI_EventHandle WPI_CreateEvent(int manual_reset, int initial_state) { - return wpi::CreateEvent(manual_reset != 0, initial_state != 0); + return wpi::util::CreateEvent(manual_reset != 0, initial_state != 0); } void WPI_DestroyEvent(WPI_EventHandle handle) { - wpi::DestroyEvent(handle); + wpi::util::DestroyEvent(handle); } void WPI_SetEvent(WPI_EventHandle handle) { - wpi::SetEvent(handle); + wpi::util::SetEvent(handle); } void WPI_ResetEvent(WPI_EventHandle handle) { - wpi::ResetEvent(handle); + wpi::util::ResetEvent(handle); } WPI_SemaphoreHandle WPI_CreateSemaphore(int initial_count, int maximum_count) { - return wpi::CreateSemaphore(initial_count, maximum_count); + return wpi::util::CreateSemaphore(initial_count, maximum_count); } void WPI_DestroySemaphore(WPI_SemaphoreHandle handle) { - wpi::DestroySemaphore(handle); + wpi::util::DestroySemaphore(handle); } int WPI_ReleaseSemaphore(WPI_SemaphoreHandle handle, int release_count, int* prev_count) { - return wpi::ReleaseSemaphore(handle, release_count, prev_count); + return wpi::util::ReleaseSemaphore(handle, release_count, prev_count); } int WPI_WaitForObject(WPI_Handle handle) { - return wpi::WaitForObject(handle); + return wpi::util::WaitForObject(handle); } int WPI_WaitForObjectTimeout(WPI_Handle handle, double timeout, int* timed_out) { bool timedOutBool; - int rv = wpi::WaitForObject(handle, timeout, &timedOutBool); + int rv = wpi::util::WaitForObject(handle, timeout, &timedOutBool); *timed_out = timedOutBool ? 1 : 0; return rv; } int WPI_WaitForObjects(const WPI_Handle* handles, int handles_count, WPI_Handle* signaled) { - return wpi::WaitForObjects(std::span(handles, handles_count), + return wpi::util::WaitForObjects(std::span(handles, handles_count), std::span(signaled, handles_count)) .size(); } @@ -456,7 +456,7 @@ int WPI_WaitForObjectsTimeout(const WPI_Handle* handles, int handles_count, WPI_Handle* signaled, double timeout, int* timed_out) { bool timedOutBool; - auto signaledResult = wpi::WaitForObjects(std::span(handles, handles_count), + auto signaledResult = wpi::util::WaitForObjects(std::span(handles, handles_count), std::span(signaled, handles_count), timeout, &timedOutBool); *timed_out = timedOutBool ? 1 : 0; @@ -465,19 +465,19 @@ int WPI_WaitForObjectsTimeout(const WPI_Handle* handles, int handles_count, void WPI_CreateSignalObject(WPI_Handle handle, int manual_reset, int initial_state) { - wpi::CreateSignalObject(handle, manual_reset, initial_state); + wpi::util::CreateSignalObject(handle, manual_reset, initial_state); } void WPI_SetSignalObject(WPI_Handle handle) { - wpi::SetSignalObject(handle); + wpi::util::SetSignalObject(handle); } void WPI_ResetSignalObject(WPI_Handle handle) { - wpi::ResetSignalObject(handle); + wpi::util::ResetSignalObject(handle); } void WPI_DestroySignalObject(WPI_Handle handle) { - wpi::DestroySignalObject(handle); + wpi::util::DestroySignalObject(handle); } } // extern "C" diff --git a/wpiutil/src/main/native/cpp/fs.cpp b/wpiutil/src/main/native/cpp/fs.cpp index fe5acd97c4..03fbfdb641 100644 --- a/wpiutil/src/main/native/cpp/fs.cpp +++ b/wpiutil/src/main/native/cpp/fs.cpp @@ -100,7 +100,7 @@ static file_t openFileInternal(const path& Path, std::error_code& EC, Disp, Flags, NULL); if (H == INVALID_HANDLE_VALUE) { DWORD LastError = ::GetLastError(); - EC = wpi::mapWindowsError(LastError); + EC = wpi::util::mapWindowsError(LastError); // Provide a better error message when trying to open directories. // This only runs if we failed to open the file, so there is probably // no performances issues. @@ -121,7 +121,7 @@ static std::error_code setDeleteDisposition(HANDLE Handle, bool Delete) { Disposition.DeleteFile = Delete; if (!::SetFileInformationByHandle(Handle, FileDispositionInfo, &Disposition, sizeof(Disposition))) - return wpi::mapWindowsError(::GetLastError()); + return wpi::util::mapWindowsError(::GetLastError()); return std::error_code(); } @@ -153,7 +153,7 @@ file_t OpenFile(const path& Path, std::error_code& EC, CreationDisposition Disp, ::SetFileTime(Result, NULL, &FileTime, NULL) == 0) { DWORD LastError = ::GetLastError(); ::CloseHandle(Result); - EC = wpi::mapWindowsError(LastError); + EC = wpi::util::mapWindowsError(LastError); return WPI_kInvalidFile; } } @@ -173,7 +173,7 @@ file_t OpenFileForRead(const path& Path, std::error_code& EC, OpenFlags Flags) { int FileToFd(file_t& F, std::error_code& EC, OpenFlags Flags) { if (F == WPI_kInvalidFile) { - EC = wpi::mapWindowsError(ERROR_INVALID_HANDLE); + EC = wpi::util::mapWindowsError(ERROR_INVALID_HANDLE); return -1; } @@ -189,7 +189,7 @@ int FileToFd(file_t& F, std::error_code& EC, OpenFlags Flags) { int ResultFD = ::_open_osfhandle(intptr_t(F), CrtOpenFlags); if (ResultFD == -1) { ::CloseHandle(F); - EC = wpi::mapWindowsError(ERROR_INVALID_HANDLE); + EC = wpi::util::mapWindowsError(ERROR_INVALID_HANDLE); return -1; } @@ -249,7 +249,7 @@ file_t OpenFile(const path& Path, std::error_code& EC, CreationDisposition Disp, // Call ::open in a lambda to avoid overload resolution in RetryAfterSignal // when open is overloaded, such as in Bionic. auto Open = [&]() { return ::open(Path.c_str(), OpenFlags, Mode); }; - if ((ResultFD = wpi::sys::RetryAfterSignal(-1, Open)) < 0) { + if ((ResultFD = wpi::util::sys::RetryAfterSignal(-1, Open)) < 0) { EC = std::error_code(errno, std::generic_category()); return WPI_kInvalidFile; } diff --git a/wpiutil/src/main/native/cpp/future.cpp b/wpiutil/src/main/native/cpp/future.cpp index ac6afac038..65bbb0d9f7 100644 --- a/wpiutil/src/main/native/cpp/future.cpp +++ b/wpiutil/src/main/native/cpp/future.cpp @@ -6,7 +6,7 @@ #include -namespace wpi { +namespace wpi::util { namespace detail { PromiseFactoryBase::~PromiseFactoryBase() { @@ -123,4 +123,4 @@ PromiseFactory& PromiseFactory::GetInstance() { return inst; } -} // namespace wpi +} // namespace wpi::util diff --git a/wpiutil/src/main/native/cpp/jni/WPIUtilJNI.cpp b/wpiutil/src/main/native/cpp/jni/WPIUtilJNI.cpp index 9d0c20874a..84eae8b6bf 100644 --- a/wpiutil/src/main/native/cpp/jni/WPIUtilJNI.cpp +++ b/wpiutil/src/main/native/cpp/jni/WPIUtilJNI.cpp @@ -14,7 +14,7 @@ #include "wpi/util/print.hpp" #include "wpi/util/timestamp.h" -using namespace wpi::java; +using namespace wpi::util::java; static bool mockTimeEnabled = false; static uint64_t mockNow = 0; @@ -34,19 +34,19 @@ static const JExceptionInit exceptions[] = { {"java/lang/NullPointerException", &nullPointerEx}, {"org/wpilib/util/runtime/MsvcRuntimeException", &msvcRuntimeEx}}; -void wpi::ThrowIllegalArgumentException(JNIEnv* env, std::string_view msg) { +void wpi::util::ThrowIllegalArgumentException(JNIEnv* env, std::string_view msg) { illegalArgEx.Throw(env, msg); } -void wpi::ThrowIndexOobException(JNIEnv* env, std::string_view msg) { +void wpi::util::ThrowIndexOobException(JNIEnv* env, std::string_view msg) { indexOobEx.Throw(env, msg); } -void wpi::ThrowIOException(JNIEnv* env, std::string_view msg) { +void wpi::util::ThrowIOException(JNIEnv* env, std::string_view msg) { ioEx.Throw(env, msg); } -void wpi::ThrowNullPointerException(JNIEnv* env, std::string_view msg) { +void wpi::util::ThrowNullPointerException(JNIEnv* env, std::string_view msg) { nullPointerEx.Throw(env, msg); } @@ -98,7 +98,7 @@ Java_org_wpilib_util_WPIUtilJNI_checkMsvcRuntime &expectedMinor, &runtimePath)) { static jmethodID ctor = env->GetMethodID(msvcRuntimeEx, "", "(IIIILjava/lang/String;)V"); - jstring jmsvcruntime = MakeJString(env, wpi::to_string_view(&runtimePath)); + jstring jmsvcruntime = MakeJString(env, wpi::util::to_string_view(&runtimePath)); jobject exception = env->NewObject(msvcRuntimeEx, ctor, foundMajor, foundMinor, expectedMajor, expectedMinor, jmsvcruntime); @@ -116,7 +116,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_util_WPIUtilJNI_writeStderr (JNIEnv* env, jclass, jstring str) { - wpi::print(stderr, "{}", JStringRef{env, str}.str()); + wpi::util::print(stderr, "{}", JStringRef{env, str}.str()); } /* @@ -129,10 +129,10 @@ Java_org_wpilib_util_WPIUtilJNI_enableMockTime (JNIEnv*, jclass) { #ifdef __FRC_SYSTEMCORE__ - wpi::print(stderr, "WPIUtil: Mocking time is not available on systemcore\n"); + wpi::util::print(stderr, "WPIUtil: Mocking time is not available on systemcore\n"); #else mockTimeEnabled = true; - wpi::SetNowImpl([] { return mockNow; }); + wpi::util::SetNowImpl([] { return mockNow; }); #endif } @@ -146,7 +146,7 @@ Java_org_wpilib_util_WPIUtilJNI_disableMockTime (JNIEnv*, jclass) { mockTimeEnabled = false; - wpi::SetNowImpl(nullptr); + wpi::util::SetNowImpl(nullptr); } /* @@ -173,7 +173,7 @@ Java_org_wpilib_util_WPIUtilJNI_now if (mockTimeEnabled) { return mockNow; } else { - return wpi::Now(); + return wpi::util::Now(); } } @@ -186,7 +186,7 @@ JNIEXPORT jlong JNICALL Java_org_wpilib_util_WPIUtilJNI_getSystemTime (JNIEnv*, jclass) { - return wpi::GetSystemTime(); + return wpi::util::GetSystemTime(); } /* @@ -198,7 +198,7 @@ JNIEXPORT jint JNICALL Java_org_wpilib_util_WPIUtilJNI_createEvent (JNIEnv*, jclass, jboolean manualReset, jboolean initialState) { - return wpi::CreateEvent(manualReset, initialState); + return wpi::util::CreateEvent(manualReset, initialState); } /* @@ -210,7 +210,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_util_WPIUtilJNI_destroyEvent (JNIEnv*, jclass, jint eventHandle) { - wpi::DestroyEvent(eventHandle); + wpi::util::DestroyEvent(eventHandle); } /* @@ -222,7 +222,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_util_WPIUtilJNI_setEvent (JNIEnv*, jclass, jint eventHandle) { - wpi::SetEvent(eventHandle); + wpi::util::SetEvent(eventHandle); } /* @@ -234,7 +234,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_util_WPIUtilJNI_resetEvent (JNIEnv*, jclass, jint eventHandle) { - wpi::ResetEvent(eventHandle); + wpi::util::ResetEvent(eventHandle); } /* @@ -246,7 +246,7 @@ JNIEXPORT jint JNICALL Java_org_wpilib_util_WPIUtilJNI_createSemaphore (JNIEnv*, jclass, jint initialCount, jint maximumCount) { - return wpi::CreateSemaphore(initialCount, maximumCount); + return wpi::util::CreateSemaphore(initialCount, maximumCount); } /* @@ -258,7 +258,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_util_WPIUtilJNI_destroySemaphore (JNIEnv*, jclass, jint semHandle) { - wpi::DestroySemaphore(semHandle); + wpi::util::DestroySemaphore(semHandle); } /* @@ -270,7 +270,7 @@ JNIEXPORT jboolean JNICALL Java_org_wpilib_util_WPIUtilJNI_releaseSemaphore (JNIEnv*, jclass, jint semHandle, jint releaseCount) { - return wpi::ReleaseSemaphore(semHandle, releaseCount); + return wpi::util::ReleaseSemaphore(semHandle, releaseCount); } /* @@ -282,7 +282,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_util_WPIUtilJNI_waitForObject (JNIEnv* env, jclass, jint handle) { - if (!wpi::WaitForObject(handle)) { + if (!wpi::util::WaitForObject(handle)) { interruptedEx.Throw(env, "WaitForObject interrupted"); } } @@ -297,7 +297,7 @@ Java_org_wpilib_util_WPIUtilJNI_waitForObjectTimeout (JNIEnv* env, jclass, jint handle, jdouble timeout) { bool timedOut; - if (!wpi::WaitForObject(handle, timeout, &timedOut) && !timedOut) { + if (!wpi::util::WaitForObject(handle, timeout, &timedOut) && !timedOut) { interruptedEx.Throw(env, "WaitForObject interrupted"); return false; } @@ -314,13 +314,13 @@ Java_org_wpilib_util_WPIUtilJNI_waitForObjects (JNIEnv* env, jclass, jintArray handles) { JSpan handlesArr{env, handles}; - wpi::SmallVector signaledBuf; + wpi::util::SmallVector signaledBuf; signaledBuf.resize(handlesArr.size()); std::span handlesArr2{ reinterpret_cast(handlesArr.data()), handlesArr.size()}; - auto signaled = wpi::WaitForObjects(handlesArr2, signaledBuf); + auto signaled = wpi::util::WaitForObjects(handlesArr2, signaledBuf); if (signaled.empty()) { interruptedEx.Throw(env, "WaitForObjects interrupted"); return nullptr; @@ -338,7 +338,7 @@ Java_org_wpilib_util_WPIUtilJNI_waitForObjectsTimeout (JNIEnv* env, jclass, jintArray handles, jdouble timeout) { JSpan handlesArr{env, handles}; - wpi::SmallVector signaledBuf; + wpi::util::SmallVector signaledBuf; signaledBuf.resize(handlesArr.size()); std::span handlesArr2{ reinterpret_cast(handlesArr.data()), @@ -346,7 +346,7 @@ Java_org_wpilib_util_WPIUtilJNI_waitForObjectsTimeout bool timedOut; auto signaled = - wpi::WaitForObjects(handlesArr2, signaledBuf, timeout, &timedOut); + wpi::util::WaitForObjects(handlesArr2, signaledBuf, timeout, &timedOut); if (signaled.empty() && !timedOut) { interruptedEx.Throw(env, "WaitForObjects interrupted"); return nullptr; @@ -363,7 +363,7 @@ JNIEXPORT jlong JNICALL Java_org_wpilib_util_WPIUtilJNI_allocateRawFrame (JNIEnv*, jclass) { - return reinterpret_cast(new wpi::RawFrame); + return reinterpret_cast(new wpi::util::RawFrame); } /* @@ -375,7 +375,7 @@ JNIEXPORT void JNICALL Java_org_wpilib_util_WPIUtilJNI_freeRawFrame (JNIEnv*, jclass, jlong frame) { - delete reinterpret_cast(frame); + delete reinterpret_cast(frame); } /* @@ -387,9 +387,9 @@ JNIEXPORT jlong JNICALL Java_org_wpilib_util_WPIUtilJNI_getRawFrameDataPtr (JNIEnv* env, jclass, jlong frame) { - auto* f = reinterpret_cast(frame); + auto* f = reinterpret_cast(frame); if (!f) { - wpi::ThrowNullPointerException(env, "frame is null"); + wpi::util::ThrowNullPointerException(env, "frame is null"); return 0; } return reinterpret_cast(f->data); @@ -405,14 +405,14 @@ Java_org_wpilib_util_WPIUtilJNI_setRawFrameData (JNIEnv* env, jclass, jlong frame, jobject data, jint size, jint width, jint height, jint stride, jint pixelFormat) { - auto* f = reinterpret_cast(frame); + auto* f = reinterpret_cast(frame); if (!f) { - wpi::ThrowNullPointerException(env, "frame is null"); + wpi::util::ThrowNullPointerException(env, "frame is null"); return; } auto buf = env->GetDirectBufferAddress(data); if (!buf) { - wpi::ThrowNullPointerException(env, "data is null"); + wpi::util::ThrowNullPointerException(env, "data is null"); return; } // there's no way to free a passed-in direct byte buffer @@ -433,9 +433,9 @@ JNIEXPORT void JNICALL Java_org_wpilib_util_WPIUtilJNI_setRawFrameTime (JNIEnv* env, jclass, jlong frame, jlong time, jint timeSource) { - auto* f = reinterpret_cast(frame); + auto* f = reinterpret_cast(frame); if (!f) { - wpi::ThrowNullPointerException(env, "frame is null"); + wpi::util::ThrowNullPointerException(env, "frame is null"); return; } f->timestamp = time; @@ -452,9 +452,9 @@ Java_org_wpilib_util_WPIUtilJNI_setRawFrameInfo (JNIEnv* env, jclass, jlong frame, jint size, jint width, jint height, jint stride, jint pixelFormat) { - auto* f = reinterpret_cast(frame); + auto* f = reinterpret_cast(frame); if (!f) { - wpi::ThrowNullPointerException(env, "frame is null"); + wpi::util::ThrowNullPointerException(env, "frame is null"); return; } f->width = width; diff --git a/wpiutil/src/main/native/cpp/jni/WPIUtilJNI.hpp b/wpiutil/src/main/native/cpp/jni/WPIUtilJNI.hpp index 4d08fdbf8b..efe0099f4e 100644 --- a/wpiutil/src/main/native/cpp/jni/WPIUtilJNI.hpp +++ b/wpiutil/src/main/native/cpp/jni/WPIUtilJNI.hpp @@ -8,11 +8,11 @@ #include -namespace wpi { +namespace wpi::util { void ThrowIllegalArgumentException(JNIEnv* env, std::string_view msg); void ThrowIndexOobException(JNIEnv* env, std::string_view msg); void ThrowIOException(JNIEnv* env, std::string_view msg); void ThrowNullPointerException(JNIEnv* env, std::string_view msg); -} // namespace wpi +} // namespace wpi::util diff --git a/wpiutil/src/main/native/cpp/protobuf/Protobuf.cpp b/wpiutil/src/main/native/cpp/protobuf/Protobuf.cpp index b08ff53f04..d7300aa45f 100644 --- a/wpiutil/src/main/native/cpp/protobuf/Protobuf.cpp +++ b/wpiutil/src/main/native/cpp/protobuf/Protobuf.cpp @@ -11,7 +11,7 @@ #include "wpi/util/SmallVector.hpp" -using namespace wpi; +using namespace wpi::util; std::string detail::GetTypeString(const pb_msgdesc_t* msg) { return fmt::format("proto:{}", msg->proto_name); @@ -52,7 +52,7 @@ bool detail::WriteFromStdVector(pb_ostream_t* stream, const pb_byte_t* buf, bool detail::WriteSubmessage(pb_ostream_t* stream, const pb_msgdesc_t* desc, const void* msg) { // Write the submessage to a separate buffer - wpi::SmallVector buf; + wpi::util::SmallVector buf; pb_ostream_t subStream{ .callback = WriteFromSmallVector, .state = &buf, diff --git a/wpiutil/src/main/native/cpp/raw_istream.cpp b/wpiutil/src/main/native/cpp/raw_istream.cpp index 65e104a4d6..27c717144f 100644 --- a/wpiutil/src/main/native/cpp/raw_istream.cpp +++ b/wpiutil/src/main/native/cpp/raw_istream.cpp @@ -31,7 +31,7 @@ #endif #endif -using namespace wpi; +using namespace wpi::util; std::string_view raw_istream::getline(SmallVectorImpl& buf, int maxLen) { buf.clear(); diff --git a/wpiutil/src/main/native/cpp/sendable/SendableRegistry.cpp b/wpiutil/src/main/native/cpp/sendable/SendableRegistry.cpp index 65e940a225..51f5e5cdce 100644 --- a/wpiutil/src/main/native/cpp/sendable/SendableRegistry.cpp +++ b/wpiutil/src/main/native/cpp/sendable/SendableRegistry.cpp @@ -17,7 +17,7 @@ #include "wpi/util/sendable/Sendable.hpp" #include "wpi/util/sendable/SendableBuilder.hpp" -using namespace wpi; +using namespace wpi::util; namespace { struct Component { @@ -26,7 +26,7 @@ struct Component { std::string name; std::string subsystem = "Ungrouped"; Sendable* parent = nullptr; - wpi::SmallVector, 2> data; + wpi::util::SmallVector, 2> data; void SetName(std::string_view moduleType, int channel) { name = fmt::format("{}[{}]", moduleType, channel); @@ -38,10 +38,10 @@ struct Component { }; struct SendableRegistryInst { - wpi::recursive_mutex mutex; + wpi::util::recursive_mutex mutex; - wpi::UidVector, 32> components; - wpi::DenseMap componentMap; + wpi::util::UidVector, 32> components; + wpi::util::DenseMap componentMap; int nextDataHandle = 0; Component& GetOrAdd(void* sendable, SendableRegistry::UID* uid = nullptr); @@ -72,11 +72,11 @@ static SendableRegistryInst& GetInstance() { } #ifndef __FRC_SYSTEMCORE__ -namespace wpi::impl { +namespace wpi::util::impl { void ResetSendableRegistry() { std::make_unique().swap(GetInstanceHolder()); } -} // namespace wpi::impl +} // namespace wpi::util::impl #endif void SendableRegistry::EnsureInitialized() { diff --git a/wpiutil/src/main/native/cpp/sha1.cpp b/wpiutil/src/main/native/cpp/sha1.cpp index 97b287b543..9da4fa918f 100644 --- a/wpiutil/src/main/native/cpp/sha1.cpp +++ b/wpiutil/src/main/native/cpp/sha1.cpp @@ -26,7 +26,7 @@ #include "wpi/util/raw_istream.hpp" #include "wpi/util/raw_ostream.hpp" -using namespace wpi; +using namespace wpi::util; static const size_t BLOCK_INTS = 16; /* number of 32bit integers per SHA1 block */ diff --git a/wpiutil/src/main/native/cpp/string.cpp b/wpiutil/src/main/native/cpp/string.cpp index dc9dab9e6b..d4c766da16 100644 --- a/wpiutil/src/main/native/cpp/string.cpp +++ b/wpiutil/src/main/native/cpp/string.cpp @@ -46,7 +46,7 @@ char* WPI_AllocateString(struct WPI_String* wpiString, size_t length) { wpiString->str = nullptr; return &writeBuffer; } - char* str = static_cast(wpi::safe_malloc(length)); + char* str = static_cast(wpi::util::safe_malloc(length)); wpiString->str = str; wpiString->len = length; return str; @@ -61,7 +61,7 @@ void WPI_FreeString(const struct WPI_String* wpiString) { struct WPI_String* WPI_AllocateStringArray(size_t length) { return static_cast( - wpi::safe_malloc(length * sizeof(struct WPI_String))); + wpi::util::safe_malloc(length * sizeof(struct WPI_String))); } void WPI_FreeStringArray(const struct WPI_String* wpiStringArray, diff --git a/wpiutil/src/main/native/cpp/struct/DynamicStruct.cpp b/wpiutil/src/main/native/cpp/struct/DynamicStruct.cpp index a61a615e59..684c28c095 100644 --- a/wpiutil/src/main/native/cpp/struct/DynamicStruct.cpp +++ b/wpiutil/src/main/native/cpp/struct/DynamicStruct.cpp @@ -16,7 +16,7 @@ #include "wpi/util/raw_ostream.hpp" #include "wpi/util/struct/SchemaParser.hpp" -using namespace wpi; +using namespace wpi::util; static size_t TypeToSize(StructFieldType type) { switch (type) { @@ -111,7 +111,7 @@ const StructFieldDescriptor* StructDescriptor::FindFieldByName( } bool StructDescriptor::CheckCircular( - wpi::SmallVectorImpl& stack) const { + wpi::util::SmallVectorImpl& stack) const { stack.emplace_back(this); for (auto&& ref : m_references) { if (std::find(stack.begin(), stack.end(), ref) != stack.end()) { @@ -126,7 +126,7 @@ bool StructDescriptor::CheckCircular( } std::string StructDescriptor::CalculateOffsets( - wpi::SmallVectorImpl& stack) { + wpi::util::SmallVectorImpl& stack) { size_t offset = 0; unsigned int shift = 0; size_t prevBitfieldSize = 0; @@ -282,7 +282,7 @@ const StructDescriptor* StructDescriptorDatabase::Add(std::string_view name, theStruct.m_valid = isValid; if (isValid) { // we have all the info needed, so calculate field offset & shift - wpi::SmallVector stack; + wpi::util::SmallVector stack; auto err2 = theStruct.CalculateOffsets(stack); if (!err2.empty()) { *err = std::move(err2); @@ -290,10 +290,10 @@ const StructDescriptor* StructDescriptorDatabase::Add(std::string_view name, } } else { // check for circular reference - wpi::SmallVector stack; + wpi::util::SmallVector stack; if (!theStruct.CheckCircular(stack)) { - wpi::SmallString<128> buf; - wpi::raw_svector_ostream os{buf}; + wpi::util::SmallString<128> buf; + wpi::util::raw_svector_ostream os{buf}; for (auto&& elem : stack) { if (!buf.empty()) { os << " <- "; diff --git a/wpiutil/src/main/native/cpp/struct/SchemaParser.cpp b/wpiutil/src/main/native/cpp/struct/SchemaParser.cpp index 49cf3530e6..f32b4c0057 100644 --- a/wpiutil/src/main/native/cpp/struct/SchemaParser.cpp +++ b/wpiutil/src/main/native/cpp/struct/SchemaParser.cpp @@ -11,9 +11,9 @@ #include "wpi/util/StringExtras.hpp" -using namespace wpi::structparser; +using namespace wpi::util::structparser; -std::string_view wpi::structparser::ToString(Token::Kind kind) { +std::string_view wpi::util::structparser::ToString(Token::Kind kind) { switch (kind) { case Token::kInteger: return "integer"; diff --git a/wpiutil/src/main/native/cpp/timestamp.cpp b/wpiutil/src/main/native/cpp/timestamp.cpp index 6215bd5ab1..3ec3acf98f 100644 --- a/wpiutil/src/main/native/cpp/timestamp.cpp +++ b/wpiutil/src/main/native/cpp/timestamp.cpp @@ -78,7 +78,7 @@ static const uint64_t offset_val = timestamp(); static const uint64_t frequency_val = update_frequency(); #endif -uint64_t wpi::NowDefault() { +uint64_t wpi::util::NowDefault() { #ifdef _WIN32 assert(offset_val > 0u); assert(frequency_val > 0u); @@ -95,36 +95,36 @@ uint64_t wpi::NowDefault() { #endif } -static std::atomic now_impl{wpi::NowDefault}; +static std::atomic now_impl{wpi::util::NowDefault}; -void wpi::SetNowImpl(uint64_t (*func)(void)) { +void wpi::util::SetNowImpl(uint64_t (*func)(void)) { now_impl = func ? func : NowDefault; } -uint64_t wpi::Now() { +uint64_t wpi::util::Now() { return (now_impl.load())(); } -uint64_t wpi::GetSystemTime() { +uint64_t wpi::util::GetSystemTime() { return time_since_epoch(); } extern "C" { uint64_t WPI_NowDefault(void) { - return wpi::NowDefault(); + return wpi::util::NowDefault(); } void WPI_SetNowImpl(uint64_t (*func)(void)) { - wpi::SetNowImpl(func); + wpi::util::SetNowImpl(func); } uint64_t WPI_Now(void) { - return wpi::Now(); + return wpi::util::Now(); } uint64_t WPI_GetSystemTime(void) { - return wpi::GetSystemTime(); + return wpi::util::GetSystemTime(); } } // extern "C" diff --git a/wpiutil/src/main/native/include/wpi/util/Algorithm.hpp b/wpiutil/src/main/native/include/wpi/util/Algorithm.hpp index 112bfc3485..64ee3b647a 100644 --- a/wpiutil/src/main/native/include/wpi/util/Algorithm.hpp +++ b/wpiutil/src/main/native/include/wpi/util/Algorithm.hpp @@ -9,7 +9,7 @@ #include #include -namespace wpi { +namespace wpi::util { // Binary insertion into vector; std::log(n) efficiency. template @@ -32,4 +32,4 @@ constexpr void for_each(F&& f, Ts&&... elems) { }(std::index_sequence_for{}); } -} // namespace wpi +} // namespace wpi::util diff --git a/wpiutil/src/main/native/include/wpi/util/Base64.hpp b/wpiutil/src/main/native/include/wpi/util/Base64.hpp index 7bd09cd674..e6271410b4 100644 --- a/wpiutil/src/main/native/include/wpi/util/Base64.hpp +++ b/wpiutil/src/main/native/include/wpi/util/Base64.hpp @@ -13,7 +13,7 @@ #include #include -namespace wpi { +namespace wpi::util { template class SmallVectorImpl; class raw_ostream; @@ -44,6 +44,6 @@ void Base64Encode(std::span plain, std::string* encoded); std::string_view Base64Encode(std::span plain, SmallVectorImpl& buf); -} // namespace wpi +} // namespace wpi::util #endif // WPIUTIL_WPI_UTIL_BASE64_HPP_ diff --git a/wpiutil/src/main/native/include/wpi/util/CallbackManager.hpp b/wpiutil/src/main/native/include/wpi/util/CallbackManager.hpp index 993fcdd500..d3a359276a 100644 --- a/wpiutil/src/main/native/include/wpi/util/CallbackManager.hpp +++ b/wpiutil/src/main/native/include/wpi/util/CallbackManager.hpp @@ -19,7 +19,7 @@ #include "wpi/util/mutex.hpp" #include "wpi/util/raw_ostream.hpp" -namespace wpi { +namespace wpi::util { template class CallbackListenerData { @@ -47,7 +47,7 @@ template >, typename TNotifierData = TUserInfo> -class CallbackThread : public wpi::SafeThread { +class CallbackThread : public wpi::util::SafeThread { public: using UserInfo = TUserInfo; using NotifierData = TNotifierData; @@ -67,10 +67,10 @@ class CallbackThread : public wpi::SafeThread { void Main() override; - wpi::UidVector m_listeners; + wpi::util::UidVector m_listeners; std::queue> m_queue; - wpi::condition_variable m_queue_empty; + wpi::util::condition_variable m_queue_empty; struct Poller { void Terminate() { @@ -81,12 +81,12 @@ class CallbackThread : public wpi::SafeThread { poll_cond.notify_all(); } std::queue poll_queue; - wpi::mutex poll_mutex; - wpi::condition_variable poll_cond; + wpi::util::mutex poll_mutex; + wpi::util::condition_variable poll_cond; bool terminating = false; bool canceling = false; }; - wpi::UidVector, 64> m_pollers; + wpi::util::UidVector, 64> m_pollers; std::function m_on_start; std::function m_on_exit; @@ -379,17 +379,17 @@ class CallbackManager { thr->m_cond.notify_one(); } - typename wpi::SafeThreadOwner::Proxy GetThread() const { + typename wpi::util::SafeThreadOwner::Proxy GetThread() const { return m_owner.GetThread(); } private: - wpi::SafeThreadOwner m_owner; + wpi::util::SafeThreadOwner m_owner; std::function m_on_start; std::function m_on_exit; }; -} // namespace wpi +} // namespace wpi::util #endif // WPIUTIL_WPI_UTIL_CALLBACKMANAGER_HPP_ diff --git a/wpiutil/src/main/native/include/wpi/util/DecayedDerivedFrom.hpp b/wpiutil/src/main/native/include/wpi/util/DecayedDerivedFrom.hpp index c776c9ce9c..63a6f86536 100644 --- a/wpiutil/src/main/native/include/wpi/util/DecayedDerivedFrom.hpp +++ b/wpiutil/src/main/native/include/wpi/util/DecayedDerivedFrom.hpp @@ -7,11 +7,11 @@ #include #include -namespace wpi { +namespace wpi::util { template concept DecayedDerivedFrom = std::derived_from, std::decay_t> && std::convertible_to*, std::decay_t*>; -} // namespace wpi +} // namespace wpi::util diff --git a/wpiutil/src/main/native/include/wpi/util/Demangle.hpp b/wpiutil/src/main/native/include/wpi/util/Demangle.hpp index 273b5e688e..b44ba74e64 100644 --- a/wpiutil/src/main/native/include/wpi/util/Demangle.hpp +++ b/wpiutil/src/main/native/include/wpi/util/Demangle.hpp @@ -9,7 +9,7 @@ #include #include -namespace wpi { +namespace wpi::util { /** * Demangle a C++ symbol. @@ -28,6 +28,6 @@ std::string GetTypeName(const T& type) { return Demangle(typeid(type).name()); } -} // namespace wpi +} // namespace wpi::util #endif // WPIUTIL_WPI_UTIL_DEMANGLE_HPP_ diff --git a/wpiutil/src/main/native/include/wpi/util/EventVector.hpp b/wpiutil/src/main/native/include/wpi/util/EventVector.hpp index a0750d2a03..d9c4014e25 100644 --- a/wpiutil/src/main/native/include/wpi/util/EventVector.hpp +++ b/wpiutil/src/main/native/include/wpi/util/EventVector.hpp @@ -8,10 +8,10 @@ #include "wpi/util/Synchronization.h" #include "wpi/util/mutex.hpp" -namespace wpi { +namespace wpi::util { struct EventVector { - wpi::mutex mutex; - wpi::SmallVector events; + wpi::util::mutex mutex; + wpi::util::SmallVector events; /** * Adds an event to the event vector. @@ -44,8 +44,8 @@ struct EventVector { void Wakeup() { std::scoped_lock lock{mutex}; for (auto&& handle : events) { - wpi::SetEvent(handle); + wpi::util::SetEvent(handle); } } }; -} // namespace wpi +} // namespace wpi::util diff --git a/wpiutil/src/main/native/include/wpi/util/FastQueue.hpp b/wpiutil/src/main/native/include/wpi/util/FastQueue.hpp index 2049ccee8a..86aff9790e 100644 --- a/wpiutil/src/main/native/include/wpi/util/FastQueue.hpp +++ b/wpiutil/src/main/native/include/wpi/util/FastQueue.hpp @@ -53,7 +53,7 @@ // Allocates memory sparingly, and only once if the original maximum size // estimate is never exceeded. -namespace wpi { +namespace wpi::util { template class FastQueue @@ -554,4 +554,4 @@ private: size_t largestBlockSize; }; -} // end namespace wpi +} // end namespace wpi::util diff --git a/wpiutil/src/main/native/include/wpi/util/Logger.hpp b/wpiutil/src/main/native/include/wpi/util/Logger.hpp index f17482f44a..3c6d69ab3e 100644 --- a/wpiutil/src/main/native/include/wpi/util/Logger.hpp +++ b/wpiutil/src/main/native/include/wpi/util/Logger.hpp @@ -10,7 +10,7 @@ #include -namespace wpi { +namespace wpi::util { enum LogLevel { WPI_LOG_CRITICAL = 50, @@ -73,22 +73,22 @@ class Logger { } #define WPI_ERROR(inst, format, ...) \ - WPI_LOG(inst, ::wpi::WPI_LOG_ERROR, format __VA_OPT__(, ) __VA_ARGS__) + WPI_LOG(inst, ::wpi::util::WPI_LOG_ERROR, format __VA_OPT__(, ) __VA_ARGS__) #define WPI_WARNING(inst, format, ...) \ - WPI_LOG(inst, ::wpi::WPI_LOG_WARNING, format __VA_OPT__(, ) __VA_ARGS__) + WPI_LOG(inst, ::wpi::util::WPI_LOG_WARNING, format __VA_OPT__(, ) __VA_ARGS__) #define WPI_INFO(inst, format, ...) \ - WPI_LOG(inst, ::wpi::WPI_LOG_INFO, format __VA_OPT__(, ) __VA_ARGS__) + WPI_LOG(inst, ::wpi::util::WPI_LOG_INFO, format __VA_OPT__(, ) __VA_ARGS__) #define WPI_DEBUG(inst, format, ...) \ - WPI_LOG(inst, ::wpi::WPI_LOG_DEBUG, format __VA_OPT__(, ) __VA_ARGS__) + WPI_LOG(inst, ::wpi::util::WPI_LOG_DEBUG, format __VA_OPT__(, ) __VA_ARGS__) #define WPI_DEBUG1(inst, format, ...) \ - WPI_LOG(inst, ::wpi::WPI_LOG_DEBUG1, format __VA_OPT__(, ) __VA_ARGS__) + WPI_LOG(inst, ::wpi::util::WPI_LOG_DEBUG1, format __VA_OPT__(, ) __VA_ARGS__) #define WPI_DEBUG2(inst, format, ...) \ - WPI_LOG(inst, ::wpi::WPI_LOG_DEBUG2, format __VA_OPT__(, ) __VA_ARGS__) + WPI_LOG(inst, ::wpi::util::WPI_LOG_DEBUG2, format __VA_OPT__(, ) __VA_ARGS__) #define WPI_DEBUG3(inst, format, ...) \ - WPI_LOG(inst, ::wpi::WPI_LOG_DEBUG3, format __VA_OPT__(, ) __VA_ARGS__) + WPI_LOG(inst, ::wpi::util::WPI_LOG_DEBUG3, format __VA_OPT__(, ) __VA_ARGS__) #define WPI_DEBUG4(inst, format, ...) \ - WPI_LOG(inst, ::wpi::WPI_LOG_DEBUG4, format __VA_OPT__(, ) __VA_ARGS__) + WPI_LOG(inst, ::wpi::util::WPI_LOG_DEBUG4, format __VA_OPT__(, ) __VA_ARGS__) -} // namespace wpi +} // namespace wpi::util #endif // WPIUTIL_WPI_UTIL_LOGGER_HPP_ diff --git a/wpiutil/src/main/native/include/wpi/util/MappedFileRegion.hpp b/wpiutil/src/main/native/include/wpi/util/MappedFileRegion.hpp index 33d3bb9df0..9322236971 100644 --- a/wpiutil/src/main/native/include/wpi/util/MappedFileRegion.hpp +++ b/wpiutil/src/main/native/include/wpi/util/MappedFileRegion.hpp @@ -18,7 +18,7 @@ using file_t = int; #endif } // namespace fs -namespace wpi { +namespace wpi::util { class MappedFileRegion { public: @@ -83,4 +83,4 @@ class MappedFileRegion { #endif }; -} // namespace wpi +} // namespace wpi::util diff --git a/wpiutil/src/main/native/include/wpi/util/NullDeleter.hpp b/wpiutil/src/main/native/include/wpi/util/NullDeleter.hpp index 26146e5ea6..d4b441944f 100644 --- a/wpiutil/src/main/native/include/wpi/util/NullDeleter.hpp +++ b/wpiutil/src/main/native/include/wpi/util/NullDeleter.hpp @@ -4,7 +4,7 @@ #pragma once -namespace wpi { +namespace wpi::util { // A struct to use as a deleter when a std::shared_ptr must wrap a raw pointer // that is being deleted by someone else. @@ -13,4 +13,4 @@ struct NullDeleter { void operator()(T*) const noexcept {}; }; -} // namespace wpi +} // namespace wpi::util diff --git a/wpiutil/src/main/native/include/wpi/util/RawFrame.h b/wpiutil/src/main/native/include/wpi/util/RawFrame.h index ce44698e92..2b7829fbb6 100644 --- a/wpiutil/src/main/native/include/wpi/util/RawFrame.h +++ b/wpiutil/src/main/native/include/wpi/util/RawFrame.h @@ -61,18 +61,18 @@ enum WPI_PixelFormat { }; /** - * Timestamp metadata. Timebase is the same as wpi::Now + * Timestamp metadata. Timebase is the same as wpi::util::Now */ enum WPI_TimestampSource { WPI_TIMESRC_UNKNOWN = 0, // unknown - WPI_TIMESRC_FRAME_DEQUEUE, // wpi::Now when the new frame was dequeued by + WPI_TIMESRC_FRAME_DEQUEUE, // wpi::util::Now when the new frame was dequeued by // CSCore. Does not account for camera exposure // time or V4L latency. WPI_TIMESRC_V4L_EOF, // End of Frame. Same as V4L2_BUF_FLAG_TSTAMP_SRC_EOF, - // translated into wpi::Now's timebase. + // translated into wpi::util::Now's timebase. WPI_TIMESRC_V4L_SOE, // Start of Exposure. Same as // V4L2_BUF_FLAG_TSTAMP_SRC_SOE, translated into - // wpi::Now's timebase. + // wpi::util::Now's timebase. }; // Returns nonzero if the frame data was allocated/reallocated @@ -88,7 +88,7 @@ void WPI_SetRawFrameData(WPI_RawFrame* frame, void* data, size_t size, #endif #ifdef __cplusplus -namespace wpi { +namespace wpi::util { struct RawFrame : public WPI_RawFrame { RawFrame() { data = nullptr; @@ -135,7 +135,7 @@ struct RawFrame : public WPI_RawFrame { }; #ifdef WPI_RAWFRAME_JNI -template T> +template T> void SetFrameData(JNIEnv* env, jclass rawFrameCls, jobject jframe, const T& frame, bool newData) { if (newData) { @@ -160,7 +160,7 @@ void SetFrameData(JNIEnv* env, jclass rawFrameCls, jobject jframe, } #endif -} // namespace wpi +} // namespace wpi::util #endif #endif // WPIUTIL_WPI_UTIL_RAWFRAME_H_ diff --git a/wpiutil/src/main/native/include/wpi/util/SafeThread.hpp b/wpiutil/src/main/native/include/wpi/util/SafeThread.hpp index bd86803e41..536f995e3c 100644 --- a/wpiutil/src/main/native/include/wpi/util/SafeThread.hpp +++ b/wpiutil/src/main/native/include/wpi/util/SafeThread.hpp @@ -14,7 +14,7 @@ #include "wpi/util/condition_variable.hpp" #include "wpi/util/mutex.hpp" -namespace wpi { +namespace wpi::util { /** * Base class for SafeThreadOwner threads. @@ -25,7 +25,7 @@ class SafeThreadBase { virtual void Main() = 0; virtual void Stop() = 0; - mutable wpi::mutex m_mutex; + mutable wpi::util::mutex m_mutex; std::atomic_bool m_active{true}; std::thread::id m_threadId; }; @@ -34,7 +34,7 @@ class SafeThread : public SafeThreadBase { public: void Stop() override; - wpi::condition_variable m_cond; + wpi::util::condition_variable m_cond; }; class SafeThreadEvent : public SafeThreadBase { @@ -55,11 +55,11 @@ class SafeThreadProxyBase { public: explicit SafeThreadProxyBase(std::shared_ptr thr); explicit operator bool() const { return m_thread != nullptr; } - std::unique_lock& GetLock() { return m_lock; } + std::unique_lock& GetLock() { return m_lock; } protected: std::shared_ptr m_thread; - std::unique_lock m_lock; + std::unique_lock m_lock; }; /** @@ -110,7 +110,7 @@ class SafeThreadOwnerBase { std::shared_ptr GetThreadSharedPtr() const; private: - mutable wpi::mutex m_mutex; + mutable wpi::util::mutex m_mutex; std::thread m_stdThread; std::weak_ptr m_thread; std::atomic_bool m_joinAtExit{true}; @@ -140,6 +140,6 @@ class SafeThreadOwner : public detail::SafeThreadOwnerBase { } }; -} // namespace wpi +} // namespace wpi::util #endif // WPIUTIL_WPI_UTIL_SAFETHREAD_HPP_ diff --git a/wpiutil/src/main/native/include/wpi/util/SpanExtras.hpp b/wpiutil/src/main/native/include/wpi/util/SpanExtras.hpp index 790a66f0ea..6ccb5542ab 100644 --- a/wpiutil/src/main/native/include/wpi/util/SpanExtras.hpp +++ b/wpiutil/src/main/native/include/wpi/util/SpanExtras.hpp @@ -7,7 +7,7 @@ #include #include -namespace wpi { +namespace wpi::util { /// Drop the first \p N elements of the array. template @@ -55,4 +55,4 @@ constexpr std::span take_back(std::span in, return drop_front(in, length - n); } -} // namespace wpi +} // namespace wpi::util diff --git a/wpiutil/src/main/native/include/wpi/util/StackTrace.hpp b/wpiutil/src/main/native/include/wpi/util/StackTrace.hpp index 98dfbdbde1..ca82ceb832 100644 --- a/wpiutil/src/main/native/include/wpi/util/StackTrace.hpp +++ b/wpiutil/src/main/native/include/wpi/util/StackTrace.hpp @@ -7,7 +7,7 @@ #include -namespace wpi { +namespace wpi::util { /** * Get a stack trace, ignoring the first "offset" symbols. @@ -30,6 +30,6 @@ std::string GetStackTraceDefault(int offset); */ void SetGetStackTraceImpl(std::string (*func)(int offset)); -} // namespace wpi +} // namespace wpi::util #endif // WPIUTIL_WPI_UTIL_STACKTRACE_HPP_ diff --git a/wpiutil/src/main/native/include/wpi/util/StringMap.hpp b/wpiutil/src/main/native/include/wpi/util/StringMap.hpp index 27b5001921..09be08458a 100644 --- a/wpiutil/src/main/native/include/wpi/util/StringMap.hpp +++ b/wpiutil/src/main/native/include/wpi/util/StringMap.hpp @@ -13,7 +13,7 @@ #include #include -namespace wpi { +namespace wpi::util { /** * StringMap is a sorted associative container that contains key-value pairs @@ -767,11 +767,11 @@ class StringMap : public std::map, Allocator> { } }; -} // namespace wpi +} // namespace wpi::util namespace std { template -inline void swap(wpi::StringMap& lhs, wpi::StringMap& rhs) { +inline void swap(wpi::util::StringMap& lhs, wpi::util::StringMap& rhs) { lhs.swap(rhs); } } // namespace std diff --git a/wpiutil/src/main/native/include/wpi/util/Synchronization.h b/wpiutil/src/main/native/include/wpi/util/Synchronization.h index aa067662d3..24086e518e 100644 --- a/wpiutil/src/main/native/include/wpi/util/Synchronization.h +++ b/wpiutil/src/main/native/include/wpi/util/Synchronization.h @@ -29,7 +29,7 @@ typedef WPI_Handle WPI_SemaphoreHandle; // NOLINT #ifdef __cplusplus -namespace wpi { +namespace wpi::util { /** Constant representing an invalid handle. */ constexpr unsigned int kInvalidHandle = 0; @@ -442,7 +442,7 @@ class SignalObject final { T m_handle; }; -} // namespace wpi +} // namespace wpi::util extern "C" { diff --git a/wpiutil/src/main/native/include/wpi/util/UidVector.hpp b/wpiutil/src/main/native/include/wpi/util/UidVector.hpp index c84921d419..3b354e0ca2 100644 --- a/wpiutil/src/main/native/include/wpi/util/UidVector.hpp +++ b/wpiutil/src/main/native/include/wpi/util/UidVector.hpp @@ -9,7 +9,7 @@ #include #include -namespace wpi { +namespace wpi::util { namespace impl { template @@ -154,6 +154,6 @@ class UidVector { size_type m_active_count{0}; }; -} // namespace wpi +} // namespace wpi::util #endif // WPIUTIL_WPI_UTIL_UIDVECTOR_HPP_ diff --git a/wpiutil/src/main/native/include/wpi/util/array.hpp b/wpiutil/src/main/native/include/wpi/util/array.hpp index d6711f16d9..e2f8292c87 100644 --- a/wpiutil/src/main/native/include/wpi/util/array.hpp +++ b/wpiutil/src/main/native/include/wpi/util/array.hpp @@ -10,7 +10,7 @@ #include #include -namespace wpi { +namespace wpi::util { struct empty_array_t {}; constexpr empty_array_t empty_array; @@ -59,42 +59,42 @@ class array : public std::array { template ... Ts> array(T, Ts...) -> array; -} // namespace wpi +} // namespace wpi::util template requires(I < N) -constexpr T& get(wpi::array& arr) noexcept { +constexpr T& get(wpi::util::array& arr) noexcept { return std::get(static_cast>(arr)); } template requires(I < N) -constexpr T&& get(wpi::array&& arr) noexcept { +constexpr T&& get(wpi::util::array&& arr) noexcept { return std::move(std::get(arr)); } template requires(I < N) -constexpr const T& get(const wpi::array& arr) noexcept { +constexpr const T& get(const wpi::util::array& arr) noexcept { return std::get(static_cast>(arr)); } template requires(I < N) -constexpr const T&& get(const wpi::array&& arr) noexcept { +constexpr const T&& get(const wpi::util::array&& arr) noexcept { return std::move(std::get(arr)); } // Enables structured bindings namespace std { // NOLINT -// Partial specialization for wpi::array +// Partial specialization for wpi::util::array template -struct tuple_size> : public integral_constant {}; +struct tuple_size> : public integral_constant {}; -// Partial specialization for wpi::array +// Partial specialization for wpi::util::array template requires(I < N) -struct tuple_element> { +struct tuple_element> { using type = T; }; } // namespace std diff --git a/wpiutil/src/main/native/include/wpi/util/circular_buffer.hpp b/wpiutil/src/main/native/include/wpi/util/circular_buffer.hpp index 4fee596755..0489e16429 100644 --- a/wpiutil/src/main/native/include/wpi/util/circular_buffer.hpp +++ b/wpiutil/src/main/native/include/wpi/util/circular_buffer.hpp @@ -8,7 +8,7 @@ #include #include -namespace wpi { +namespace wpi::util { /** * This is a simple circular buffer so we don't need to "bucket brigade" copy @@ -117,7 +117,7 @@ class circular_buffer { * Returns end iterator. */ constexpr iterator end() { - return iterator(this, ::wpi::circular_buffer::size()); + return iterator(this, ::wpi::util::circular_buffer::size()); } /** @@ -129,7 +129,7 @@ class circular_buffer { * Returns const end iterator. */ constexpr const_iterator end() const { - return const_iterator(this, ::wpi::circular_buffer::size()); + return const_iterator(this, ::wpi::util::circular_buffer::size()); } /** @@ -141,7 +141,7 @@ class circular_buffer { * Returns const end iterator. */ constexpr const_iterator cend() const { - return const_iterator(this, ::wpi::circular_buffer::size()); + return const_iterator(this, ::wpi::util::circular_buffer::size()); } /** @@ -431,4 +431,4 @@ class circular_buffer { } }; -} // namespace wpi +} // namespace wpi::util diff --git a/wpiutil/src/main/native/include/wpi/util/condition_variable.hpp b/wpiutil/src/main/native/include/wpi/util/condition_variable.hpp index e21157a238..c7b7e57aeb 100644 --- a/wpiutil/src/main/native/include/wpi/util/condition_variable.hpp +++ b/wpiutil/src/main/native/include/wpi/util/condition_variable.hpp @@ -8,7 +8,7 @@ #include "wpi/util/priority_mutex.hpp" -namespace wpi { +namespace wpi::util { #if defined(__linux__) && defined(WPI_HAVE_PRIORITY_MUTEX) using condition_variable = ::std::condition_variable_any; @@ -16,4 +16,4 @@ using condition_variable = ::std::condition_variable_any; using condition_variable = ::std::condition_variable; #endif -} // namespace wpi +} // namespace wpi::util diff --git a/wpiutil/src/main/native/include/wpi/util/ct_string.hpp b/wpiutil/src/main/native/include/wpi/util/ct_string.hpp index 2c7796b4f6..725473620f 100644 --- a/wpiutil/src/main/native/include/wpi/util/ct_string.hpp +++ b/wpiutil/src/main/native/include/wpi/util/ct_string.hpp @@ -12,7 +12,7 @@ #include #include -namespace wpi { +namespace wpi::util { // derived from: // https://codereview.stackexchange.com/questions/282514/string-literals-concatenation-with-support-for-dynamic-strings @@ -228,4 +228,4 @@ constexpr auto NumToCtString() { return res; } -} // namespace wpi +} // namespace wpi::util diff --git a/wpiutil/src/main/native/include/wpi/util/fmt/raw_ostream.hpp b/wpiutil/src/main/native/include/wpi/util/fmt/raw_ostream.hpp index 61d24a4242..77f9528e6e 100644 --- a/wpiutil/src/main/native/include/wpi/util/fmt/raw_ostream.hpp +++ b/wpiutil/src/main/native/include/wpi/util/fmt/raw_ostream.hpp @@ -9,9 +9,9 @@ #include "wpi/util/raw_ostream.hpp" -namespace wpi { +namespace wpi::util { -inline void vprint(wpi::raw_ostream& os, fmt::string_view format_str, +inline void vprint(wpi::util::raw_ostream& os, fmt::string_view format_str, fmt::format_args args) { fmt::memory_buffer buffer; fmt::detail::vformat_to(buffer, format_str, args); @@ -22,10 +22,10 @@ inline void vprint(wpi::raw_ostream& os, fmt::string_view format_str, * Prints formatted data to the stream *os*. */ template -void print(wpi::raw_ostream& os, const S& format_str, Args&&... args) { +void print(wpi::util::raw_ostream& os, const S& format_str, Args&&... args) { vprint(os, format_str, fmt::make_format_args(args...)); } -} // namespace wpi +} // namespace wpi::util #endif // WPIUTIL_WPI_UTIL_FMT_RAW_OSTREAM_HPP_ diff --git a/wpiutil/src/main/native/include/wpi/util/future.hpp b/wpiutil/src/main/native/include/wpi/util/future.hpp index 44edc088f9..beca9b5685 100644 --- a/wpiutil/src/main/native/include/wpi/util/future.hpp +++ b/wpiutil/src/main/native/include/wpi/util/future.hpp @@ -18,7 +18,7 @@ #include "wpi/util/condition_variable.hpp" #include "wpi/util/mutex.hpp" -namespace wpi { +namespace wpi::util { template class PromiseFactory; @@ -39,16 +39,16 @@ class PromiseFactoryBase { bool IsActive() const { return m_active; } - wpi::mutex& GetResultMutex() { return m_resultMutex; } + wpi::util::mutex& GetResultMutex() { return m_resultMutex; } void Notify() { m_resultCv.notify_all(); } // must be called with locked lock == ResultMutex - void Wait(std::unique_lock& lock) { m_resultCv.wait(lock); } + void Wait(std::unique_lock& lock) { m_resultCv.wait(lock); } // returns false if timeout reached template - bool WaitUntil(std::unique_lock& lock, + bool WaitUntil(std::unique_lock& lock, const std::chrono::time_point& timeout_time) { return m_resultCv.wait_until(lock, timeout_time) == std::cv_status::no_timeout; @@ -67,9 +67,9 @@ class PromiseFactoryBase { uint64_t CreateErasedRequest() { return ++m_uid; } private: - wpi::mutex m_resultMutex; + wpi::util::mutex m_resultMutex; std::atomic_bool m_active{true}; - wpi::condition_variable m_resultCv; + wpi::util::condition_variable m_resultCv; uint64_t m_uid = 0; std::vector m_requests; @@ -938,6 +938,6 @@ future detail::FutureThen::Create( return factory.CreateFuture(req); } -} // namespace wpi +} // namespace wpi::util #endif // WPIUTIL_WPI_UTIL_FUTURE_HPP_ diff --git a/wpiutil/src/main/native/include/wpi/util/interpolating_map.hpp b/wpiutil/src/main/native/include/wpi/util/interpolating_map.hpp index d334cd8026..3c34a91f2d 100644 --- a/wpiutil/src/main/native/include/wpi/util/interpolating_map.hpp +++ b/wpiutil/src/main/native/include/wpi/util/interpolating_map.hpp @@ -7,7 +7,7 @@ #include #include -namespace wpi { +namespace wpi::util { /** * Implements a table of key-value pairs with linear interpolation between @@ -84,4 +84,4 @@ class interpolating_map { std::map m_container; }; -} // namespace wpi +} // namespace wpi::util diff --git a/wpiutil/src/main/native/include/wpi/util/jni_util.hpp b/wpiutil/src/main/native/include/wpi/util/jni_util.hpp index 75fecb0dc1..4b6b1aedd7 100644 --- a/wpiutil/src/main/native/include/wpi/util/jni_util.hpp +++ b/wpiutil/src/main/native/include/wpi/util/jni_util.hpp @@ -26,7 +26,7 @@ #include "wpi/util/string.h" /** Java Native Interface (JNI) utility functions */ -namespace wpi::java { +namespace wpi::util::java { /** * Gets a Java stack trace. @@ -160,7 +160,7 @@ class JStringRef { env->ReleaseStringCritical(str, chars); } } else { - wpi::print(stderr, "JStringRef was passed a null pointer at\n", + wpi::util::print(stderr, "JStringRef was passed a null pointer at\n", GetJavaStackTrace(env)); } // Ensure str is null-terminated. @@ -172,7 +172,7 @@ class JStringRef { std::string_view str() const { return m_str.str(); } const char* c_str() const { return m_str.data(); } size_t size() const { return m_str.size(); } - WPI_String wpi_str() const { return wpi::make_string(str()); } + WPI_String wpi_str() const { return wpi::util::make_string(str()); } private: SmallString<128> m_str; @@ -284,7 +284,7 @@ class JSpanBase { m_elements{static_cast*>( bb ? env->GetDirectBufferAddress(bb) : nullptr)} { if (!bb) { - wpi::print(stderr, "JSpan was passed a null pointer at\n", + wpi::util::print(stderr, "JSpan was passed a null pointer at\n", GetJavaStackTrace(env)); } } @@ -303,7 +303,7 @@ class JSpanBase { m_elements = ArrHelper::GetArrayElements(env, jarr); } } else { - wpi::print(stderr, "JSpan was passed a null pointer at\n", + wpi::util::print(stderr, "JSpan was passed a null pointer at\n", GetJavaStackTrace(env)); } } @@ -845,7 +845,7 @@ inline std::string GetJavaStackTrace(JNIEnv* env, std::string_view skipPrefix) { // add a line to res JStringRef elem(env, stackElementString); if (!foundFirst) { - if (wpi::starts_with(elem, skipPrefix)) { + if (wpi::util::starts_with(elem, skipPrefix)) { continue; } foundFirst = true; @@ -928,7 +928,7 @@ inline std::string GetJavaStackTrace(JNIEnv* env, std::string* func, if (i == 1) { *func = elem.str(); } else if (i > 1 && !haveLoc && !excludeFuncPrefix.empty() && - !wpi::starts_with(elem, excludeFuncPrefix)) { + !wpi::util::starts_with(elem, excludeFuncPrefix)) { *func = elem.str(); haveLoc = true; } @@ -975,6 +975,6 @@ struct JExceptionInit { JException* cls; }; -} // namespace wpi::java +} // namespace wpi::util::java #endif // WPIUTIL_WPI_UTIL_JNI_UTIL_HPP_ diff --git a/wpiutil/src/main/native/include/wpi/util/mutex.hpp b/wpiutil/src/main/native/include/wpi/util/mutex.hpp index f4a07bbbe4..016c042210 100644 --- a/wpiutil/src/main/native/include/wpi/util/mutex.hpp +++ b/wpiutil/src/main/native/include/wpi/util/mutex.hpp @@ -8,7 +8,7 @@ #include "wpi/util/priority_mutex.hpp" -namespace wpi { +namespace wpi::util { #ifdef WPI_HAVE_PRIORITY_MUTEX using mutex = priority_mutex; @@ -18,4 +18,4 @@ using mutex = ::std::mutex; using recursive_mutex = ::std::recursive_mutex; #endif -} // namespace wpi +} // namespace wpi::util diff --git a/wpiutil/src/main/native/include/wpi/util/print.hpp b/wpiutil/src/main/native/include/wpi/util/print.hpp index 422e65dc63..146a73df18 100644 --- a/wpiutil/src/main/native/include/wpi/util/print.hpp +++ b/wpiutil/src/main/native/include/wpi/util/print.hpp @@ -14,7 +14,7 @@ #include #endif -namespace wpi { +namespace wpi::util { /** * Wrapper around fmt::print() that squelches write failure exceptions. @@ -60,4 +60,4 @@ inline void println(std::FILE* f, fmt::format_string fmt, T&&... args) { } } -} // namespace wpi +} // namespace wpi::util diff --git a/wpiutil/src/main/native/include/wpi/util/priority_mutex.hpp b/wpiutil/src/main/native/include/wpi/util/priority_mutex.hpp index d27d4815e3..3451c0ddfc 100644 --- a/wpiutil/src/main/native/include/wpi/util/priority_mutex.hpp +++ b/wpiutil/src/main/native/include/wpi/util/priority_mutex.hpp @@ -11,7 +11,7 @@ #include -namespace wpi { +namespace wpi::util { #if defined(__FRC_SYSTEMCORE__) && !defined(WPI_USE_PRIORITY_MUTEX) #define WPI_USE_PRIORITY_MUTEX @@ -75,4 +75,4 @@ class priority_mutex { #endif // defined(WPI_USE_PRIORITY_MUTEX) && defined(__linux__) -} // namespace wpi +} // namespace wpi::util diff --git a/wpiutil/src/main/native/include/wpi/util/priority_queue.hpp b/wpiutil/src/main/native/include/wpi/util/priority_queue.hpp index 0447bc8433..d3c55ce00e 100644 --- a/wpiutil/src/main/native/include/wpi/util/priority_queue.hpp +++ b/wpiutil/src/main/native/include/wpi/util/priority_queue.hpp @@ -11,7 +11,7 @@ #include #include -namespace wpi { +namespace wpi::util { /** * This class is the same as std::priority_queue with two changes: @@ -111,6 +111,6 @@ class priority_queue { Compare comp; }; -} // namespace wpi +} // namespace wpi::util #endif // WPIUTIL_WPI_UTIL_PRIORITY_QUEUE_HPP_ diff --git a/wpiutil/src/main/native/include/wpi/util/protobuf/Protobuf.hpp b/wpiutil/src/main/native/include/wpi/util/protobuf/Protobuf.hpp index 99aa6f1953..d8eecb13d4 100644 --- a/wpiutil/src/main/native/include/wpi/util/protobuf/Protobuf.hpp +++ b/wpiutil/src/main/native/include/wpi/util/protobuf/Protobuf.hpp @@ -20,7 +20,7 @@ #include "wpi/util/array.hpp" #include "wpi/util/function_ref.hpp" -namespace wpi { +namespace wpi::util { template class SmallVectorImpl; @@ -36,7 +36,7 @@ template struct Protobuf {}; namespace detail { -using SmallVectorType = wpi::SmallVectorImpl; +using SmallVectorType = wpi::util::SmallVectorImpl; using StdVectorType = std::vector; bool WriteFromSmallVector(pb_ostream_t* stream, const pb_byte_t* buf, size_t count); @@ -232,25 +232,25 @@ class ProtoOutputStream { * values into a nanopb Stream and deserialization consists of * reading values from nanopb Stream. * - * Implementations must define a template specialization for wpi::Protobuf with + * Implementations must define a template specialization for wpi::util::Protobuf with * T being the type that is being serialized/deserialized, with the following * static members (as enforced by this concept): * - using MessageStruct = nanopb_message_struct_here: typedef to the wpilib * modified nanopb message struct - * - std::optional Unpack(wpi::ProtoInputStream&): function + * - std::optional Unpack(wpi::util::ProtoInputStream&): function * for deserialization - * - bool Pack(wpi::ProtoOutputStream&, T&& value): function + * - bool Pack(wpi::util::ProtoOutputStream&, T&& value): function * for serialization * * As a suggestion, 2 extra type usings can be added to simplify the stream * definitions, however these are not required. - * - using InputStream = wpi::ProtoInputStream; - * - using OutputStream = wpi::ProtoOutputStream; + * - using InputStream = wpi::util::ProtoInputStream; + * - using OutputStream = wpi::util::ProtoOutputStream; */ template concept ProtobufSerializable = requires( - wpi::ProtoOutputStream>& ostream, - wpi::ProtoInputStream>& istream, const T& value) { + wpi::util::ProtoOutputStream>& ostream, + wpi::util::ProtoInputStream>& istream, const T& value) { typename Protobuf>; { Protobuf>::Unpack(istream) @@ -274,14 +274,14 @@ concept ProtobufSerializable = requires( * Specifies that a type is capable of in-place protobuf deserialization. * * In addition to meeting ProtobufSerializable, implementations must define a - * wpi::Protobuf static member - - * `bool UnpackInto(T*, wpi::ProtoInputStream&)` to update the pointed-to T + * wpi::util::Protobuf static member - + * `bool UnpackInto(T*, wpi::util::ProtoInputStream&)` to update the pointed-to T * with the contents of the message. */ template concept MutableProtobufSerializable = ProtobufSerializable && - requires(T* out, wpi::ProtoInputStream& istream) { + requires(T* out, wpi::util::ProtoInputStream& istream) { { Protobuf>::UnpackInto(out, istream) } -> std::same_as; @@ -345,7 +345,7 @@ class ProtobufMessage { * @param[in] value value * @return true if successful */ - bool Pack(wpi::SmallVectorImpl& out, const T& value) { + bool Pack(wpi::util::SmallVectorImpl& out, const T& value) { ProtoOutputStream> stream{out}; return Protobuf>::Pack(stream, value); } @@ -391,4 +391,4 @@ class ProtobufMessage { } }; -} // namespace wpi +} // namespace wpi::util diff --git a/wpiutil/src/main/native/include/wpi/util/protobuf/ProtobufCallbacks.hpp b/wpiutil/src/main/native/include/wpi/util/protobuf/ProtobufCallbacks.hpp index 05fdd899ec..1881c8babf 100644 --- a/wpiutil/src/main/native/include/wpi/util/protobuf/ProtobufCallbacks.hpp +++ b/wpiutil/src/main/native/include/wpi/util/protobuf/ProtobufCallbacks.hpp @@ -15,7 +15,7 @@ #include "wpi/util/array.hpp" #include "wpi/util/protobuf/Protobuf.hpp" -namespace wpi { +namespace wpi::util { /** * The behavior to use when more elements are in the message then expected when @@ -268,7 +268,7 @@ class DirectUnpackCallback { space.size()); } else if constexpr (ProtobufSerializable) { ProtoInputStream istream{stream}; - auto decoded = wpi::Protobuf::Unpack(istream); + auto decoded = wpi::util::Protobuf::Unpack(istream); if (decoded.has_value()) { m_storage.emplace_back(std::move(decoded.value())); return true; @@ -332,13 +332,13 @@ class DirectUnpackCallback { */ template class UnpackCallback - : public DirectUnpackCallback, N> { + : public DirectUnpackCallback, N> { public: /** * Constructs an UnpackCallback. */ UnpackCallback() - : DirectUnpackCallback, N>{m_storedBuffer} { + : DirectUnpackCallback, N>{m_storedBuffer} { this->SetLimits(DecodeLimits::Ignore); } @@ -361,10 +361,10 @@ class UnpackCallback * * @return small vector reference */ - wpi::SmallVector& Vec() noexcept { return m_storedBuffer; } + wpi::util::SmallVector& Vec() noexcept { return m_storedBuffer; } private: - wpi::SmallVector m_storedBuffer; + wpi::util::SmallVector m_storedBuffer; }; /** @@ -414,12 +414,12 @@ class StdVectorUnpackCallback }; /** - * A wrapper around a wpi::array that lets us + * A wrapper around a wpi::util::array that lets us * treat it as a limited sized vector. */ template struct WpiArrayEmplaceWrapper { - wpi::array m_array{wpi::empty_array_t{}}; + wpi::util::array m_array{wpi::util::empty_array_t{}}; size_t m_currentIndex = 0; size_t size() const { return m_currentIndex; } @@ -433,7 +433,7 @@ struct WpiArrayEmplaceWrapper { }; /** - * A DirectUnpackCallback backed by a wpi::array. + * A DirectUnpackCallback backed by a wpi::util::array. * * Any elements in the packed buffer past N will * be cause decoding to fail. @@ -471,7 +471,7 @@ struct WpiArrayUnpackCallback * * @return array reference */ - wpi::array& Array() noexcept { return m_array.m_array; } + wpi::util::array& Array() noexcept { return m_array.m_array; } private: WpiArrayEmplaceWrapper m_array; @@ -581,7 +581,7 @@ class PackCallback { reinterpret_cast(view.data()), view.size()); } else if constexpr (ProtobufSerializable) { - return wpi::Protobuf::Pack(stream, value); + return wpi::util::Protobuf::Pack(stream, value); } } @@ -667,4 +667,4 @@ class PackCallback { pb_callback_t m_callback; }; -} // namespace wpi +} // namespace wpi::util diff --git a/wpiutil/src/main/native/include/wpi/util/raw_istream.hpp b/wpiutil/src/main/native/include/wpi/util/raw_istream.hpp index 42c39dcfe8..ca87b6ce75 100644 --- a/wpiutil/src/main/native/include/wpi/util/raw_istream.hpp +++ b/wpiutil/src/main/native/include/wpi/util/raw_istream.hpp @@ -17,7 +17,7 @@ #include "wpi/util/SmallVector.hpp" -namespace wpi { +namespace wpi::util { class raw_istream { public: @@ -171,6 +171,6 @@ class raw_fd_istream : public raw_istream { bool m_shouldClose; }; -} // namespace wpi +} // namespace wpi::util #endif // WPIUTIL_WPI_UTIL_RAW_ISTREAM_HPP_ diff --git a/wpiutil/src/main/native/include/wpi/util/rotated_span.hpp b/wpiutil/src/main/native/include/wpi/util/rotated_span.hpp index 92d7036363..aceb21167b 100644 --- a/wpiutil/src/main/native/include/wpi/util/rotated_span.hpp +++ b/wpiutil/src/main/native/include/wpi/util/rotated_span.hpp @@ -10,7 +10,7 @@ #include #include -namespace wpi { +namespace wpi::util { /** * This is a simple rotated span view. Indexed/iterated access provides a @@ -251,4 +251,4 @@ as_writable_bytes(rotated_span sp) noexcept { return {std::as_writable_bytes(sp.data()), sp.offset() * sizeof(Type)}; } -} // namespace wpi +} // namespace wpi::util diff --git a/wpiutil/src/main/native/include/wpi/util/sendable/Sendable.hpp b/wpiutil/src/main/native/include/wpi/util/sendable/Sendable.hpp index 3a78ddf2b8..4e7538ad83 100644 --- a/wpiutil/src/main/native/include/wpi/util/sendable/Sendable.hpp +++ b/wpiutil/src/main/native/include/wpi/util/sendable/Sendable.hpp @@ -6,7 +6,7 @@ #include "wpi/util/SymbolExports.hpp" -namespace wpi { +namespace wpi::util { class SendableBuilder; @@ -25,4 +25,4 @@ class WPILIB_DLLEXPORT Sendable { virtual void InitSendable(SendableBuilder& builder) = 0; }; -} // namespace wpi +} // namespace wpi::util diff --git a/wpiutil/src/main/native/include/wpi/util/sendable/SendableBuilder.hpp b/wpiutil/src/main/native/include/wpi/util/sendable/SendableBuilder.hpp index 36e8df4068..7da25f5102 100644 --- a/wpiutil/src/main/native/include/wpi/util/sendable/SendableBuilder.hpp +++ b/wpiutil/src/main/native/include/wpi/util/sendable/SendableBuilder.hpp @@ -13,7 +13,7 @@ #include "wpi/util/SmallVector.hpp" -namespace wpi { +namespace wpi::util { /** * Helper class for building Sendable dashboard representations. @@ -277,7 +277,7 @@ class SendableBuilder { */ virtual void AddSmallStringProperty( std::string_view key, - std::function& buf)> getter, + std::function& buf)> getter, std::function setter) = 0; /** @@ -289,7 +289,7 @@ class SendableBuilder { */ virtual void AddSmallBooleanArrayProperty( std::string_view key, - std::function(wpi::SmallVectorImpl& buf)> + std::function(wpi::util::SmallVectorImpl& buf)> getter, std::function)> setter) = 0; @@ -303,7 +303,7 @@ class SendableBuilder { virtual void AddSmallIntegerArrayProperty( std::string_view key, std::function< - std::span(wpi::SmallVectorImpl& buf)> + std::span(wpi::util::SmallVectorImpl& buf)> getter, std::function)> setter) = 0; @@ -316,7 +316,7 @@ class SendableBuilder { */ virtual void AddSmallFloatArrayProperty( std::string_view key, - std::function(wpi::SmallVectorImpl& buf)> + std::function(wpi::util::SmallVectorImpl& buf)> getter, std::function)> setter) = 0; @@ -329,7 +329,7 @@ class SendableBuilder { */ virtual void AddSmallDoubleArrayProperty( std::string_view key, - std::function(wpi::SmallVectorImpl& buf)> + std::function(wpi::util::SmallVectorImpl& buf)> getter, std::function)> setter) = 0; @@ -343,7 +343,7 @@ class SendableBuilder { virtual void AddSmallStringArrayProperty( std::string_view key, std::function< - std::span(wpi::SmallVectorImpl& buf)> + std::span(wpi::util::SmallVectorImpl& buf)> getter, std::function)> setter) = 0; @@ -357,7 +357,7 @@ class SendableBuilder { */ virtual void AddSmallRawProperty( std::string_view key, std::string_view typeString, - std::function(wpi::SmallVectorImpl& buf)> + std::function(wpi::util::SmallVectorImpl& buf)> getter, std::function)> setter) = 0; @@ -386,4 +386,4 @@ class SendableBuilder { virtual void ClearProperties() = 0; }; -} // namespace wpi +} // namespace wpi::util diff --git a/wpiutil/src/main/native/include/wpi/util/sendable/SendableHelper.hpp b/wpiutil/src/main/native/include/wpi/util/sendable/SendableHelper.hpp index 9e8ec0596e..16f652e9fc 100644 --- a/wpiutil/src/main/native/include/wpi/util/sendable/SendableHelper.hpp +++ b/wpiutil/src/main/native/include/wpi/util/sendable/SendableHelper.hpp @@ -8,7 +8,7 @@ #include "wpi/util/sendable/SendableRegistry.hpp" -namespace wpi { +namespace wpi::util { /** * A helper class for use with objects that add themselves to SendableRegistry. @@ -59,4 +59,4 @@ class SendableHelper { } }; -} // namespace wpi +} // namespace wpi::util diff --git a/wpiutil/src/main/native/include/wpi/util/sendable/SendableRegistry.hpp b/wpiutil/src/main/native/include/wpi/util/sendable/SendableRegistry.hpp index 324c7d286a..77cdfa1acc 100644 --- a/wpiutil/src/main/native/include/wpi/util/sendable/SendableRegistry.hpp +++ b/wpiutil/src/main/native/include/wpi/util/sendable/SendableRegistry.hpp @@ -8,7 +8,7 @@ #include #include -namespace wpi { +namespace wpi::util { class Sendable; class SendableBuilder; @@ -237,4 +237,4 @@ class SendableRegistry final { static void Update(UID sendableUid); }; -} // namespace wpi +} // namespace wpi::util diff --git a/wpiutil/src/main/native/include/wpi/util/sha1.hpp b/wpiutil/src/main/native/include/wpi/util/sha1.hpp index 611782dcfd..855da55818 100644 --- a/wpiutil/src/main/native/include/wpi/util/sha1.hpp +++ b/wpiutil/src/main/native/include/wpi/util/sha1.hpp @@ -25,7 +25,7 @@ #include #include -namespace wpi { +namespace wpi::util { template class SmallVectorImpl; class raw_istream; @@ -47,6 +47,6 @@ class SHA1 { uint64_t transforms; }; -} // namespace wpi +} // namespace wpi::util #endif // WPIUTIL_WPI_UTIL_SHA1_HPP_ diff --git a/wpiutil/src/main/native/include/wpi/util/spinlock.hpp b/wpiutil/src/main/native/include/wpi/util/spinlock.hpp index bf9046d033..0bf1cf19e6 100644 --- a/wpiutil/src/main/native/include/wpi/util/spinlock.hpp +++ b/wpiutil/src/main/native/include/wpi/util/spinlock.hpp @@ -11,7 +11,7 @@ #include "wpi/util/Compiler.hpp" -namespace wpi { +namespace wpi::util { /** * A spinlock mutex. Wraps std::atomic_flag in a std::mutex compatible way. @@ -141,4 +141,4 @@ using recursive_spinlock = recursive_spinlock2; using recursive_spinlock = recursive_spinlock1; #endif -} // namespace wpi +} // namespace wpi::util diff --git a/wpiutil/src/main/native/include/wpi/util/static_circular_buffer.hpp b/wpiutil/src/main/native/include/wpi/util/static_circular_buffer.hpp index 133c9e3a67..a342cf798e 100644 --- a/wpiutil/src/main/native/include/wpi/util/static_circular_buffer.hpp +++ b/wpiutil/src/main/native/include/wpi/util/static_circular_buffer.hpp @@ -8,7 +8,7 @@ #include #include -namespace wpi { +namespace wpi::util { /** * This is a simple circular buffer so we don't need to "bucket brigade" copy @@ -108,7 +108,7 @@ class static_circular_buffer { * Returns end iterator. */ constexpr iterator end() { - return iterator(this, ::wpi::static_circular_buffer::size()); + return iterator(this, ::wpi::util::static_circular_buffer::size()); } /** @@ -120,7 +120,7 @@ class static_circular_buffer { * Returns const end iterator. */ constexpr const_iterator end() const { - return const_iterator(this, ::wpi::static_circular_buffer::size()); + return const_iterator(this, ::wpi::util::static_circular_buffer::size()); } /** @@ -132,7 +132,7 @@ class static_circular_buffer { * Returns const end iterator. */ constexpr const_iterator cend() const { - return const_iterator(this, ::wpi::static_circular_buffer::size()); + return const_iterator(this, ::wpi::util::static_circular_buffer::size()); } /** @@ -348,4 +348,4 @@ class static_circular_buffer { } }; -} // namespace wpi +} // namespace wpi::util diff --git a/wpiutil/src/main/native/include/wpi/util/string.h b/wpiutil/src/main/native/include/wpi/util/string.h index 151c9f6c93..006af17ad0 100644 --- a/wpiutil/src/main/native/include/wpi/util/string.h +++ b/wpiutil/src/main/native/include/wpi/util/string.h @@ -20,7 +20,7 @@ struct WPI_String { }; #ifdef __cplusplus -namespace wpi { +namespace wpi::util { /** Converts a WPI_String to a string_view */ constexpr std::string_view to_string_view(const struct WPI_String* str) { if (str) { @@ -34,7 +34,7 @@ constexpr std::string_view to_string_view(const struct WPI_String* str) { constexpr WPI_String make_string(std::string_view view) { return WPI_String{view.data(), view.size()}; } -} // namespace wpi +} // namespace wpi::util #endif // __cplusplus #ifdef __cplusplus @@ -109,7 +109,7 @@ void WPI_FreeStringArray(const struct WPI_String* wpiStringArray, #endif // __cplusplus #ifdef __cplusplus -namespace wpi { +namespace wpi::util { /** Allocates a copy of a string_view and stores the result into a WPI_String */ inline WPI_String alloc_wpi_string(std::string_view view) { @@ -126,5 +126,5 @@ inline WPI_String copy_wpi_string(const WPI_String& str) { } return alloc_wpi_string(to_string_view(&str)); } -} // namespace wpi +} // namespace wpi::util #endif diff --git a/wpiutil/src/main/native/include/wpi/util/struct/DynamicStruct.hpp b/wpiutil/src/main/native/include/wpi/util/struct/DynamicStruct.hpp index fd0e6c2e34..aca89f3bd3 100644 --- a/wpiutil/src/main/native/include/wpi/util/struct/DynamicStruct.hpp +++ b/wpiutil/src/main/native/include/wpi/util/struct/DynamicStruct.hpp @@ -16,7 +16,7 @@ #include "wpi/util/StringMap.hpp" #include "wpi/util/bit.hpp" -namespace wpi { +namespace wpi::util { template class SmallVectorImpl; @@ -316,9 +316,9 @@ class StructDescriptor { private: bool CheckCircular( - wpi::SmallVectorImpl& stack) const; + wpi::util::SmallVectorImpl& stack) const; std::string CalculateOffsets( - wpi::SmallVectorImpl& stack); + wpi::util::SmallVectorImpl& stack); std::string m_name; std::string m_schema; @@ -696,4 +696,4 @@ class DynamicStructObject : private impl::DSOData, public MutableDynamicStruct { DynamicStructObject& operator=(DynamicStructObject&&) = delete; }; -} // namespace wpi +} // namespace wpi::util diff --git a/wpiutil/src/main/native/include/wpi/util/struct/SchemaParser.hpp b/wpiutil/src/main/native/include/wpi/util/struct/SchemaParser.hpp index 4e5a1df457..e57c4215a1 100644 --- a/wpiutil/src/main/native/include/wpi/util/struct/SchemaParser.hpp +++ b/wpiutil/src/main/native/include/wpi/util/struct/SchemaParser.hpp @@ -11,7 +11,7 @@ #include #include -namespace wpi::structparser { +namespace wpi::util::structparser { /** * A lexed raw struct schema token. @@ -196,4 +196,4 @@ class Parser { std::string m_error; }; -} // namespace wpi::structparser +} // namespace wpi::util::structparser diff --git a/wpiutil/src/main/native/include/wpi/util/struct/Struct.hpp b/wpiutil/src/main/native/include/wpi/util/struct/Struct.hpp index d2734ca0e8..4adfdafa4d 100644 --- a/wpiutil/src/main/native/include/wpi/util/struct/Struct.hpp +++ b/wpiutil/src/main/native/include/wpi/util/struct/Struct.hpp @@ -25,7 +25,7 @@ #include "wpi/util/mutex.hpp" #include "wpi/util/type_traits.hpp" -namespace wpi { +namespace wpi::util { /** * Struct serialization template. Unspecialized class has no members; only @@ -47,7 +47,7 @@ struct Struct {}; * values into a mutable std::span and deserialization consists of reading * values from an immutable std::span. * - * Implementations must define a template specialization for wpi::Struct with + * Implementations must define a template specialization for wpi::util::Struct with * T being the type that is being serialized/deserialized, with the following * static members (as enforced by this concept): * - std::string_view GetTypeName(): function that returns the type name @@ -96,7 +96,7 @@ concept StructSerializable = requires(std::span in, * Specifies that a type is capable of in-place raw struct deserialization. * * In addition to meeting StructSerializable, implementations must define a - * wpi::Struct static member `void UnpackInto(T*, std::span)` + * wpi::util::Struct static member `void UnpackInto(T*, std::span)` * to update the pointed-to T with the contents of the span. */ template @@ -111,7 +111,7 @@ concept MutableStructSerializable = * Specifies that a struct type has nested struct declarations. * * In addition to meeting StructSerializable, implementations must define a - * wpi::Struct static member + * wpi::util::Struct static member * `void ForEachNested(std::invocable on each nested struct * type. @@ -169,17 +169,17 @@ inline T UnpackStruct(std::span data, const I&... info) { * @return Deserialized array */ template -inline wpi::array UnpackStructArray(std::span data) { +inline wpi::util::array UnpackStructArray(std::span data) { if (is_constexpr([] { Struct>::GetSize(); })) { constexpr auto StructSize = Struct>::GetSize(); - wpi::array arr(wpi::empty_array); + wpi::util::array arr(wpi::util::empty_array); [&](std::index_sequence) { ((arr[Is] = UnpackStruct(data)), ...); }(std::make_index_sequence{}); return arr; } else { auto size = Struct>::GetSize(); - wpi::array arr(wpi::empty_array); + wpi::util::array arr(wpi::util::empty_array); for (size_t i = 0; i < N; i++) { arr[i] = UnpackStruct(data); data = data.subspan(size); @@ -232,7 +232,7 @@ inline void PackStruct(std::span data, T&& value, const I&... info) { */ template inline void PackStructArray(std::span data, - const wpi::array& arr) { + const wpi::util::array& arr) { if (is_constexpr([] { Struct>::GetSize(); })) { constexpr auto StructSize = Struct>::GetSize(); [&](std::index_sequence) { @@ -480,7 +480,7 @@ class StructArrayBuffer { } private: - wpi::mutex m_mutex; + wpi::util::mutex m_mutex; std::vector m_buf; }; @@ -711,4 +711,4 @@ struct Struct { } }; -} // namespace wpi +} // namespace wpi::util diff --git a/wpiutil/src/main/native/include/wpi/util/timestamp.h b/wpiutil/src/main/native/include/wpi/util/timestamp.h index 6ea7af37f0..2f6df2f32b 100644 --- a/wpiutil/src/main/native/include/wpi/util/timestamp.h +++ b/wpiutil/src/main/native/include/wpi/util/timestamp.h @@ -51,7 +51,7 @@ uint64_t WPI_GetSystemTime(void); #endif #ifdef __cplusplus -namespace wpi { +namespace wpi::util { /** * The default implementation used for Now(). @@ -83,7 +83,7 @@ uint64_t Now(); */ uint64_t GetSystemTime(); -} // namespace wpi +} // namespace wpi::util #endif #endif // WPIUTIL_WPI_UTIL_TIMESTAMP_H_ diff --git a/wpiutil/src/main/native/thirdparty/argparse/include/wpi/util/argparse.hpp b/wpiutil/src/main/native/thirdparty/argparse/include/wpi/util/argparse.hpp index 7ce9081150..3113e14035 100644 --- a/wpiutil/src/main/native/thirdparty/argparse/include/wpi/util/argparse.hpp +++ b/wpiutil/src/main/native/thirdparty/argparse/include/wpi/util/argparse.hpp @@ -71,7 +71,7 @@ SOFTWARE. #define WPI_CUSTOM_STRTOLD strtold #endif -namespace wpi { +namespace wpi::util { namespace details { // namespace for helper methods @@ -2540,4 +2540,4 @@ protected: std::vector m_group_names; }; -} // namespace wpi +} // namespace wpi::util diff --git a/wpiutil/src/main/native/thirdparty/debugging/include/debugging.hpp b/wpiutil/src/main/native/thirdparty/debugging/include/debugging.hpp index 291d4c723e..79d3c16d96 100644 --- a/wpiutil/src/main/native/thirdparty/debugging/include/debugging.hpp +++ b/wpiutil/src/main/native/thirdparty/debugging/include/debugging.hpp @@ -3,7 +3,7 @@ #include -namespace wpi { +namespace wpi::util { bool is_debugger_present() noexcept; @@ -24,6 +24,6 @@ inline void breakpoint_if_debugging() noexcept if (is_debugger_present()) breakpoint(); } -} // namespace wpi +} // namespace wpi::util #endif diff --git a/wpiutil/src/main/native/thirdparty/debugging/src/emscripten.cpp b/wpiutil/src/main/native/thirdparty/debugging/src/emscripten.cpp index 16924894cc..4d72e8c4b1 100644 --- a/wpiutil/src/main/native/thirdparty/debugging/src/emscripten.cpp +++ b/wpiutil/src/main/native/thirdparty/debugging/src/emscripten.cpp @@ -6,13 +6,13 @@ # include # include -namespace wpi { +namespace wpi::util { bool is_debugger_present() noexcept { return false; } -} // namespace wpi +} // namespace wpi::util #endif diff --git a/wpiutil/src/main/native/thirdparty/debugging/src/linux.cpp b/wpiutil/src/main/native/thirdparty/debugging/src/linux.cpp index 40402a50f8..11628e2d90 100644 --- a/wpiutil/src/main/native/thirdparty/debugging/src/linux.cpp +++ b/wpiutil/src/main/native/thirdparty/debugging/src/linux.cpp @@ -7,7 +7,7 @@ # include # include -namespace wpi { +namespace wpi::util { bool is_debugger_present() noexcept { @@ -20,6 +20,6 @@ bool is_debugger_present() noexcept return buffer[index + 11] != '0'; } -} // namespace wpi +} // namespace wpi::util #endif diff --git a/wpiutil/src/main/native/thirdparty/debugging/src/macos.cpp b/wpiutil/src/main/native/thirdparty/debugging/src/macos.cpp index 0e90a952d2..4d1bd55859 100644 --- a/wpiutil/src/main/native/thirdparty/debugging/src/macos.cpp +++ b/wpiutil/src/main/native/thirdparty/debugging/src/macos.cpp @@ -11,7 +11,7 @@ template auto exc = std::array { {} }; -namespace wpi { +namespace wpi::util { bool is_debugger_present() noexcept { @@ -31,6 +31,6 @@ bool is_debugger_present() noexcept return end != std::find_if(begin, end, valid); } -} // namespace wpi +} // namespace wpi::util #endif diff --git a/wpiutil/src/main/native/thirdparty/debugging/src/windows.cpp b/wpiutil/src/main/native/thirdparty/debugging/src/windows.cpp index 465c92fbd6..db80d70e2d 100644 --- a/wpiutil/src/main/native/thirdparty/debugging/src/windows.cpp +++ b/wpiutil/src/main/native/thirdparty/debugging/src/windows.cpp @@ -6,13 +6,13 @@ # define WIN32_LEAN_AND_MEAN # include -namespace wpi { +namespace wpi::util { bool is_debugger_present() noexcept { return ::IsDebuggerPresent(); } -} // namespace wpi +} // namespace wpi::util #endif diff --git a/wpiutil/src/main/native/thirdparty/json/include/wpi/util/adl_serializer.hpp b/wpiutil/src/main/native/thirdparty/json/include/wpi/util/adl_serializer.hpp index 6160cceb05..11be2e76ef 100644 --- a/wpiutil/src/main/native/thirdparty/json/include/wpi/util/adl_serializer.hpp +++ b/wpiutil/src/main/native/thirdparty/json/include/wpi/util/adl_serializer.hpp @@ -25,30 +25,30 @@ struct adl_serializer /// @sa https://json.nlohmann.me/api/adl_serializer/from_json/ template static auto from_json(BasicJsonType && j, TargetType& val) noexcept( - noexcept(::wpi::from_json(std::forward(j), val))) - -> decltype(::wpi::from_json(std::forward(j), val), void()) + noexcept(::wpi::util::from_json(std::forward(j), val))) + -> decltype(::wpi::util::from_json(std::forward(j), val), void()) { - ::wpi::from_json(std::forward(j), val); + ::wpi::util::from_json(std::forward(j), val); } /// @brief convert a JSON value to any value type /// @sa https://json.nlohmann.me/api/adl_serializer/from_json/ template static auto from_json(BasicJsonType && j) noexcept( - noexcept(::wpi::from_json(std::forward(j), detail::identity_tag {}))) - -> decltype(::wpi::from_json(std::forward(j), detail::identity_tag {})) + noexcept(::wpi::util::from_json(std::forward(j), detail::identity_tag {}))) + -> decltype(::wpi::util::from_json(std::forward(j), detail::identity_tag {})) { - return ::wpi::from_json(std::forward(j), detail::identity_tag {}); + return ::wpi::util::from_json(std::forward(j), detail::identity_tag {}); } /// @brief convert any value type to a JSON value /// @sa https://json.nlohmann.me/api/adl_serializer/to_json/ template static auto to_json(BasicJsonType& j, TargetType && val) noexcept( - noexcept(::wpi::to_json(j, std::forward(val)))) - -> decltype(::wpi::to_json(j, std::forward(val)), void()) + noexcept(::wpi::util::to_json(j, std::forward(val)))) + -> decltype(::wpi::util::to_json(j, std::forward(val)), void()) { - ::wpi::to_json(j, std::forward(val)); + ::wpi::util::to_json(j, std::forward(val)); } }; diff --git a/wpiutil/src/main/native/thirdparty/json/include/wpi/util/detail/abi_macros.hpp b/wpiutil/src/main/native/thirdparty/json/include/wpi/util/detail/abi_macros.hpp index b4d0fccd40..b36f93f2ff 100644 --- a/wpiutil/src/main/native/thirdparty/json/include/wpi/util/detail/abi_macros.hpp +++ b/wpiutil/src/main/native/thirdparty/json/include/wpi/util/detail/abi_macros.hpp @@ -44,18 +44,18 @@ #ifndef WPI_JSON_NAMESPACE #define WPI_JSON_NAMESPACE \ - wpi::WPI_JSON_NAMESPACE_CONCAT( \ + wpi::util::WPI_JSON_NAMESPACE_CONCAT( \ WPI_JSON_ABI_TAGS, \ WPI_JSON_NAMESPACE_VERSION) #endif #ifndef WPI_JSON_NAMESPACE_BEGIN #define WPI_JSON_NAMESPACE_BEGIN \ - namespace wpi \ + namespace wpi::util \ { #endif #ifndef WPI_JSON_NAMESPACE_END #define WPI_JSON_NAMESPACE_END \ - } // namespace wpi + } // namespace wpi::util #endif diff --git a/wpiutil/src/main/native/thirdparty/json/include/wpi/util/detail/input/json_sax.hpp b/wpiutil/src/main/native/thirdparty/json/include/wpi/util/detail/input/json_sax.hpp index 4885362393..42ff5f3285 100644 --- a/wpiutil/src/main/native/thirdparty/json/include/wpi/util/detail/input/json_sax.hpp +++ b/wpiutil/src/main/native/thirdparty/json/include/wpi/util/detail/input/json_sax.hpp @@ -22,7 +22,7 @@ WPI_JSON_NAMESPACE_BEGIN /*! @brief SAX interface -This class describes the SAX interface used by @ref wpi::json::sax_parse. +This class describes the SAX interface used by @ref wpi::util::json::sax_parse. Each function is called in different situations while the input is parsed. The boolean return value informs the parser whether to continue processing the input. diff --git a/wpiutil/src/main/native/thirdparty/json/include/wpi/util/detail/iterators/iteration_proxy.hpp b/wpiutil/src/main/native/thirdparty/json/include/wpi/util/detail/iterators/iteration_proxy.hpp index 1898a3ed13..2f828298d1 100644 --- a/wpiutil/src/main/native/thirdparty/json/include/wpi/util/detail/iterators/iteration_proxy.hpp +++ b/wpiutil/src/main/native/thirdparty/json/include/wpi/util/detail/iterators/iteration_proxy.hpp @@ -190,7 +190,7 @@ template class iteration_proxy // For further reference see https://blog.tartanllama.xyz/structured-bindings/ // And see https://github.com/nlohmann/json/pull/1391 template = 0> -auto get(const wpi::detail::iteration_proxy_value& i) -> decltype(i.key()) +auto get(const wpi::util::detail::iteration_proxy_value& i) -> decltype(i.key()) { return i.key(); } @@ -198,7 +198,7 @@ auto get(const wpi::detail::iteration_proxy_value& i) -> decltype( // For further reference see https://blog.tartanllama.xyz/structured-bindings/ // And see https://github.com/nlohmann/json/pull/1391 template = 0> -auto get(const wpi::detail::iteration_proxy_value& i) -> decltype(i.value()) +auto get(const wpi::util::detail::iteration_proxy_value& i) -> decltype(i.value()) { return i.value(); } @@ -219,16 +219,16 @@ namespace std #pragma clang diagnostic ignored "-Wmismatched-tags" #endif template -class tuple_size<::wpi::detail::iteration_proxy_value> // NOLINT(cert-dcl58-cpp) +class tuple_size<::wpi::util::detail::iteration_proxy_value> // NOLINT(cert-dcl58-cpp) : public std::integral_constant {}; template -class tuple_element> // NOLINT(cert-dcl58-cpp) +class tuple_element> // NOLINT(cert-dcl58-cpp) { public: using type = decltype( get(std::declval < - ::wpi::detail::iteration_proxy_value> ())); + ::wpi::util::detail::iteration_proxy_value> ())); }; #if defined(__clang__) #pragma clang diagnostic pop @@ -238,5 +238,5 @@ class tuple_element> // N #if JSON_HAS_RANGES template - inline constexpr bool ::std::ranges::enable_borrowed_range<::wpi::detail::iteration_proxy> = true; + inline constexpr bool ::std::ranges::enable_borrowed_range<::wpi::util::detail::iteration_proxy> = true; #endif diff --git a/wpiutil/src/main/native/thirdparty/json/include/wpi/util/detail/macro_scope.hpp b/wpiutil/src/main/native/thirdparty/json/include/wpi/util/detail/macro_scope.hpp index 924dc8bcdb..38fb7006d3 100644 --- a/wpiutil/src/main/native/thirdparty/json/include/wpi/util/detail/macro_scope.hpp +++ b/wpiutil/src/main/native/thirdparty/json/include/wpi/util/detail/macro_scope.hpp @@ -399,15 +399,15 @@ @since version 3.9.0 */ #define WPI_DEFINE_TYPE_INTRUSIVE(Type, ...) \ - friend void to_json(wpi::json& nlohmann_json_j, const Type& nlohmann_json_t) { WPI_JSON_EXPAND(WPI_JSON_PASTE(WPI_JSON_TO, __VA_ARGS__)) } \ - friend void from_json(const wpi::json& nlohmann_json_j, Type& nlohmann_json_t) { WPI_JSON_EXPAND(WPI_JSON_PASTE(WPI_JSON_FROM, __VA_ARGS__)) } + friend void to_json(wpi::util::json& nlohmann_json_j, const Type& nlohmann_json_t) { WPI_JSON_EXPAND(WPI_JSON_PASTE(WPI_JSON_TO, __VA_ARGS__)) } \ + friend void from_json(const wpi::util::json& nlohmann_json_j, Type& nlohmann_json_t) { WPI_JSON_EXPAND(WPI_JSON_PASTE(WPI_JSON_FROM, __VA_ARGS__)) } #define WPI_DEFINE_TYPE_INTRUSIVE_WITH_DEFAULT(Type, ...) \ - friend void to_json(wpi::json& nlohmann_json_j, const Type& nlohmann_json_t) { WPI_JSON_EXPAND(WPI_JSON_PASTE(WPI_JSON_TO, __VA_ARGS__)) } \ - friend void from_json(const wpi::json& nlohmann_json_j, Type& nlohmann_json_t) { const Type nlohmann_json_default_obj{}; WPI_JSON_EXPAND(WPI_JSON_PASTE(WPI_JSON_FROM_WITH_DEFAULT, __VA_ARGS__)) } + friend void to_json(wpi::util::json& nlohmann_json_j, const Type& nlohmann_json_t) { WPI_JSON_EXPAND(WPI_JSON_PASTE(WPI_JSON_TO, __VA_ARGS__)) } \ + friend void from_json(const wpi::util::json& nlohmann_json_j, Type& nlohmann_json_t) { const Type nlohmann_json_default_obj{}; WPI_JSON_EXPAND(WPI_JSON_PASTE(WPI_JSON_FROM_WITH_DEFAULT, __VA_ARGS__)) } #define WPI_DEFINE_TYPE_INTRUSIVE_ONLY_SERIALIZE(Type, ...) \ - friend void to_json(wpi::json& nlohmann_json_j, const Type& nlohmann_json_t) { WPI_JSON_EXPAND(WPI_JSON_PASTE(WPI_JSON_TO, __VA_ARGS__)) } + friend void to_json(wpi::util::json& nlohmann_json_j, const Type& nlohmann_json_t) { WPI_JSON_EXPAND(WPI_JSON_PASTE(WPI_JSON_TO, __VA_ARGS__)) } /*! @brief macro @@ -415,15 +415,15 @@ @since version 3.9.0 */ #define WPI_DEFINE_TYPE_NON_INTRUSIVE(Type, ...) \ - inline void to_json(wpi::json& nlohmann_json_j, const Type& nlohmann_json_t) { WPI_JSON_EXPAND(WPI_JSON_PASTE(WPI_JSON_TO, __VA_ARGS__)) } \ - inline void from_json(const wpi::json& nlohmann_json_j, Type& nlohmann_json_t) { WPI_JSON_EXPAND(WPI_JSON_PASTE(WPI_JSON_FROM, __VA_ARGS__)) } + inline void to_json(wpi::util::json& nlohmann_json_j, const Type& nlohmann_json_t) { WPI_JSON_EXPAND(WPI_JSON_PASTE(WPI_JSON_TO, __VA_ARGS__)) } \ + inline void from_json(const wpi::util::json& nlohmann_json_j, Type& nlohmann_json_t) { WPI_JSON_EXPAND(WPI_JSON_PASTE(WPI_JSON_FROM, __VA_ARGS__)) } #define WPI_DEFINE_TYPE_NON_INTRUSIVE_ONLY_SERIALIZE(Type, ...) \ - inline void to_json(wpi::json& nlohmann_json_j, const Type& nlohmann_json_t) { WPI_JSON_EXPAND(WPI_JSON_PASTE(WPI_JSON_TO, __VA_ARGS__)) } + inline void to_json(wpi::util::json& nlohmann_json_j, const Type& nlohmann_json_t) { WPI_JSON_EXPAND(WPI_JSON_PASTE(WPI_JSON_TO, __VA_ARGS__)) } #define WPI_DEFINE_TYPE_NON_INTRUSIVE_WITH_DEFAULT(Type, ...) \ - inline void to_json(wpi::json& nlohmann_json_j, const Type& nlohmann_json_t) { WPI_JSON_EXPAND(WPI_JSON_PASTE(WPI_JSON_TO, __VA_ARGS__)) } \ - inline void from_json(const wpi::json& nlohmann_json_j, Type& nlohmann_json_t) { const Type nlohmann_json_default_obj{}; WPI_JSON_EXPAND(WPI_JSON_PASTE(WPI_JSON_FROM_WITH_DEFAULT, __VA_ARGS__)) } + inline void to_json(wpi::util::json& nlohmann_json_j, const Type& nlohmann_json_t) { WPI_JSON_EXPAND(WPI_JSON_PASTE(WPI_JSON_TO, __VA_ARGS__)) } \ + inline void from_json(const wpi::util::json& nlohmann_json_j, Type& nlohmann_json_t) { const Type nlohmann_json_default_obj{}; WPI_JSON_EXPAND(WPI_JSON_PASTE(WPI_JSON_FROM_WITH_DEFAULT, __VA_ARGS__)) } // inspired from https://stackoverflow.com/a/26745591 // allows to call any std function as if (e.g. with begin): @@ -453,7 +453,7 @@ template \ struct would_call_std_##std_name \ { \ - static constexpr auto const value = ::wpi::detail:: \ + static constexpr auto const value = ::wpi::util::detail:: \ is_detected_exact::value; \ }; \ } /* namespace detail2 */ \ diff --git a/wpiutil/src/main/native/thirdparty/json/include/wpi/util/detail/meta/type_traits.hpp b/wpiutil/src/main/native/thirdparty/json/include/wpi/util/detail/meta/type_traits.hpp index d98f445f5a..672328dc7d 100644 --- a/wpiutil/src/main/native/thirdparty/json/include/wpi/util/detail/meta/type_traits.hpp +++ b/wpiutil/src/main/native/thirdparty/json/include/wpi/util/detail/meta/type_traits.hpp @@ -557,7 +557,7 @@ template