diff --git a/apriltag/src/main/native/cpp/AprilTag.cpp b/apriltag/src/main/native/cpp/AprilTag.cpp index 46d696a04c..38055736e1 100644 --- a/apriltag/src/main/native/cpp/AprilTag.cpp +++ b/apriltag/src/main/native/cpp/AprilTag.cpp @@ -8,14 +8,6 @@ using namespace frc; -bool AprilTag::operator==(const AprilTag& other) const { - return ID == other.ID && pose == other.pose; -} - -bool AprilTag::operator!=(const AprilTag& other) const { - return !operator==(other); -} - void frc::to_json(wpi::json& json, const AprilTag& apriltag) { json = wpi::json{{"ID", apriltag.ID}, {"pose", apriltag.pose}}; } diff --git a/apriltag/src/main/native/cpp/AprilTagFieldLayout.cpp b/apriltag/src/main/native/cpp/AprilTagFieldLayout.cpp index 22ac3ccbef..0baf3b8df7 100644 --- a/apriltag/src/main/native/cpp/AprilTagFieldLayout.cpp +++ b/apriltag/src/main/native/cpp/AprilTagFieldLayout.cpp @@ -81,16 +81,6 @@ void AprilTagFieldLayout::Serialize(std::string_view path) { output.flush(); } -bool AprilTagFieldLayout::operator==(const AprilTagFieldLayout& other) const { - return m_apriltags == other.m_apriltags && m_origin == other.m_origin && - m_fieldLength == other.m_fieldLength && - m_fieldWidth == other.m_fieldWidth; -} - -bool AprilTagFieldLayout::operator!=(const AprilTagFieldLayout& other) const { - return !operator==(other); -} - void frc::to_json(wpi::json& json, const AprilTagFieldLayout& layout) { std::vector tagVector; tagVector.reserve(layout.m_apriltags.size()); diff --git a/apriltag/src/main/native/include/frc/apriltag/AprilTag.h b/apriltag/src/main/native/include/frc/apriltag/AprilTag.h index 444106df23..fc5723185c 100644 --- a/apriltag/src/main/native/include/frc/apriltag/AprilTag.h +++ b/apriltag/src/main/native/include/frc/apriltag/AprilTag.h @@ -21,19 +21,8 @@ struct WPILIB_DLLEXPORT AprilTag { /** * Checks equality between this AprilTag and another object. - * - * @param other The other object. - * @return Whether the two objects are equal. */ - bool operator==(const AprilTag& other) const; - - /** - * Checks inequality between this AprilTag and another object. - * - * @param other The other object. - * @return Whether the two objects are not equal. - */ - bool operator!=(const AprilTag& other) const; + bool operator==(const AprilTag&) const = default; }; WPILIB_DLLEXPORT diff --git a/apriltag/src/main/native/include/frc/apriltag/AprilTagFieldLayout.h b/apriltag/src/main/native/include/frc/apriltag/AprilTagFieldLayout.h index 1fe0b2adec..8f1c296a01 100644 --- a/apriltag/src/main/native/include/frc/apriltag/AprilTagFieldLayout.h +++ b/apriltag/src/main/native/include/frc/apriltag/AprilTagFieldLayout.h @@ -103,19 +103,8 @@ class WPILIB_DLLEXPORT AprilTagFieldLayout { /* * Checks equality between this AprilTagFieldLayout and another object. - * - * @param other The other object. - * @return Whether the two objects are equal. */ - bool operator==(const AprilTagFieldLayout& other) const; - - /** - * Checks inequality between this AprilTagFieldLayout and another object. - * - * @param other The other object. - * @return Whether the two objects are not equal. - */ - bool operator!=(const AprilTagFieldLayout& other) const; + bool operator==(const AprilTagFieldLayout&) const = default; private: std::unordered_map m_apriltags; diff --git a/cscore/src/main/native/include/cscore_cpp.h b/cscore/src/main/native/include/cscore_cpp.h index 615b200399..47bb4db840 100644 --- a/cscore/src/main/native/include/cscore_cpp.h +++ b/cscore/src/main/native/include/cscore_cpp.h @@ -90,8 +90,6 @@ struct VideoMode : public CS_VideoMode { return pixelFormat == other.pixelFormat && width == other.width && height == other.height && fps == other.fps; } - - bool operator!=(const VideoMode& other) const { return !(*this == other); } }; /** diff --git a/cscore/src/main/native/include/cscore_oo.h b/cscore/src/main/native/include/cscore_oo.h index f6fb1741a9..ab09fe7355 100644 --- a/cscore/src/main/native/include/cscore_oo.h +++ b/cscore/src/main/native/include/cscore_oo.h @@ -140,8 +140,6 @@ class VideoSource { return m_handle == other.m_handle; } - bool operator!=(const VideoSource& other) const { return !(*this == other); } - /** * Get the kind of the source. */ @@ -736,8 +734,6 @@ class VideoSink { return m_handle == other.m_handle; } - bool operator!=(const VideoSink& other) const { return !(*this == other); } - /** * Get the kind of the sink. */ diff --git a/ntcore/src/main/native/cpp/net3/SequenceNumber.cpp b/ntcore/src/main/native/cpp/net3/SequenceNumber.cpp deleted file mode 100644 index 04bec2dc33..0000000000 --- a/ntcore/src/main/native/cpp/net3/SequenceNumber.cpp +++ /dev/null @@ -1,29 +0,0 @@ -// Copyright (c) FIRST and other WPILib contributors. -// Open Source Software; you can modify and/or share it under the terms of -// the WPILib BSD license file in the root directory of this project. - -#include "SequenceNumber.h" - -namespace nt::net3 { - -bool operator<(const SequenceNumber& lhs, const SequenceNumber& rhs) { - if (lhs.m_value < rhs.m_value) { - return (rhs.m_value - lhs.m_value) < (1u << 15); - } else if (lhs.m_value > rhs.m_value) { - return (lhs.m_value - rhs.m_value) > (1u << 15); - } else { - return false; - } -} - -bool operator>(const SequenceNumber& lhs, const SequenceNumber& rhs) { - if (lhs.m_value < rhs.m_value) { - return (rhs.m_value - lhs.m_value) > (1u << 15); - } else if (lhs.m_value > rhs.m_value) { - return (lhs.m_value - rhs.m_value) < (1u << 15); - } else { - return false; - } -} - -} // namespace nt::net3 diff --git a/ntcore/src/main/native/cpp/net3/SequenceNumber.h b/ntcore/src/main/native/cpp/net3/SequenceNumber.h index e5ac2484c4..d8bf995172 100644 --- a/ntcore/src/main/native/cpp/net3/SequenceNumber.h +++ b/ntcore/src/main/native/cpp/net3/SequenceNumber.h @@ -4,6 +4,8 @@ #pragma once +#include + namespace nt::net3 { /* A sequence number per RFC 1982 */ @@ -26,34 +28,11 @@ class SequenceNumber { return tmp; } - friend bool operator<(const SequenceNumber& lhs, const SequenceNumber& rhs); - friend bool operator>(const SequenceNumber& lhs, const SequenceNumber& rhs); - friend bool operator<=(const SequenceNumber& lhs, const SequenceNumber& rhs); - friend bool operator>=(const SequenceNumber& lhs, const SequenceNumber& rhs); - friend bool operator==(const SequenceNumber& lhs, const SequenceNumber& rhs); - friend bool operator!=(const SequenceNumber& lhs, const SequenceNumber& rhs); + friend auto operator<=>(const SequenceNumber& lhs, + const SequenceNumber& rhs) = default; private: unsigned int m_value{0}; }; -bool operator<(const SequenceNumber& lhs, const SequenceNumber& rhs); -bool operator>(const SequenceNumber& lhs, const SequenceNumber& rhs); - -inline bool operator<=(const SequenceNumber& lhs, const SequenceNumber& rhs) { - return lhs == rhs || lhs < rhs; -} - -inline bool operator>=(const SequenceNumber& lhs, const SequenceNumber& rhs) { - return lhs == rhs || lhs > rhs; -} - -inline bool operator==(const SequenceNumber& lhs, const SequenceNumber& rhs) { - return lhs.m_value == rhs.m_value; -} - -inline bool operator!=(const SequenceNumber& lhs, const SequenceNumber& rhs) { - return lhs.m_value != rhs.m_value; -} - } // namespace nt::net3 diff --git a/ntcore/src/main/native/include/networktables/NetworkTableEntry.h b/ntcore/src/main/native/include/networktables/NetworkTableEntry.h index 939d03af25..b9d509aed1 100644 --- a/ntcore/src/main/native/include/networktables/NetworkTableEntry.h +++ b/ntcore/src/main/native/include/networktables/NetworkTableEntry.h @@ -520,14 +520,7 @@ class NetworkTableEntry final { * Equality operator. Returns true if both instances refer to the same * native handle. */ - bool operator==(const NetworkTableEntry& oth) const { - return m_handle == oth.m_handle; - } - - /** Inequality operator. */ - bool operator!=(const NetworkTableEntry& oth) const { - return !(*this == oth); - } + bool operator==(const NetworkTableEntry&) const = default; protected: /* Native handle */ diff --git a/ntcore/src/main/native/include/networktables/NetworkTableInstance.h b/ntcore/src/main/native/include/networktables/NetworkTableInstance.h index a161c2fe64..b8555bf56c 100644 --- a/ntcore/src/main/native/include/networktables/NetworkTableInstance.h +++ b/ntcore/src/main/native/include/networktables/NetworkTableInstance.h @@ -688,14 +688,7 @@ class NetworkTableInstance final { * Equality operator. Returns true if both instances refer to the same * native handle. */ - bool operator==(const NetworkTableInstance& other) const { - return m_handle == other.m_handle; - } - - /** Inequality operator. */ - bool operator!=(const NetworkTableInstance& other) const { - return !(*this == other); - } + bool operator==(const NetworkTableInstance&) const = default; private: /* Native handle */ diff --git a/ntcore/src/main/native/include/networktables/NetworkTableValue.h b/ntcore/src/main/native/include/networktables/NetworkTableValue.h index 52e1430fd1..673a833eb4 100644 --- a/ntcore/src/main/native/include/networktables/NetworkTableValue.h +++ b/ntcore/src/main/native/include/networktables/NetworkTableValue.h @@ -636,9 +636,6 @@ class Value final { }; bool operator==(const Value& lhs, const Value& rhs); -inline bool operator!=(const Value& lhs, const Value& rhs) { - return !(lhs == rhs); -} /** * NetworkTable Value alias for similarity with Java. diff --git a/ntcore/src/main/native/include/networktables/Topic.h b/ntcore/src/main/native/include/networktables/Topic.h index 2f28f0c494..9825135450 100644 --- a/ntcore/src/main/native/include/networktables/Topic.h +++ b/ntcore/src/main/native/include/networktables/Topic.h @@ -278,10 +278,7 @@ class Topic { * Equality operator. Returns true if both instances refer to the same * native handle. */ - bool operator==(const Topic& oth) const { return m_handle == oth.m_handle; } - - /** Inequality operator. */ - bool operator!=(const Topic& oth) const { return !(*this == oth); } + bool operator==(const Topic&) const = default; protected: NT_Topic m_handle{0}; diff --git a/wpilibc/src/main/native/include/frc/util/Color.h b/wpilibc/src/main/native/include/frc/util/Color.h index 822d3b01e6..6e4d3ddb27 100644 --- a/wpilibc/src/main/native/include/frc/util/Color.h +++ b/wpilibc/src/main/native/include/frc/util/Color.h @@ -763,6 +763,8 @@ class Color { constexpr Color(int r, int g, int b) : Color(r / 255.0, g / 255.0, b / 255.0) {} + constexpr bool operator==(const Color&) const = default; + /** * Creates a Color from HSV values. * @@ -830,14 +832,6 @@ class Color { } }; -inline bool operator==(const Color& c1, const Color& c2) { - return c1.red == c2.red && c1.green == c2.green && c1.blue == c2.blue; -} - -inline bool operator!=(const Color& c1, const Color& c2) { - return !(c1 == c2); -} - /* * FIRST Colors */ diff --git a/wpilibc/src/main/native/include/frc/util/Color8Bit.h b/wpilibc/src/main/native/include/frc/util/Color8Bit.h index 099196be08..10afead93d 100644 --- a/wpilibc/src/main/native/include/frc/util/Color8Bit.h +++ b/wpilibc/src/main/native/include/frc/util/Color8Bit.h @@ -44,6 +44,8 @@ class Color8Bit { return Color(red / 255.0, green / 255.0, blue / 255.0); } + constexpr bool operator==(const Color8Bit&) const = default; + /** * Return this color represented as a hex string. * @@ -56,8 +58,4 @@ class Color8Bit { int blue = 0; }; -inline bool operator==(const Color8Bit& c1, const Color8Bit& c2) { - return c1.red == c2.red && c1.green == c2.green && c1.blue == c2.blue; -} - } // namespace frc diff --git a/wpimath/src/main/native/cpp/geometry/Pose2d.cpp b/wpimath/src/main/native/cpp/geometry/Pose2d.cpp index 3e7c0c0bd9..2648a909de 100644 --- a/wpimath/src/main/native/cpp/geometry/Pose2d.cpp +++ b/wpimath/src/main/native/cpp/geometry/Pose2d.cpp @@ -15,14 +15,6 @@ Transform2d Pose2d::operator-(const Pose2d& other) const { return Transform2d{pose.Translation(), pose.Rotation()}; } -bool Pose2d::operator==(const Pose2d& other) const { - return m_translation == other.m_translation && m_rotation == other.m_rotation; -} - -bool Pose2d::operator!=(const Pose2d& other) const { - return !operator==(other); -} - Pose2d Pose2d::RelativeTo(const Pose2d& other) const { const Transform2d transform{other, *this}; return {transform.Translation(), transform.Rotation()}; diff --git a/wpimath/src/main/native/cpp/geometry/Pose3d.cpp b/wpimath/src/main/native/cpp/geometry/Pose3d.cpp index 8909cc8d10..4732c4d10c 100644 --- a/wpimath/src/main/native/cpp/geometry/Pose3d.cpp +++ b/wpimath/src/main/native/cpp/geometry/Pose3d.cpp @@ -52,14 +52,6 @@ Transform3d Pose3d::operator-(const Pose3d& other) const { return Transform3d{pose.Translation(), pose.Rotation()}; } -bool Pose3d::operator==(const Pose3d& other) const { - return m_translation == other.m_translation && m_rotation == other.m_rotation; -} - -bool Pose3d::operator!=(const Pose3d& other) const { - return !operator==(other); -} - Pose3d Pose3d::operator*(double scalar) const { return Pose3d{m_translation * scalar, m_rotation * scalar}; } diff --git a/wpimath/src/main/native/cpp/geometry/Quaternion.cpp b/wpimath/src/main/native/cpp/geometry/Quaternion.cpp index 7f77b139ca..9c2cedaecf 100644 --- a/wpimath/src/main/native/cpp/geometry/Quaternion.cpp +++ b/wpimath/src/main/native/cpp/geometry/Quaternion.cpp @@ -33,10 +33,6 @@ bool Quaternion::operator==(const Quaternion& other) const { return std::abs(m_r * other.m_r + m_v.dot(other.m_v)) > 1.0 - 1E-9; } -bool Quaternion::operator!=(const Quaternion& other) const { - return !operator==(other); -} - Quaternion Quaternion::Inverse() const { return Quaternion{m_r, -m_v(0), -m_v(1), -m_v(2)}; } diff --git a/wpimath/src/main/native/cpp/geometry/Rotation3d.cpp b/wpimath/src/main/native/cpp/geometry/Rotation3d.cpp index 7146df6d03..bf27407313 100644 --- a/wpimath/src/main/native/cpp/geometry/Rotation3d.cpp +++ b/wpimath/src/main/native/cpp/geometry/Rotation3d.cpp @@ -170,14 +170,6 @@ Rotation3d Rotation3d::operator/(double scalar) const { return *this * (1.0 / scalar); } -bool Rotation3d::operator==(const Rotation3d& other) const { - return m_q == other.m_q; -} - -bool Rotation3d::operator!=(const Rotation3d& other) const { - return !operator==(other); -} - Rotation3d Rotation3d::RotateBy(const Rotation3d& other) const { return Rotation3d{other.m_q * m_q}; } diff --git a/wpimath/src/main/native/cpp/geometry/Transform2d.cpp b/wpimath/src/main/native/cpp/geometry/Transform2d.cpp index dd3019d276..25b05907ed 100644 --- a/wpimath/src/main/native/cpp/geometry/Transform2d.cpp +++ b/wpimath/src/main/native/cpp/geometry/Transform2d.cpp @@ -21,11 +21,3 @@ Transform2d::Transform2d(Pose2d initial, Pose2d final) { Transform2d Transform2d::operator+(const Transform2d& other) const { return Transform2d{Pose2d{}, Pose2d{}.TransformBy(*this).TransformBy(other)}; } - -bool Transform2d::operator==(const Transform2d& other) const { - return m_translation == other.m_translation && m_rotation == other.m_rotation; -} - -bool Transform2d::operator!=(const Transform2d& other) const { - return !operator==(other); -} diff --git a/wpimath/src/main/native/cpp/geometry/Transform3d.cpp b/wpimath/src/main/native/cpp/geometry/Transform3d.cpp index f8a11857e9..1cfabaa1c4 100644 --- a/wpimath/src/main/native/cpp/geometry/Transform3d.cpp +++ b/wpimath/src/main/native/cpp/geometry/Transform3d.cpp @@ -31,11 +31,3 @@ Transform3d Transform3d::Inverse() const { Transform3d Transform3d::operator+(const Transform3d& other) const { return Transform3d{Pose3d{}, Pose3d{}.TransformBy(*this).TransformBy(other)}; } - -bool Transform3d::operator==(const Transform3d& other) const { - return m_translation == other.m_translation && m_rotation == other.m_rotation; -} - -bool Transform3d::operator!=(const Transform3d& other) const { - return !operator==(other); -} diff --git a/wpimath/src/main/native/cpp/geometry/Translation2d.cpp b/wpimath/src/main/native/cpp/geometry/Translation2d.cpp index a44414c2b9..d463696e6d 100644 --- a/wpimath/src/main/native/cpp/geometry/Translation2d.cpp +++ b/wpimath/src/main/native/cpp/geometry/Translation2d.cpp @@ -23,10 +23,6 @@ bool Translation2d::operator==(const Translation2d& other) const { units::math::abs(m_y - other.m_y) < 1E-9_m; } -bool Translation2d::operator!=(const Translation2d& other) const { - return !operator==(other); -} - void frc::to_json(wpi::json& json, const Translation2d& translation) { json = wpi::json{{"x", translation.X().value()}, {"y", translation.Y().value()}}; diff --git a/wpimath/src/main/native/cpp/geometry/Translation3d.cpp b/wpimath/src/main/native/cpp/geometry/Translation3d.cpp index 690a59eaf8..2c53791bfd 100644 --- a/wpimath/src/main/native/cpp/geometry/Translation3d.cpp +++ b/wpimath/src/main/native/cpp/geometry/Translation3d.cpp @@ -41,10 +41,6 @@ bool Translation3d::operator==(const Translation3d& other) const { units::math::abs(m_z - other.m_z) < 1E-9_m; } -bool Translation3d::operator!=(const Translation3d& other) const { - return !operator==(other); -} - void frc::to_json(wpi::json& json, const Translation3d& translation) { json = wpi::json{{"x", translation.X().value()}, {"y", translation.Y().value()}, diff --git a/wpimath/src/main/native/cpp/trajectory/Trajectory.cpp b/wpimath/src/main/native/cpp/trajectory/Trajectory.cpp index 097edce726..de47547276 100644 --- a/wpimath/src/main/native/cpp/trajectory/Trajectory.cpp +++ b/wpimath/src/main/native/cpp/trajectory/Trajectory.cpp @@ -13,16 +13,6 @@ using namespace frc; -bool Trajectory::State::operator==(const Trajectory::State& other) const { - return t == other.t && velocity == other.velocity && - acceleration == other.acceleration && pose == other.pose && - curvature == other.curvature; -} - -bool Trajectory::State::operator!=(const Trajectory::State& other) const { - return !operator==(other); -} - Trajectory::State Trajectory::State::Interpolate(State endValue, double i) const { // Find the new [t] value. @@ -163,11 +153,3 @@ void frc::from_json(const wpi::json& json, Trajectory::State& state) { units::meters_per_second_squared_t{json.at("acceleration").get()}; state.curvature = units::curvature_t{json.at("curvature").get()}; } - -bool Trajectory::operator==(const Trajectory& other) const { - return m_states == other.States(); -} - -bool Trajectory::operator!=(const Trajectory& other) const { - return !operator==(other); -} diff --git a/wpimath/src/main/native/include/frc/geometry/Pose2d.h b/wpimath/src/main/native/include/frc/geometry/Pose2d.h index f992af4c7a..d096e8c9ed 100644 --- a/wpimath/src/main/native/include/frc/geometry/Pose2d.h +++ b/wpimath/src/main/native/include/frc/geometry/Pose2d.h @@ -70,19 +70,8 @@ class WPILIB_DLLEXPORT Pose2d { /** * Checks equality between this Pose2d and another object. - * - * @param other The other object. - * @return Whether the two objects are equal. */ - bool operator==(const Pose2d& other) const; - - /** - * Checks inequality between this Pose2d and another object. - * - * @param other The other object. - * @return Whether the two objects are not equal. - */ - bool operator!=(const Pose2d& other) const; + bool operator==(const Pose2d&) const = default; /** * Returns the underlying translation. diff --git a/wpimath/src/main/native/include/frc/geometry/Pose3d.h b/wpimath/src/main/native/include/frc/geometry/Pose3d.h index ab82877e7c..8c7ace3681 100644 --- a/wpimath/src/main/native/include/frc/geometry/Pose3d.h +++ b/wpimath/src/main/native/include/frc/geometry/Pose3d.h @@ -74,19 +74,8 @@ class WPILIB_DLLEXPORT Pose3d { /** * Checks equality between this Pose3d and another object. - * - * @param other The other object. - * @return Whether the two objects are equal. */ - bool operator==(const Pose3d& other) const; - - /** - * Checks inequality between this Pose3d and another object. - * - * @param other The other object. - * @return Whether the two objects are not equal. - */ - bool operator!=(const Pose3d& other) const; + bool operator==(const Pose3d&) const = default; /** * Returns the underlying translation. diff --git a/wpimath/src/main/native/include/frc/geometry/Quaternion.h b/wpimath/src/main/native/include/frc/geometry/Quaternion.h index 97933abe5b..b5a318b25a 100644 --- a/wpimath/src/main/native/include/frc/geometry/Quaternion.h +++ b/wpimath/src/main/native/include/frc/geometry/Quaternion.h @@ -46,14 +46,6 @@ class WPILIB_DLLEXPORT Quaternion { */ bool operator==(const Quaternion& other) const; - /** - * Checks inequality between this Quaternion and another object. - * - * @param other The other object. - * @return Whether the two objects are not equal. - */ - bool operator!=(const Quaternion& other) const; - /** * Returns the inverse of the quaternion. */ diff --git a/wpimath/src/main/native/include/frc/geometry/Rotation2d.h b/wpimath/src/main/native/include/frc/geometry/Rotation2d.h index 11074af9a8..be3315aa81 100644 --- a/wpimath/src/main/native/include/frc/geometry/Rotation2d.h +++ b/wpimath/src/main/native/include/frc/geometry/Rotation2d.h @@ -108,14 +108,6 @@ class WPILIB_DLLEXPORT Rotation2d { */ constexpr bool operator==(const Rotation2d& other) const; - /** - * Checks inequality between this Rotation2d and another object. - * - * @param other The other object. - * @return Whether the two objects are not equal. - */ - constexpr bool operator!=(const Rotation2d& other) const; - /** * Adds the new rotation to the current rotation using a rotation matrix. * diff --git a/wpimath/src/main/native/include/frc/geometry/Rotation2d.inc b/wpimath/src/main/native/include/frc/geometry/Rotation2d.inc index 5399c89f90..9b5e45355d 100644 --- a/wpimath/src/main/native/include/frc/geometry/Rotation2d.inc +++ b/wpimath/src/main/native/include/frc/geometry/Rotation2d.inc @@ -58,10 +58,6 @@ constexpr bool Rotation2d::operator==(const Rotation2d& other) const { : std::hypot(Cos() - other.Cos(), Sin() - other.Sin())) < 1E-9; } -constexpr bool Rotation2d::operator!=(const Rotation2d& other) const { - return !operator==(other); -} - constexpr Rotation2d Rotation2d::RotateBy(const Rotation2d& other) const { return {Cos() * other.Cos() - Sin() * other.Sin(), Cos() * other.Sin() + Sin() * other.Cos()}; diff --git a/wpimath/src/main/native/include/frc/geometry/Rotation3d.h b/wpimath/src/main/native/include/frc/geometry/Rotation3d.h index 39674733d2..7c1a60d65a 100644 --- a/wpimath/src/main/native/include/frc/geometry/Rotation3d.h +++ b/wpimath/src/main/native/include/frc/geometry/Rotation3d.h @@ -125,19 +125,8 @@ class WPILIB_DLLEXPORT Rotation3d { /** * Checks equality between this Rotation3d and another object. - * - * @param other The other object. - * @return Whether the two objects are equal. */ - bool operator==(const Rotation3d& other) const; - - /** - * Checks inequality between this Rotation3d and another object. - * - * @param other The other object. - * @return Whether the two objects are not equal. - */ - bool operator!=(const Rotation3d& other) const; + bool operator==(const Rotation3d&) const = default; /** * Adds the new rotation to the current rotation. diff --git a/wpimath/src/main/native/include/frc/geometry/Transform2d.h b/wpimath/src/main/native/include/frc/geometry/Transform2d.h index 7a87315616..3c21ec1d6e 100644 --- a/wpimath/src/main/native/include/frc/geometry/Transform2d.h +++ b/wpimath/src/main/native/include/frc/geometry/Transform2d.h @@ -103,19 +103,8 @@ class WPILIB_DLLEXPORT Transform2d { /** * Checks equality between this Transform2d and another object. - * - * @param other The other object. - * @return Whether the two objects are equal. */ - bool operator==(const Transform2d& other) const; - - /** - * Checks inequality between this Transform2d and another object. - * - * @param other The other object. - * @return Whether the two objects are not equal. - */ - bool operator!=(const Transform2d& other) const; + bool operator==(const Transform2d&) const = default; private: Translation2d m_translation; diff --git a/wpimath/src/main/native/include/frc/geometry/Transform3d.h b/wpimath/src/main/native/include/frc/geometry/Transform3d.h index 88fa8fca2f..5f50ec2577 100644 --- a/wpimath/src/main/native/include/frc/geometry/Transform3d.h +++ b/wpimath/src/main/native/include/frc/geometry/Transform3d.h @@ -108,19 +108,8 @@ class WPILIB_DLLEXPORT Transform3d { /** * Checks equality between this Transform3d and another object. - * - * @param other The other object. - * @return Whether the two objects are equal. */ - bool operator==(const Transform3d& other) const; - - /** - * Checks inequality between this Transform3d and another object. - * - * @param other The other object. - * @return Whether the two objects are not equal. - */ - bool operator!=(const Transform3d& other) const; + bool operator==(const Transform3d&) const = default; private: Translation3d m_translation; diff --git a/wpimath/src/main/native/include/frc/geometry/Translation2d.h b/wpimath/src/main/native/include/frc/geometry/Translation2d.h index dd1a8d29b2..e1685108a3 100644 --- a/wpimath/src/main/native/include/frc/geometry/Translation2d.h +++ b/wpimath/src/main/native/include/frc/geometry/Translation2d.h @@ -170,14 +170,6 @@ class WPILIB_DLLEXPORT Translation2d { */ bool operator==(const Translation2d& other) const; - /** - * Checks inequality between this Translation2d and another object. - * - * @param other The other object. - * @return Whether the two objects are not equal. - */ - bool operator!=(const Translation2d& other) const; - private: units::meter_t m_x = 0_m; units::meter_t m_y = 0_m; diff --git a/wpimath/src/main/native/include/frc/geometry/Translation3d.h b/wpimath/src/main/native/include/frc/geometry/Translation3d.h index 4477749f49..ab641fa02b 100644 --- a/wpimath/src/main/native/include/frc/geometry/Translation3d.h +++ b/wpimath/src/main/native/include/frc/geometry/Translation3d.h @@ -172,14 +172,6 @@ class WPILIB_DLLEXPORT Translation3d { */ bool operator==(const Translation3d& other) const; - /** - * Checks inequality between this Translation3d and another object. - * - * @param other The other object. - * @return Whether the two objects are not equal. - */ - bool operator!=(const Translation3d& other) const; - private: units::meter_t m_x = 0_m; units::meter_t m_y = 0_m; diff --git a/wpimath/src/main/native/include/frc/geometry/Twist2d.h b/wpimath/src/main/native/include/frc/geometry/Twist2d.h index 690686a44e..620b6887af 100644 --- a/wpimath/src/main/native/include/frc/geometry/Twist2d.h +++ b/wpimath/src/main/native/include/frc/geometry/Twist2d.h @@ -46,14 +46,6 @@ struct WPILIB_DLLEXPORT Twist2d { units::math::abs(dtheta - other.dtheta) < 1E-9_rad; } - /** - * Checks inequality between this Twist2d and another object. - * - * @param other The other object. - * @return Whether the two objects are not equal. - */ - bool operator!=(const Twist2d& other) const { return !operator==(other); } - /** * Scale this by a given factor. * diff --git a/wpimath/src/main/native/include/frc/geometry/Twist3d.h b/wpimath/src/main/native/include/frc/geometry/Twist3d.h index 465b553f17..3040ab3ef0 100644 --- a/wpimath/src/main/native/include/frc/geometry/Twist3d.h +++ b/wpimath/src/main/native/include/frc/geometry/Twist3d.h @@ -65,14 +65,6 @@ struct WPILIB_DLLEXPORT Twist3d { units::math::abs(rz - other.rz) < 1E-9_rad; } - /** - * Checks inequality between this Twist3d and another object. - * - * @param other The other object. - * @return Whether the two objects are not equal. - */ - bool operator!=(const Twist3d& other) const { return !operator==(other); } - /** * Scale this by a given factor. * diff --git a/wpimath/src/main/native/include/frc/trajectory/Trajectory.h b/wpimath/src/main/native/include/frc/trajectory/Trajectory.h index d071ca36a3..f5ee79b65a 100644 --- a/wpimath/src/main/native/include/frc/trajectory/Trajectory.h +++ b/wpimath/src/main/native/include/frc/trajectory/Trajectory.h @@ -48,19 +48,8 @@ class WPILIB_DLLEXPORT Trajectory { /** * Checks equality between this State and another object. - * - * @param other The other object. - * @return Whether the two objects are equal. */ - bool operator==(const State& other) const; - - /** - * Checks inequality between this State and another object. - * - * @param other The other object. - * @return Whether the two objects are not equal. - */ - bool operator!=(const State& other) const; + bool operator==(const State&) const = default; /** * Interpolates between two States. @@ -140,19 +129,8 @@ class WPILIB_DLLEXPORT Trajectory { /** * Checks equality between this Trajectory and another object. - * - * @param other The other object. - * @return Whether the two objects are equal. */ - bool operator==(const Trajectory& other) const; - - /** - * Checks inequality between this Trajectory and another object. - * - * @param other The other object. - * @return Whether the two objects are inequal. - */ - bool operator!=(const Trajectory& other) const; + bool operator==(const Trajectory&) const = default; private: std::vector m_states; diff --git a/wpimath/src/main/native/include/frc/trajectory/TrapezoidProfile.h b/wpimath/src/main/native/include/frc/trajectory/TrapezoidProfile.h index 5925a306e8..24a8253f7d 100644 --- a/wpimath/src/main/native/include/frc/trajectory/TrapezoidProfile.h +++ b/wpimath/src/main/native/include/frc/trajectory/TrapezoidProfile.h @@ -68,10 +68,7 @@ class TrapezoidProfile { public: Distance_t position{0}; Velocity_t velocity{0}; - bool operator==(const State& rhs) const { - return position == rhs.position && velocity == rhs.velocity; - } - bool operator!=(const State& rhs) const { return !(*this == rhs); } + bool operator==(const State&) const = default; }; /** diff --git a/wpiutil/src/main/native/include/wpi/circular_buffer.h b/wpiutil/src/main/native/include/wpi/circular_buffer.h index 40913f9e64..c54e2f55db 100644 --- a/wpiutil/src/main/native/include/wpi/circular_buffer.h +++ b/wpiutil/src/main/native/include/wpi/circular_buffer.h @@ -43,10 +43,7 @@ class circular_buffer { ++(*this); return retval; } - bool operator==(const iterator& other) const { - return m_buffer == other.m_buffer && m_index == other.m_index; - } - bool operator!=(const iterator& other) const { return !(*this == other); } + bool operator==(const iterator&) const = default; reference operator*() { return (*m_buffer)[m_index]; } private: @@ -74,12 +71,7 @@ class circular_buffer { ++(*this); return retval; } - bool operator==(const const_iterator& other) const { - return m_buffer == other.m_buffer && m_index == other.m_index; - } - bool operator!=(const const_iterator& other) const { - return !(*this == other); - } + bool operator==(const const_iterator&) const = default; const_reference operator*() const { return (*m_buffer)[m_index]; } private: diff --git a/wpiutil/src/main/native/include/wpi/static_circular_buffer.h b/wpiutil/src/main/native/include/wpi/static_circular_buffer.h index 8cbf3fe64e..76498a1192 100644 --- a/wpiutil/src/main/native/include/wpi/static_circular_buffer.h +++ b/wpiutil/src/main/native/include/wpi/static_circular_buffer.h @@ -38,10 +38,7 @@ class static_circular_buffer { ++(*this); return retval; } - bool operator==(const iterator& other) const { - return m_buffer == other.m_buffer && m_index == other.m_index; - } - bool operator!=(const iterator& other) const { return !(*this == other); } + bool operator==(const iterator&) const = default; reference operator*() { return (*m_buffer)[m_index]; } private: @@ -69,12 +66,7 @@ class static_circular_buffer { ++(*this); return retval; } - bool operator==(const const_iterator& other) const { - return m_buffer == other.m_buffer && m_index == other.m_index; - } - bool operator!=(const const_iterator& other) const { - return !(*this == other); - } + bool operator==(const const_iterator&) const = default; const_reference operator*() const { return (*m_buffer)[m_index]; } private: