mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
[wpimath] Mark all geometry classes as final (#8790)
In Java, these are likely to become value classes in the future. Make C++ final for consistency.
This commit is contained in:
@@ -9,7 +9,7 @@ import org.wpilib.math.linalg.Vector;
|
||||
import org.wpilib.math.numbers.N3;
|
||||
|
||||
/** A class representing a coordinate system axis within the NWU coordinate system. */
|
||||
public class CoordinateAxis {
|
||||
public final class CoordinateAxis {
|
||||
private static final CoordinateAxis m_n = new CoordinateAxis(1.0, 0.0, 0.0);
|
||||
private static final CoordinateAxis m_s = new CoordinateAxis(-1.0, 0.0, 0.0);
|
||||
private static final CoordinateAxis m_e = new CoordinateAxis(0.0, -1.0, 0.0);
|
||||
|
||||
@@ -9,7 +9,7 @@ import org.wpilib.math.util.MathSharedStore;
|
||||
import org.wpilib.math.util.Nat;
|
||||
|
||||
/** A helper class that converts Pose3d objects between different standard coordinate frames. */
|
||||
public class CoordinateSystem {
|
||||
public final class CoordinateSystem {
|
||||
private static final CoordinateSystem m_nwu =
|
||||
new CoordinateSystem(CoordinateAxis.N(), CoordinateAxis.W(), CoordinateAxis.U());
|
||||
private static final CoordinateSystem m_edn =
|
||||
|
||||
@@ -18,7 +18,7 @@ import org.wpilib.util.protobuf.ProtobufSerializable;
|
||||
import org.wpilib.util.struct.StructSerializable;
|
||||
|
||||
/** Represents a 2d ellipse space containing translational, rotational, and scaling components. */
|
||||
public class Ellipse2d implements ProtobufSerializable, StructSerializable {
|
||||
public final class Ellipse2d implements ProtobufSerializable, StructSerializable {
|
||||
private final Pose2d m_center;
|
||||
private final double m_xSemiAxis;
|
||||
private final double m_ySemiAxis;
|
||||
|
||||
@@ -24,7 +24,8 @@ import org.wpilib.util.struct.StructSerializable;
|
||||
|
||||
/** Represents a 2D pose containing translational and rotational elements. */
|
||||
@Json
|
||||
public class Pose2d implements Interpolatable<Pose2d>, ProtobufSerializable, StructSerializable {
|
||||
public final class Pose2d
|
||||
implements Interpolatable<Pose2d>, ProtobufSerializable, StructSerializable {
|
||||
/**
|
||||
* A preallocated Pose2d representing the origin.
|
||||
*
|
||||
|
||||
@@ -24,7 +24,8 @@ import org.wpilib.util.struct.StructSerializable;
|
||||
|
||||
/** Represents a 3D pose containing translational and rotational elements. */
|
||||
@Json
|
||||
public class Pose3d implements Interpolatable<Pose3d>, ProtobufSerializable, StructSerializable {
|
||||
public final class Pose3d
|
||||
implements Interpolatable<Pose3d>, ProtobufSerializable, StructSerializable {
|
||||
/**
|
||||
* A preallocated Pose3d representing the origin.
|
||||
*
|
||||
|
||||
@@ -16,7 +16,7 @@ import org.wpilib.util.struct.StructSerializable;
|
||||
|
||||
/** Represents a quaternion. */
|
||||
@Json
|
||||
public class Quaternion implements ProtobufSerializable, StructSerializable {
|
||||
public final class Quaternion implements ProtobufSerializable, StructSerializable {
|
||||
// Scalar r in versor form
|
||||
@Json.Ignore private final double m_w;
|
||||
|
||||
|
||||
@@ -16,7 +16,7 @@ import org.wpilib.util.struct.StructSerializable;
|
||||
/**
|
||||
* Represents a 2d rectangular space containing translational, rotational, and scaling components.
|
||||
*/
|
||||
public class Rectangle2d implements ProtobufSerializable, StructSerializable {
|
||||
public final class Rectangle2d implements ProtobufSerializable, StructSerializable {
|
||||
private final Pose2d m_center;
|
||||
private final double m_xWidth;
|
||||
private final double m_yWidth;
|
||||
|
||||
@@ -25,7 +25,7 @@ import org.wpilib.util.struct.StructSerializable;
|
||||
* A rotation in a 2D coordinate frame represented by a point on the unit circle (cosine and sine).
|
||||
*/
|
||||
@Json
|
||||
public class Rotation2d
|
||||
public final class Rotation2d
|
||||
implements Interpolatable<Rotation2d>, ProtobufSerializable, StructSerializable {
|
||||
/**
|
||||
* A preallocated Rotation2d representing no rotation.
|
||||
|
||||
@@ -66,7 +66,7 @@ import org.wpilib.util.struct.StructSerializable;
|
||||
* applying the same series in the opposite order intrinsically.
|
||||
*/
|
||||
@Json
|
||||
public class Rotation3d
|
||||
public final class Rotation3d
|
||||
implements Interpolatable<Rotation3d>, ProtobufSerializable, StructSerializable {
|
||||
/**
|
||||
* A preallocated Rotation3d representing no rotation.
|
||||
|
||||
@@ -18,7 +18,7 @@ import org.wpilib.util.protobuf.ProtobufSerializable;
|
||||
import org.wpilib.util.struct.StructSerializable;
|
||||
|
||||
/** Represents a transformation for a Pose2d in the pose's frame. */
|
||||
public class Transform2d implements ProtobufSerializable, StructSerializable {
|
||||
public final class Transform2d implements ProtobufSerializable, StructSerializable {
|
||||
/**
|
||||
* A preallocated Transform2d representing no transformation.
|
||||
*
|
||||
|
||||
@@ -22,7 +22,7 @@ import org.wpilib.util.struct.StructSerializable;
|
||||
* Represents a transformation for a Pose3d in the pose's frame. Translation is applied before
|
||||
* rotation. (The translation is applied in the pose's original frame, not the transformed frame.)
|
||||
*/
|
||||
public class Transform3d implements ProtobufSerializable, StructSerializable {
|
||||
public final class Transform3d implements ProtobufSerializable, StructSerializable {
|
||||
/**
|
||||
* A preallocated Transform3d representing no transformation.
|
||||
*
|
||||
|
||||
@@ -29,7 +29,7 @@ import org.wpilib.util.struct.StructSerializable;
|
||||
* origin facing in the positive X direction, forward is positive X and left is positive Y.
|
||||
*/
|
||||
@Json
|
||||
public class Translation2d
|
||||
public final class Translation2d
|
||||
implements Interpolatable<Translation2d>, ProtobufSerializable, StructSerializable {
|
||||
/**
|
||||
* A preallocated Translation2d representing the origin.
|
||||
|
||||
@@ -30,7 +30,7 @@ import org.wpilib.util.struct.StructSerializable;
|
||||
* positive Z.
|
||||
*/
|
||||
@Json
|
||||
public class Translation3d
|
||||
public final class Translation3d
|
||||
implements Interpolatable<Translation3d>, ProtobufSerializable, StructSerializable {
|
||||
/**
|
||||
* A preallocated Translation3d representing the origin.
|
||||
|
||||
@@ -16,7 +16,7 @@ import org.wpilib.util.struct.StructSerializable;
|
||||
*
|
||||
* <p>A Twist can be used to represent a difference between two poses.
|
||||
*/
|
||||
public class Twist2d implements ProtobufSerializable, StructSerializable {
|
||||
public final class Twist2d implements ProtobufSerializable, StructSerializable {
|
||||
/** Linear "dx" component. */
|
||||
public double dx;
|
||||
|
||||
|
||||
@@ -17,7 +17,7 @@ import org.wpilib.util.struct.StructSerializable;
|
||||
*
|
||||
* <p>A Twist can be used to represent a difference between two poses.
|
||||
*/
|
||||
public class Twist3d implements ProtobufSerializable, StructSerializable {
|
||||
public final class Twist3d implements ProtobufSerializable, StructSerializable {
|
||||
/** Linear "dx" component. */
|
||||
public double dx;
|
||||
|
||||
|
||||
@@ -10,7 +10,7 @@ import org.wpilib.math.proto.ProtobufEllipse2d;
|
||||
import org.wpilib.util.protobuf.Protobuf;
|
||||
import us.hebi.quickbuf.Descriptors.Descriptor;
|
||||
|
||||
public class Ellipse2dProto implements Protobuf<Ellipse2d, ProtobufEllipse2d> {
|
||||
public final class Ellipse2dProto implements Protobuf<Ellipse2d, ProtobufEllipse2d> {
|
||||
@Override
|
||||
public Class<Ellipse2d> getTypeClass() {
|
||||
return Ellipse2d.class;
|
||||
|
||||
@@ -11,7 +11,7 @@ import org.wpilib.math.proto.ProtobufPose2d;
|
||||
import org.wpilib.util.protobuf.Protobuf;
|
||||
import us.hebi.quickbuf.Descriptors.Descriptor;
|
||||
|
||||
public class Pose2dProto implements Protobuf<Pose2d, ProtobufPose2d> {
|
||||
public final class Pose2dProto implements Protobuf<Pose2d, ProtobufPose2d> {
|
||||
@Override
|
||||
public Class<Pose2d> getTypeClass() {
|
||||
return Pose2d.class;
|
||||
|
||||
@@ -11,7 +11,7 @@ import org.wpilib.math.proto.ProtobufPose3d;
|
||||
import org.wpilib.util.protobuf.Protobuf;
|
||||
import us.hebi.quickbuf.Descriptors.Descriptor;
|
||||
|
||||
public class Pose3dProto implements Protobuf<Pose3d, ProtobufPose3d> {
|
||||
public final class Pose3dProto implements Protobuf<Pose3d, ProtobufPose3d> {
|
||||
@Override
|
||||
public Class<Pose3d> getTypeClass() {
|
||||
return Pose3d.class;
|
||||
|
||||
@@ -9,7 +9,7 @@ import org.wpilib.math.proto.ProtobufQuaternion;
|
||||
import org.wpilib.util.protobuf.Protobuf;
|
||||
import us.hebi.quickbuf.Descriptors.Descriptor;
|
||||
|
||||
public class QuaternionProto implements Protobuf<Quaternion, ProtobufQuaternion> {
|
||||
public final class QuaternionProto implements Protobuf<Quaternion, ProtobufQuaternion> {
|
||||
@Override
|
||||
public Class<Quaternion> getTypeClass() {
|
||||
return Quaternion.class;
|
||||
|
||||
@@ -10,7 +10,7 @@ import org.wpilib.math.proto.ProtobufRectangle2d;
|
||||
import org.wpilib.util.protobuf.Protobuf;
|
||||
import us.hebi.quickbuf.Descriptors.Descriptor;
|
||||
|
||||
public class Rectangle2dProto implements Protobuf<Rectangle2d, ProtobufRectangle2d> {
|
||||
public final class Rectangle2dProto implements Protobuf<Rectangle2d, ProtobufRectangle2d> {
|
||||
@Override
|
||||
public Class<Rectangle2d> getTypeClass() {
|
||||
return Rectangle2d.class;
|
||||
|
||||
@@ -9,7 +9,7 @@ import org.wpilib.math.proto.ProtobufRotation2d;
|
||||
import org.wpilib.util.protobuf.Protobuf;
|
||||
import us.hebi.quickbuf.Descriptors.Descriptor;
|
||||
|
||||
public class Rotation2dProto implements Protobuf<Rotation2d, ProtobufRotation2d> {
|
||||
public final class Rotation2dProto implements Protobuf<Rotation2d, ProtobufRotation2d> {
|
||||
@Override
|
||||
public Class<Rotation2d> getTypeClass() {
|
||||
return Rotation2d.class;
|
||||
|
||||
@@ -10,7 +10,7 @@ import org.wpilib.math.proto.ProtobufRotation3d;
|
||||
import org.wpilib.util.protobuf.Protobuf;
|
||||
import us.hebi.quickbuf.Descriptors.Descriptor;
|
||||
|
||||
public class Rotation3dProto implements Protobuf<Rotation3d, ProtobufRotation3d> {
|
||||
public final class Rotation3dProto implements Protobuf<Rotation3d, ProtobufRotation3d> {
|
||||
@Override
|
||||
public Class<Rotation3d> getTypeClass() {
|
||||
return Rotation3d.class;
|
||||
|
||||
@@ -11,7 +11,7 @@ import org.wpilib.math.proto.ProtobufTransform2d;
|
||||
import org.wpilib.util.protobuf.Protobuf;
|
||||
import us.hebi.quickbuf.Descriptors.Descriptor;
|
||||
|
||||
public class Transform2dProto implements Protobuf<Transform2d, ProtobufTransform2d> {
|
||||
public final class Transform2dProto implements Protobuf<Transform2d, ProtobufTransform2d> {
|
||||
@Override
|
||||
public Class<Transform2d> getTypeClass() {
|
||||
return Transform2d.class;
|
||||
|
||||
@@ -11,7 +11,7 @@ import org.wpilib.math.proto.ProtobufTransform3d;
|
||||
import org.wpilib.util.protobuf.Protobuf;
|
||||
import us.hebi.quickbuf.Descriptors.Descriptor;
|
||||
|
||||
public class Transform3dProto implements Protobuf<Transform3d, ProtobufTransform3d> {
|
||||
public final class Transform3dProto implements Protobuf<Transform3d, ProtobufTransform3d> {
|
||||
@Override
|
||||
public Class<Transform3d> getTypeClass() {
|
||||
return Transform3d.class;
|
||||
|
||||
@@ -9,7 +9,7 @@ import org.wpilib.math.proto.ProtobufTranslation2d;
|
||||
import org.wpilib.util.protobuf.Protobuf;
|
||||
import us.hebi.quickbuf.Descriptors.Descriptor;
|
||||
|
||||
public class Translation2dProto implements Protobuf<Translation2d, ProtobufTranslation2d> {
|
||||
public final class Translation2dProto implements Protobuf<Translation2d, ProtobufTranslation2d> {
|
||||
@Override
|
||||
public Class<Translation2d> getTypeClass() {
|
||||
return Translation2d.class;
|
||||
|
||||
@@ -9,7 +9,7 @@ import org.wpilib.math.proto.ProtobufTranslation3d;
|
||||
import org.wpilib.util.protobuf.Protobuf;
|
||||
import us.hebi.quickbuf.Descriptors.Descriptor;
|
||||
|
||||
public class Translation3dProto implements Protobuf<Translation3d, ProtobufTranslation3d> {
|
||||
public final class Translation3dProto implements Protobuf<Translation3d, ProtobufTranslation3d> {
|
||||
@Override
|
||||
public Class<Translation3d> getTypeClass() {
|
||||
return Translation3d.class;
|
||||
|
||||
@@ -9,7 +9,7 @@ import org.wpilib.math.proto.ProtobufTwist2d;
|
||||
import org.wpilib.util.protobuf.Protobuf;
|
||||
import us.hebi.quickbuf.Descriptors.Descriptor;
|
||||
|
||||
public class Twist2dProto implements Protobuf<Twist2d, ProtobufTwist2d> {
|
||||
public final class Twist2dProto implements Protobuf<Twist2d, ProtobufTwist2d> {
|
||||
@Override
|
||||
public Class<Twist2d> getTypeClass() {
|
||||
return Twist2d.class;
|
||||
|
||||
@@ -9,7 +9,7 @@ import org.wpilib.math.proto.ProtobufTwist3d;
|
||||
import org.wpilib.util.protobuf.Protobuf;
|
||||
import us.hebi.quickbuf.Descriptors.Descriptor;
|
||||
|
||||
public class Twist3dProto implements Protobuf<Twist3d, ProtobufTwist3d> {
|
||||
public final class Twist3dProto implements Protobuf<Twist3d, ProtobufTwist3d> {
|
||||
@Override
|
||||
public Class<Twist3d> getTypeClass() {
|
||||
return Twist3d.class;
|
||||
|
||||
@@ -9,7 +9,7 @@ import org.wpilib.math.geometry.Ellipse2d;
|
||||
import org.wpilib.math.geometry.Pose2d;
|
||||
import org.wpilib.util.struct.Struct;
|
||||
|
||||
public class Ellipse2dStruct implements Struct<Ellipse2d> {
|
||||
public final class Ellipse2dStruct implements Struct<Ellipse2d> {
|
||||
@Override
|
||||
public Class<Ellipse2d> getTypeClass() {
|
||||
return Ellipse2d.class;
|
||||
|
||||
@@ -10,7 +10,7 @@ import org.wpilib.math.geometry.Rotation2d;
|
||||
import org.wpilib.math.geometry.Translation2d;
|
||||
import org.wpilib.util.struct.Struct;
|
||||
|
||||
public class Pose2dStruct implements Struct<Pose2d> {
|
||||
public final class Pose2dStruct implements Struct<Pose2d> {
|
||||
@Override
|
||||
public Class<Pose2d> getTypeClass() {
|
||||
return Pose2d.class;
|
||||
|
||||
@@ -10,7 +10,7 @@ import org.wpilib.math.geometry.Rotation3d;
|
||||
import org.wpilib.math.geometry.Translation3d;
|
||||
import org.wpilib.util.struct.Struct;
|
||||
|
||||
public class Pose3dStruct implements Struct<Pose3d> {
|
||||
public final class Pose3dStruct implements Struct<Pose3d> {
|
||||
@Override
|
||||
public Class<Pose3d> getTypeClass() {
|
||||
return Pose3d.class;
|
||||
|
||||
@@ -8,7 +8,7 @@ import java.nio.ByteBuffer;
|
||||
import org.wpilib.math.geometry.Quaternion;
|
||||
import org.wpilib.util.struct.Struct;
|
||||
|
||||
public class QuaternionStruct implements Struct<Quaternion> {
|
||||
public final class QuaternionStruct implements Struct<Quaternion> {
|
||||
@Override
|
||||
public Class<Quaternion> getTypeClass() {
|
||||
return Quaternion.class;
|
||||
|
||||
@@ -9,7 +9,7 @@ import org.wpilib.math.geometry.Pose2d;
|
||||
import org.wpilib.math.geometry.Rectangle2d;
|
||||
import org.wpilib.util.struct.Struct;
|
||||
|
||||
public class Rectangle2dStruct implements Struct<Rectangle2d> {
|
||||
public final class Rectangle2dStruct implements Struct<Rectangle2d> {
|
||||
@Override
|
||||
public Class<Rectangle2d> getTypeClass() {
|
||||
return Rectangle2d.class;
|
||||
|
||||
@@ -8,7 +8,7 @@ import java.nio.ByteBuffer;
|
||||
import org.wpilib.math.geometry.Rotation2d;
|
||||
import org.wpilib.util.struct.Struct;
|
||||
|
||||
public class Rotation2dStruct implements Struct<Rotation2d> {
|
||||
public final class Rotation2dStruct implements Struct<Rotation2d> {
|
||||
@Override
|
||||
public Class<Rotation2d> getTypeClass() {
|
||||
return Rotation2d.class;
|
||||
|
||||
@@ -9,7 +9,7 @@ import org.wpilib.math.geometry.Quaternion;
|
||||
import org.wpilib.math.geometry.Rotation3d;
|
||||
import org.wpilib.util.struct.Struct;
|
||||
|
||||
public class Rotation3dStruct implements Struct<Rotation3d> {
|
||||
public final class Rotation3dStruct implements Struct<Rotation3d> {
|
||||
@Override
|
||||
public Class<Rotation3d> getTypeClass() {
|
||||
return Rotation3d.class;
|
||||
|
||||
@@ -10,7 +10,7 @@ import org.wpilib.math.geometry.Transform2d;
|
||||
import org.wpilib.math.geometry.Translation2d;
|
||||
import org.wpilib.util.struct.Struct;
|
||||
|
||||
public class Transform2dStruct implements Struct<Transform2d> {
|
||||
public final class Transform2dStruct implements Struct<Transform2d> {
|
||||
@Override
|
||||
public Class<Transform2d> getTypeClass() {
|
||||
return Transform2d.class;
|
||||
|
||||
@@ -10,7 +10,7 @@ import org.wpilib.math.geometry.Transform3d;
|
||||
import org.wpilib.math.geometry.Translation3d;
|
||||
import org.wpilib.util.struct.Struct;
|
||||
|
||||
public class Transform3dStruct implements Struct<Transform3d> {
|
||||
public final class Transform3dStruct implements Struct<Transform3d> {
|
||||
@Override
|
||||
public Class<Transform3d> getTypeClass() {
|
||||
return Transform3d.class;
|
||||
|
||||
@@ -8,7 +8,7 @@ import java.nio.ByteBuffer;
|
||||
import org.wpilib.math.geometry.Translation2d;
|
||||
import org.wpilib.util.struct.Struct;
|
||||
|
||||
public class Translation2dStruct implements Struct<Translation2d> {
|
||||
public final class Translation2dStruct implements Struct<Translation2d> {
|
||||
@Override
|
||||
public Class<Translation2d> getTypeClass() {
|
||||
return Translation2d.class;
|
||||
|
||||
@@ -8,7 +8,7 @@ import java.nio.ByteBuffer;
|
||||
import org.wpilib.math.geometry.Translation3d;
|
||||
import org.wpilib.util.struct.Struct;
|
||||
|
||||
public class Translation3dStruct implements Struct<Translation3d> {
|
||||
public final class Translation3dStruct implements Struct<Translation3d> {
|
||||
@Override
|
||||
public Class<Translation3d> getTypeClass() {
|
||||
return Translation3d.class;
|
||||
|
||||
@@ -8,7 +8,7 @@ import java.nio.ByteBuffer;
|
||||
import org.wpilib.math.geometry.Twist2d;
|
||||
import org.wpilib.util.struct.Struct;
|
||||
|
||||
public class Twist2dStruct implements Struct<Twist2d> {
|
||||
public final class Twist2dStruct implements Struct<Twist2d> {
|
||||
@Override
|
||||
public Class<Twist2d> getTypeClass() {
|
||||
return Twist2d.class;
|
||||
|
||||
@@ -8,7 +8,7 @@ import java.nio.ByteBuffer;
|
||||
import org.wpilib.math.geometry.Twist3d;
|
||||
import org.wpilib.util.struct.Struct;
|
||||
|
||||
public class Twist3dStruct implements Struct<Twist3d> {
|
||||
public final class Twist3dStruct implements Struct<Twist3d> {
|
||||
@Override
|
||||
public Class<Twist3d> getTypeClass() {
|
||||
return Twist3d.class;
|
||||
|
||||
@@ -15,7 +15,7 @@ namespace wpi::math {
|
||||
* A class representing a coordinate system axis within the NWU coordinate
|
||||
* system.
|
||||
*/
|
||||
class WPILIB_DLLEXPORT CoordinateAxis {
|
||||
class WPILIB_DLLEXPORT CoordinateAxis final {
|
||||
public:
|
||||
/**
|
||||
* Constructs a coordinate system axis within the NWU coordinate system and
|
||||
|
||||
@@ -19,7 +19,7 @@ namespace wpi::math {
|
||||
* A helper class that converts Pose3d objects between different standard
|
||||
* coordinate frames.
|
||||
*/
|
||||
class WPILIB_DLLEXPORT CoordinateSystem {
|
||||
class WPILIB_DLLEXPORT CoordinateSystem final {
|
||||
public:
|
||||
/**
|
||||
* Constructs a coordinate system with the given cardinal directions for each
|
||||
|
||||
@@ -23,7 +23,7 @@ namespace wpi::math {
|
||||
* Represents a 2d ellipse space containing translational, rotational, and
|
||||
* scaling components.
|
||||
*/
|
||||
class WPILIB_DLLEXPORT Ellipse2d {
|
||||
class WPILIB_DLLEXPORT Ellipse2d final {
|
||||
public:
|
||||
/**
|
||||
* Constructs an ellipse around a center point and two semi-axes, a horizontal
|
||||
|
||||
@@ -27,7 +27,7 @@ class Transform2d;
|
||||
/**
|
||||
* Represents a 2D pose containing translational and rotational elements.
|
||||
*/
|
||||
class WPILIB_DLLEXPORT Pose2d {
|
||||
class WPILIB_DLLEXPORT Pose2d final {
|
||||
public:
|
||||
/**
|
||||
* Constructs a pose at the origin facing toward the positive X axis.
|
||||
|
||||
@@ -28,7 +28,7 @@ class Transform3d;
|
||||
/**
|
||||
* Represents a 3D pose containing translational and rotational elements.
|
||||
*/
|
||||
class WPILIB_DLLEXPORT Pose3d {
|
||||
class WPILIB_DLLEXPORT Pose3d final {
|
||||
public:
|
||||
/**
|
||||
* Constructs a pose at the origin facing toward the positive X axis.
|
||||
|
||||
@@ -20,7 +20,7 @@ namespace wpi::math {
|
||||
/**
|
||||
* Represents a quaternion.
|
||||
*/
|
||||
class WPILIB_DLLEXPORT Quaternion {
|
||||
class WPILIB_DLLEXPORT Quaternion final {
|
||||
public:
|
||||
/**
|
||||
* Constructs a quaternion with a default angle of 0 degrees.
|
||||
|
||||
@@ -21,7 +21,7 @@ namespace wpi::math {
|
||||
* Represents a 2d rectangular space containing translational, rotational, and
|
||||
* scaling components.
|
||||
*/
|
||||
class WPILIB_DLLEXPORT Rectangle2d {
|
||||
class WPILIB_DLLEXPORT Rectangle2d final {
|
||||
public:
|
||||
/**
|
||||
* Constructs a rectangle at the specified position with the specified width
|
||||
|
||||
@@ -26,7 +26,7 @@ namespace wpi::math {
|
||||
* A rotation in a 2D coordinate frame represented by a point on the unit circle
|
||||
* (cosine and sine).
|
||||
*/
|
||||
class WPILIB_DLLEXPORT Rotation2d {
|
||||
class WPILIB_DLLEXPORT Rotation2d final {
|
||||
public:
|
||||
/**
|
||||
* Constructs a Rotation2d with a default angle of 0 degrees.
|
||||
|
||||
@@ -69,7 +69,7 @@ namespace wpi::math {
|
||||
* neat property is that applying a series of rotations extrinsically is the
|
||||
* same as applying the same series in the opposite order intrinsically.
|
||||
*/
|
||||
class WPILIB_DLLEXPORT Rotation3d {
|
||||
class WPILIB_DLLEXPORT Rotation3d final {
|
||||
public:
|
||||
/**
|
||||
* Constructs a Rotation3d representing no rotation.
|
||||
|
||||
@@ -18,7 +18,7 @@ struct Twist2d;
|
||||
/**
|
||||
* Represents a transformation for a Pose2d in the pose's frame.
|
||||
*/
|
||||
class WPILIB_DLLEXPORT Transform2d {
|
||||
class WPILIB_DLLEXPORT Transform2d final {
|
||||
public:
|
||||
/**
|
||||
* Constructs the transform that maps the initial pose to the final pose.
|
||||
|
||||
@@ -20,7 +20,7 @@ struct Twist3d;
|
||||
* applied before rotation. (The translation is applied in the pose's original
|
||||
* frame, not the transformed frame.)
|
||||
*/
|
||||
class WPILIB_DLLEXPORT Transform3d {
|
||||
class WPILIB_DLLEXPORT Transform3d final {
|
||||
public:
|
||||
/**
|
||||
* Constructs the transform that maps the initial pose to the final pose.
|
||||
|
||||
@@ -30,7 +30,7 @@ namespace wpi::math {
|
||||
* When the robot is at the origin facing in the positive X direction, forward
|
||||
* is positive X and left is positive Y.
|
||||
*/
|
||||
class WPILIB_DLLEXPORT Translation2d {
|
||||
class WPILIB_DLLEXPORT Translation2d final {
|
||||
public:
|
||||
/**
|
||||
* Constructs a Translation2d with X and Y components equal to zero.
|
||||
|
||||
@@ -31,7 +31,7 @@ namespace wpi::math {
|
||||
* robot is at the origin facing in the positive X direction, forward is
|
||||
* positive X, left is positive Y, and up is positive Z.
|
||||
*/
|
||||
class WPILIB_DLLEXPORT Translation3d {
|
||||
class WPILIB_DLLEXPORT Translation3d final {
|
||||
public:
|
||||
/**
|
||||
* Constructs a Translation3d with X, Y, and Z components equal to zero.
|
||||
|
||||
@@ -20,7 +20,7 @@ class Transform2d;
|
||||
*
|
||||
* A Twist can be used to represent a difference between two poses.
|
||||
*/
|
||||
struct WPILIB_DLLEXPORT Twist2d {
|
||||
struct WPILIB_DLLEXPORT Twist2d final {
|
||||
/**
|
||||
* Linear "dx" component
|
||||
*/
|
||||
|
||||
@@ -20,7 +20,7 @@ class Transform3d;
|
||||
*
|
||||
* A Twist can be used to represent a difference between two poses.
|
||||
*/
|
||||
struct WPILIB_DLLEXPORT Twist3d {
|
||||
struct WPILIB_DLLEXPORT Twist3d final {
|
||||
/**
|
||||
* Linear "dx" component
|
||||
*/
|
||||
|
||||
@@ -10,7 +10,7 @@
|
||||
#include "wpimath/protobuf/geometry2d.npb.h"
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::util::Protobuf<wpi::math::Ellipse2d> {
|
||||
struct WPILIB_DLLEXPORT wpi::util::Protobuf<wpi::math::Ellipse2d> final {
|
||||
using MessageStruct = wpi_proto_ProtobufEllipse2d;
|
||||
using InputStream = wpi::util::ProtoInputStream<wpi::math::Ellipse2d>;
|
||||
using OutputStream = wpi::util::ProtoOutputStream<wpi::math::Ellipse2d>;
|
||||
|
||||
@@ -11,7 +11,7 @@
|
||||
#include "wpimath/protobuf/geometry2d.npb.h"
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::util::Protobuf<wpi::math::Pose2d> {
|
||||
struct WPILIB_DLLEXPORT wpi::util::Protobuf<wpi::math::Pose2d> final {
|
||||
using MessageStruct = wpi_proto_ProtobufPose2d;
|
||||
using InputStream = wpi::util::ProtoInputStream<wpi::math::Pose2d>;
|
||||
using OutputStream = wpi::util::ProtoOutputStream<wpi::math::Pose2d>;
|
||||
|
||||
@@ -10,7 +10,7 @@
|
||||
#include "wpimath/protobuf/geometry3d.npb.h"
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::util::Protobuf<wpi::math::Pose3d> {
|
||||
struct WPILIB_DLLEXPORT wpi::util::Protobuf<wpi::math::Pose3d> final {
|
||||
using MessageStruct = wpi_proto_ProtobufPose3d;
|
||||
using InputStream = wpi::util::ProtoInputStream<wpi::math::Pose3d>;
|
||||
using OutputStream = wpi::util::ProtoOutputStream<wpi::math::Pose3d>;
|
||||
|
||||
@@ -10,7 +10,7 @@
|
||||
#include "wpimath/protobuf/geometry3d.npb.h"
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::util::Protobuf<wpi::math::Quaternion> {
|
||||
struct WPILIB_DLLEXPORT wpi::util::Protobuf<wpi::math::Quaternion> final {
|
||||
using MessageStruct = wpi_proto_ProtobufQuaternion;
|
||||
using InputStream = wpi::util::ProtoInputStream<wpi::math::Quaternion>;
|
||||
using OutputStream = wpi::util::ProtoOutputStream<wpi::math::Quaternion>;
|
||||
|
||||
@@ -10,7 +10,7 @@
|
||||
#include "wpimath/protobuf/geometry2d.npb.h"
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::util::Protobuf<wpi::math::Rectangle2d> {
|
||||
struct WPILIB_DLLEXPORT wpi::util::Protobuf<wpi::math::Rectangle2d> final {
|
||||
using MessageStruct = wpi_proto_ProtobufRectangle2d;
|
||||
using InputStream = wpi::util::ProtoInputStream<wpi::math::Rectangle2d>;
|
||||
using OutputStream = wpi::util::ProtoOutputStream<wpi::math::Rectangle2d>;
|
||||
|
||||
@@ -11,7 +11,7 @@
|
||||
#include "wpimath/protobuf/geometry2d.npb.h"
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::util::Protobuf<wpi::math::Rotation2d> {
|
||||
struct WPILIB_DLLEXPORT wpi::util::Protobuf<wpi::math::Rotation2d> final {
|
||||
using MessageStruct = wpi_proto_ProtobufRotation2d;
|
||||
using InputStream = wpi::util::ProtoInputStream<wpi::math::Rotation2d>;
|
||||
using OutputStream = wpi::util::ProtoOutputStream<wpi::math::Rotation2d>;
|
||||
|
||||
@@ -10,7 +10,7 @@
|
||||
#include "wpimath/protobuf/geometry3d.npb.h"
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::util::Protobuf<wpi::math::Rotation3d> {
|
||||
struct WPILIB_DLLEXPORT wpi::util::Protobuf<wpi::math::Rotation3d> final {
|
||||
using MessageStruct = wpi_proto_ProtobufRotation3d;
|
||||
using InputStream = wpi::util::ProtoInputStream<wpi::math::Rotation3d>;
|
||||
using OutputStream = wpi::util::ProtoOutputStream<wpi::math::Rotation3d>;
|
||||
|
||||
@@ -10,7 +10,7 @@
|
||||
#include "wpimath/protobuf/geometry2d.npb.h"
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::util::Protobuf<wpi::math::Transform2d> {
|
||||
struct WPILIB_DLLEXPORT wpi::util::Protobuf<wpi::math::Transform2d> final {
|
||||
using MessageStruct = wpi_proto_ProtobufTransform2d;
|
||||
using InputStream = wpi::util::ProtoInputStream<wpi::math::Transform2d>;
|
||||
using OutputStream = wpi::util::ProtoOutputStream<wpi::math::Transform2d>;
|
||||
|
||||
@@ -10,7 +10,7 @@
|
||||
#include "wpimath/protobuf/geometry3d.npb.h"
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::util::Protobuf<wpi::math::Transform3d> {
|
||||
struct WPILIB_DLLEXPORT wpi::util::Protobuf<wpi::math::Transform3d> final {
|
||||
using MessageStruct = wpi_proto_ProtobufTransform3d;
|
||||
using InputStream = wpi::util::ProtoInputStream<wpi::math::Transform3d>;
|
||||
using OutputStream = wpi::util::ProtoOutputStream<wpi::math::Transform3d>;
|
||||
|
||||
@@ -11,7 +11,7 @@
|
||||
#include "wpimath/protobuf/geometry2d.npb.h"
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::util::Protobuf<wpi::math::Translation2d> {
|
||||
struct WPILIB_DLLEXPORT wpi::util::Protobuf<wpi::math::Translation2d> final {
|
||||
using MessageStruct = wpi_proto_ProtobufTranslation2d;
|
||||
using InputStream = wpi::util::ProtoInputStream<wpi::math::Translation2d>;
|
||||
using OutputStream = wpi::util::ProtoOutputStream<wpi::math::Translation2d>;
|
||||
|
||||
@@ -10,7 +10,7 @@
|
||||
#include "wpimath/protobuf/geometry3d.npb.h"
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::util::Protobuf<wpi::math::Translation3d> {
|
||||
struct WPILIB_DLLEXPORT wpi::util::Protobuf<wpi::math::Translation3d> final {
|
||||
using MessageStruct = wpi_proto_ProtobufTranslation3d;
|
||||
using InputStream = wpi::util::ProtoInputStream<wpi::math::Translation3d>;
|
||||
using OutputStream = wpi::util::ProtoOutputStream<wpi::math::Translation3d>;
|
||||
|
||||
@@ -10,7 +10,7 @@
|
||||
#include "wpimath/protobuf/geometry2d.npb.h"
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::util::Protobuf<wpi::math::Twist2d> {
|
||||
struct WPILIB_DLLEXPORT wpi::util::Protobuf<wpi::math::Twist2d> final {
|
||||
using MessageStruct = wpi_proto_ProtobufTwist2d;
|
||||
using InputStream = wpi::util::ProtoInputStream<wpi::math::Twist2d>;
|
||||
using OutputStream = wpi::util::ProtoOutputStream<wpi::math::Twist2d>;
|
||||
|
||||
@@ -10,7 +10,7 @@
|
||||
#include "wpimath/protobuf/geometry3d.npb.h"
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::util::Protobuf<wpi::math::Twist3d> {
|
||||
struct WPILIB_DLLEXPORT wpi::util::Protobuf<wpi::math::Twist3d> final {
|
||||
using MessageStruct = wpi_proto_ProtobufTwist3d;
|
||||
using InputStream = wpi::util::ProtoInputStream<wpi::math::Twist3d>;
|
||||
using OutputStream = wpi::util::ProtoOutputStream<wpi::math::Twist3d>;
|
||||
|
||||
@@ -9,7 +9,7 @@
|
||||
#include "wpi/util/struct/Struct.hpp"
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::util::Struct<wpi::math::Ellipse2d> {
|
||||
struct WPILIB_DLLEXPORT wpi::util::Struct<wpi::math::Ellipse2d> final {
|
||||
static constexpr std::string_view GetTypeName() { return "Ellipse2d"; }
|
||||
static constexpr size_t GetSize() {
|
||||
return wpi::util::GetStructSize<wpi::math::Pose2d>() + 16;
|
||||
|
||||
@@ -9,7 +9,7 @@
|
||||
#include "wpi/util/struct/Struct.hpp"
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::util::Struct<wpi::math::Pose2d> {
|
||||
struct WPILIB_DLLEXPORT wpi::util::Struct<wpi::math::Pose2d> final {
|
||||
static constexpr std::string_view GetTypeName() { return "Pose2d"; }
|
||||
static constexpr size_t GetSize() {
|
||||
return wpi::util::GetStructSize<wpi::math::Translation2d>() +
|
||||
|
||||
@@ -9,7 +9,7 @@
|
||||
#include "wpi/util/struct/Struct.hpp"
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::util::Struct<wpi::math::Pose3d> {
|
||||
struct WPILIB_DLLEXPORT wpi::util::Struct<wpi::math::Pose3d> final {
|
||||
static constexpr std::string_view GetTypeName() { return "Pose3d"; }
|
||||
static constexpr size_t GetSize() {
|
||||
return wpi::util::GetStructSize<wpi::math::Translation3d>() +
|
||||
|
||||
@@ -9,7 +9,7 @@
|
||||
#include "wpi/util/struct/Struct.hpp"
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::util::Struct<wpi::math::Quaternion> {
|
||||
struct WPILIB_DLLEXPORT wpi::util::Struct<wpi::math::Quaternion> final {
|
||||
static constexpr std::string_view GetTypeName() { return "Quaternion"; }
|
||||
static constexpr size_t GetSize() { return 32; }
|
||||
static constexpr std::string_view GetSchema() {
|
||||
|
||||
@@ -9,7 +9,7 @@
|
||||
#include "wpi/util/struct/Struct.hpp"
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::util::Struct<wpi::math::Rectangle2d> {
|
||||
struct WPILIB_DLLEXPORT wpi::util::Struct<wpi::math::Rectangle2d> final {
|
||||
static constexpr std::string_view GetTypeName() { return "Rectangle2d"; }
|
||||
static constexpr size_t GetSize() {
|
||||
return wpi::util::GetStructSize<wpi::math::Pose2d>() + 16;
|
||||
|
||||
@@ -9,7 +9,7 @@
|
||||
#include "wpi/util/struct/Struct.hpp"
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::util::Struct<wpi::math::Rotation2d> {
|
||||
struct WPILIB_DLLEXPORT wpi::util::Struct<wpi::math::Rotation2d> final {
|
||||
static constexpr std::string_view GetTypeName() { return "Rotation2d"; }
|
||||
static constexpr size_t GetSize() { return 8; }
|
||||
static constexpr std::string_view GetSchema() { return "double value"; }
|
||||
|
||||
@@ -9,7 +9,7 @@
|
||||
#include "wpi/util/struct/Struct.hpp"
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::util::Struct<wpi::math::Rotation3d> {
|
||||
struct WPILIB_DLLEXPORT wpi::util::Struct<wpi::math::Rotation3d> final {
|
||||
static constexpr std::string_view GetTypeName() { return "Rotation3d"; }
|
||||
static constexpr size_t GetSize() {
|
||||
return wpi::util::GetStructSize<wpi::math::Quaternion>();
|
||||
|
||||
@@ -9,7 +9,7 @@
|
||||
#include "wpi/util/struct/Struct.hpp"
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::util::Struct<wpi::math::Transform2d> {
|
||||
struct WPILIB_DLLEXPORT wpi::util::Struct<wpi::math::Transform2d> final {
|
||||
static constexpr std::string_view GetTypeName() { return "Transform2d"; }
|
||||
static constexpr size_t GetSize() {
|
||||
return wpi::util::GetStructSize<wpi::math::Translation2d>() +
|
||||
|
||||
@@ -9,7 +9,7 @@
|
||||
#include "wpi/util/struct/Struct.hpp"
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::util::Struct<wpi::math::Transform3d> {
|
||||
struct WPILIB_DLLEXPORT wpi::util::Struct<wpi::math::Transform3d> final {
|
||||
static constexpr std::string_view GetTypeName() { return "Transform3d"; }
|
||||
static constexpr size_t GetSize() {
|
||||
return wpi::util::GetStructSize<wpi::math::Translation3d>() +
|
||||
|
||||
@@ -9,7 +9,7 @@
|
||||
#include "wpi/util/struct/Struct.hpp"
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::util::Struct<wpi::math::Translation2d> {
|
||||
struct WPILIB_DLLEXPORT wpi::util::Struct<wpi::math::Translation2d> final {
|
||||
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"; }
|
||||
|
||||
@@ -9,7 +9,7 @@
|
||||
#include "wpi/util/struct/Struct.hpp"
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::util::Struct<wpi::math::Translation3d> {
|
||||
struct WPILIB_DLLEXPORT wpi::util::Struct<wpi::math::Translation3d> final {
|
||||
static constexpr std::string_view GetTypeName() { return "Translation3d"; }
|
||||
static constexpr size_t GetSize() { return 24; }
|
||||
static constexpr std::string_view GetSchema() {
|
||||
|
||||
@@ -9,7 +9,7 @@
|
||||
#include "wpi/util/struct/Struct.hpp"
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::util::Struct<wpi::math::Twist2d> {
|
||||
struct WPILIB_DLLEXPORT wpi::util::Struct<wpi::math::Twist2d> final {
|
||||
static constexpr std::string_view GetTypeName() { return "Twist2d"; }
|
||||
static constexpr size_t GetSize() { return 24; }
|
||||
static constexpr std::string_view GetSchema() {
|
||||
|
||||
@@ -9,7 +9,7 @@
|
||||
#include "wpi/util/struct/Struct.hpp"
|
||||
|
||||
template <>
|
||||
struct WPILIB_DLLEXPORT wpi::util::Struct<wpi::math::Twist3d> {
|
||||
struct WPILIB_DLLEXPORT wpi::util::Struct<wpi::math::Twist3d> final {
|
||||
static constexpr std::string_view GetTypeName() { return "Twist3d"; }
|
||||
static constexpr size_t GetSize() { return 48; }
|
||||
static constexpr std::string_view GetSchema() {
|
||||
|
||||
Reference in New Issue
Block a user