mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
Use defaulted comparison operators in C++ (#4723)
Comparison operators which compared against every class member variable now use C++20's default comparison operators. Also remove operator!= that in C++20 is now auto-generated from operator==.
This commit is contained in:
@@ -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}};
|
||||
}
|
||||
|
||||
@@ -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<AprilTag> tagVector;
|
||||
tagVector.reserve(layout.m_apriltags.size());
|
||||
|
||||
@@ -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
|
||||
|
||||
@@ -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<int, AprilTag> m_apriltags;
|
||||
|
||||
@@ -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); }
|
||||
};
|
||||
|
||||
/**
|
||||
|
||||
@@ -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.
|
||||
*/
|
||||
|
||||
@@ -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
|
||||
@@ -4,6 +4,8 @@
|
||||
|
||||
#pragma once
|
||||
|
||||
#include <compare>
|
||||
|
||||
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
|
||||
|
||||
@@ -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 */
|
||||
|
||||
@@ -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 */
|
||||
|
||||
@@ -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.
|
||||
|
||||
@@ -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};
|
||||
|
||||
@@ -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
|
||||
*/
|
||||
|
||||
@@ -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
|
||||
|
||||
@@ -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()};
|
||||
|
||||
@@ -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};
|
||||
}
|
||||
|
||||
@@ -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)};
|
||||
}
|
||||
|
||||
@@ -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};
|
||||
}
|
||||
|
||||
@@ -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);
|
||||
}
|
||||
|
||||
@@ -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);
|
||||
}
|
||||
|
||||
@@ -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()}};
|
||||
|
||||
@@ -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()},
|
||||
|
||||
@@ -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<double>()};
|
||||
state.curvature = units::curvature_t{json.at("curvature").get<double>()};
|
||||
}
|
||||
|
||||
bool Trajectory::operator==(const Trajectory& other) const {
|
||||
return m_states == other.States();
|
||||
}
|
||||
|
||||
bool Trajectory::operator!=(const Trajectory& other) const {
|
||||
return !operator==(other);
|
||||
}
|
||||
|
||||
@@ -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.
|
||||
|
||||
@@ -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.
|
||||
|
||||
@@ -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.
|
||||
*/
|
||||
|
||||
@@ -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.
|
||||
*
|
||||
|
||||
@@ -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()};
|
||||
|
||||
@@ -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.
|
||||
|
||||
@@ -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;
|
||||
|
||||
@@ -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;
|
||||
|
||||
@@ -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;
|
||||
|
||||
@@ -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;
|
||||
|
||||
@@ -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.
|
||||
*
|
||||
|
||||
@@ -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.
|
||||
*
|
||||
|
||||
@@ -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<State> m_states;
|
||||
|
||||
@@ -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;
|
||||
};
|
||||
|
||||
/**
|
||||
|
||||
@@ -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:
|
||||
|
||||
@@ -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:
|
||||
|
||||
Reference in New Issue
Block a user