diff --git a/wpimath/src/generated/main/java/edu/wpi/first/math/proto/Controller.java b/wpimath/src/generated/main/java/edu/wpi/first/math/proto/Controller.java index ed423da5831..1498b67a62a 100644 --- a/wpimath/src/generated/main/java/edu/wpi/first/math/proto/Controller.java +++ b/wpimath/src/generated/main/java/edu/wpi/first/math/proto/Controller.java @@ -18,36 +18,37 @@ import us.hebi.quickbuf.RepeatedByte; public final class Controller { - private static final RepeatedByte descriptorData = ProtoUtil.decodeBase64(1684, + private static final RepeatedByte descriptorData = ProtoUtil.decodeBase64(1755, "ChBjb250cm9sbGVyLnByb3RvEgl3cGkucHJvdG8iWAoWUHJvdG9idWZBcm1GZWVkZm9yd2FyZBIOCgJr" + "cxgBIAEoAVICa3MSDgoCa2cYAiABKAFSAmtnEg4KAmt2GAMgASgBUgJrdhIOCgJrYRgEIAEoAVICa2Ei" + "ngEKJFByb3RvYnVmRGlmZmVyZW50aWFsRHJpdmVGZWVkZm9yd2FyZBIbCglrdl9saW5lYXIYASABKAFS" + "CGt2TGluZWFyEhsKCWthX2xpbmVhchgCIAEoAVIIa2FMaW5lYXISHQoKa3ZfYW5ndWxhchgDIAEoAVIJ" + "a3ZBbmd1bGFyEh0KCmthX2FuZ3VsYXIYBCABKAFSCWthQW5ndWxhciJdChtQcm90b2J1ZkVsZXZhdG9y" + "RmVlZGZvcndhcmQSDgoCa3MYASABKAFSAmtzEg4KAmtnGAIgASgBUgJrZxIOCgJrdhgDIAEoAVICa3YS" + - "DgoCa2EYBCABKAFSAmthIlAKHlByb3RvYnVmU2ltcGxlTW90b3JGZWVkZm9yd2FyZBIOCgJrcxgBIAEo" + - "AVICa3MSDgoCa3YYAiABKAFSAmt2Eg4KAmthGAMgASgBUgJrYSJSCiZQcm90b2J1ZkRpZmZlcmVudGlh" + - "bERyaXZlV2hlZWxWb2x0YWdlcxISCgRsZWZ0GAEgASgBUgRsZWZ0EhQKBXJpZ2h0GAIgASgBUgVyaWdo" + - "dEIaChhlZHUud3BpLmZpcnN0Lm1hdGgucHJvdG9K0AgKBhIEAAAkAQoICgEMEgMAABIKCAoBAhIDAgAS" + - "CggKAQgSAwQAMQoJCgIIARIDBAAxCgoKAgQAEgQGAAsBCgoKAwQAARIDBggeCgsKBAQAAgASAwcCEAoM" + - "CgUEAAIABRIDBwIICgwKBQQAAgABEgMHCQsKDAoFBAACAAMSAwcODwoLCgQEAAIBEgMIAhAKDAoFBAAC" + - "AQUSAwgCCAoMCgUEAAIBARIDCAkLCgwKBQQAAgEDEgMIDg8KCwoEBAACAhIDCQIQCgwKBQQAAgIFEgMJ" + - "AggKDAoFBAACAgESAwkJCwoMCgUEAAICAxIDCQ4PCgsKBAQAAgMSAwoCEAoMCgUEAAIDBRIDCgIICgwK" + - "BQQAAgMBEgMKCQsKDAoFBAACAwMSAwoODwoKCgIEARIEDQASAQoKCgMEAQESAw0ILAoLCgQEAQIAEgMO" + - "AhcKDAoFBAECAAUSAw4CCAoMCgUEAQIAARIDDgkSCgwKBQQBAgADEgMOFRYKCwoEBAECARIDDwIXCgwK" + - "BQQBAgEFEgMPAggKDAoFBAECAQESAw8JEgoMCgUEAQIBAxIDDxUWCgsKBAQBAgISAxACGAoMCgUEAQIC" + - "BRIDEAIICgwKBQQBAgIBEgMQCRMKDAoFBAECAgMSAxAWFwoLCgQEAQIDEgMRAhgKDAoFBAECAwUSAxEC" + - "CAoMCgUEAQIDARIDEQkTCgwKBQQBAgMDEgMRFhcKCgoCBAISBBQAGQEKCgoDBAIBEgMUCCMKCwoEBAIC" + - "ABIDFQIQCgwKBQQCAgAFEgMVAggKDAoFBAICAAESAxUJCwoMCgUEAgIAAxIDFQ4PCgsKBAQCAgESAxYC", - "EAoMCgUEAgIBBRIDFgIICgwKBQQCAgEBEgMWCQsKDAoFBAICAQMSAxYODwoLCgQEAgICEgMXAhAKDAoF" + - "BAICAgUSAxcCCAoMCgUEAgICARIDFwkLCgwKBQQCAgIDEgMXDg8KCwoEBAICAxIDGAIQCgwKBQQCAgMF" + - "EgMYAggKDAoFBAICAwESAxgJCwoMCgUEAgIDAxIDGA4PCgoKAgQDEgQbAB8BCgoKAwQDARIDGwgmCgsK" + - "BAQDAgASAxwCEAoMCgUEAwIABRIDHAIICgwKBQQDAgABEgMcCQsKDAoFBAMCAAMSAxwODwoLCgQEAwIB" + - "EgMdAhAKDAoFBAMCAQUSAx0CCAoMCgUEAwIBARIDHQkLCgwKBQQDAgEDEgMdDg8KCwoEBAMCAhIDHgIQ" + - "CgwKBQQDAgIFEgMeAggKDAoFBAMCAgESAx4JCwoMCgUEAwICAxIDHg4PCgoKAgQEEgQhACQBCgoKAwQE" + - "ARIDIQguCgsKBAQEAgASAyICEgoMCgUEBAIABRIDIgIICgwKBQQEAgABEgMiCQ0KDAoFBAQCAAMSAyIQ" + - "EQoLCgQEBAIBEgMjAhMKDAoFBAQCAQUSAyMCCAoMCgUEBAIBARIDIwkOCgwKBQQEAgEDEgMjERJiBnBy" + - "b3RvMw=="); + "DgoCa2EYBCABKAFSAmthImAKHlByb3RvYnVmU2ltcGxlTW90b3JGZWVkZm9yd2FyZBIOCgJrcxgBIAEo" + + "AVICa3MSDgoCa3YYAiABKAFSAmt2Eg4KAmthGAMgASgBUgJrYRIOCgJkdBgEIAEoAVICZHQiUgomUHJv" + + "dG9idWZEaWZmZXJlbnRpYWxEcml2ZVdoZWVsVm9sdGFnZXMSEgoEbGVmdBgBIAEoAVIEbGVmdBIUCgVy" + + "aWdodBgCIAEoAVIFcmlnaHRCGgoYZWR1LndwaS5maXJzdC5tYXRoLnByb3RvSocJCgYSBAAAJQEKCAoB" + + "DBIDAAASCggKAQISAwIAEgoICgEIEgMEADEKCQoCCAESAwQAMQoKCgIEABIEBgALAQoKCgMEAAESAwYI" + + "HgoLCgQEAAIAEgMHAhAKDAoFBAACAAUSAwcCCAoMCgUEAAIAARIDBwkLCgwKBQQAAgADEgMHDg8KCwoE" + + "BAACARIDCAIQCgwKBQQAAgEFEgMIAggKDAoFBAACAQESAwgJCwoMCgUEAAIBAxIDCA4PCgsKBAQAAgIS" + + "AwkCEAoMCgUEAAICBRIDCQIICgwKBQQAAgIBEgMJCQsKDAoFBAACAgMSAwkODwoLCgQEAAIDEgMKAhAK" + + "DAoFBAACAwUSAwoCCAoMCgUEAAIDARIDCgkLCgwKBQQAAgMDEgMKDg8KCgoCBAESBA0AEgEKCgoDBAEB" + + "EgMNCCwKCwoEBAECABIDDgIXCgwKBQQBAgAFEgMOAggKDAoFBAECAAESAw4JEgoMCgUEAQIAAxIDDhUW" + + "CgsKBAQBAgESAw8CFwoMCgUEAQIBBRIDDwIICgwKBQQBAgEBEgMPCRIKDAoFBAECAQMSAw8VFgoLCgQE" + + "AQICEgMQAhgKDAoFBAECAgUSAxACCAoMCgUEAQICARIDEAkTCgwKBQQBAgIDEgMQFhcKCwoEBAECAxID" + + "EQIYCgwKBQQBAgMFEgMRAggKDAoFBAECAwESAxEJEwoMCgUEAQIDAxIDERYXCgoKAgQCEgQUABkBCgoK" + + "AwQCARIDFAgjCgsKBAQCAgASAxUCEAoMCgUEAgIABRIDFQIICgwKBQQCAgABEgMVCQsKDAoFBAICAAMS", + "AxUODwoLCgQEAgIBEgMWAhAKDAoFBAICAQUSAxYCCAoMCgUEAgIBARIDFgkLCgwKBQQCAgEDEgMWDg8K" + + "CwoEBAICAhIDFwIQCgwKBQQCAgIFEgMXAggKDAoFBAICAgESAxcJCwoMCgUEAgICAxIDFw4PCgsKBAQC" + + "AgMSAxgCEAoMCgUEAgIDBRIDGAIICgwKBQQCAgMBEgMYCQsKDAoFBAICAwMSAxgODwoKCgIEAxIEGwAg" + + "AQoKCgMEAwESAxsIJgoLCgQEAwIAEgMcAhAKDAoFBAMCAAUSAxwCCAoMCgUEAwIAARIDHAkLCgwKBQQD" + + "AgADEgMcDg8KCwoEBAMCARIDHQIQCgwKBQQDAgEFEgMdAggKDAoFBAMCAQESAx0JCwoMCgUEAwIBAxID" + + "HQ4PCgsKBAQDAgISAx4CEAoMCgUEAwICBRIDHgIICgwKBQQDAgIBEgMeCQsKDAoFBAMCAgMSAx4ODwoL" + + "CgQEAwIDEgMfAhAKDAoFBAMCAwUSAx8CCAoMCgUEAwIDARIDHwkLCgwKBQQDAgMDEgMfDg8KCgoCBAQS" + + "BCIAJQEKCgoDBAQBEgMiCC4KCwoEBAQCABIDIwISCgwKBQQEAgAFEgMjAggKDAoFBAQCAAESAyMJDQoM" + + "CgUEBAIAAxIDIxARCgsKBAQEAgESAyQCEwoMCgUEBAIBBRIDJAIICgwKBQQEAgEBEgMkCQ4KDAoFBAQC" + + "AQMSAyQREmIGcHJvdG8z"); static final Descriptors.FileDescriptor descriptor = Descriptors.FileDescriptor.internalBuildGeneratedFileFrom("controller.proto", "wpi.proto", descriptorData); @@ -57,9 +58,9 @@ public final class Controller { static final Descriptors.Descriptor wpi_proto_ProtobufElevatorFeedforward_descriptor = descriptor.internalContainedType(282, 93, "ProtobufElevatorFeedforward", "wpi.proto.ProtobufElevatorFeedforward"); - static final Descriptors.Descriptor wpi_proto_ProtobufSimpleMotorFeedforward_descriptor = descriptor.internalContainedType(377, 80, "ProtobufSimpleMotorFeedforward", "wpi.proto.ProtobufSimpleMotorFeedforward"); + static final Descriptors.Descriptor wpi_proto_ProtobufSimpleMotorFeedforward_descriptor = descriptor.internalContainedType(377, 96, "ProtobufSimpleMotorFeedforward", "wpi.proto.ProtobufSimpleMotorFeedforward"); - static final Descriptors.Descriptor wpi_proto_ProtobufDifferentialDriveWheelVoltages_descriptor = descriptor.internalContainedType(459, 82, "ProtobufDifferentialDriveWheelVoltages", "wpi.proto.ProtobufDifferentialDriveWheelVoltages"); + static final Descriptors.Descriptor wpi_proto_ProtobufDifferentialDriveWheelVoltages_descriptor = descriptor.internalContainedType(475, 82, "ProtobufDifferentialDriveWheelVoltages", "wpi.proto.ProtobufDifferentialDriveWheelVoltages"); /** * @return this proto file's descriptor. @@ -1576,6 +1577,11 @@ public static final class ProtobufSimpleMotorFeedforward extends ProtoMessageoptional double dt = 4; + */ + private double dt; + private ProtobufSimpleMotorFeedforward() { } @@ -1697,6 +1703,43 @@ public ProtobufSimpleMotorFeedforward setKa(final double value) { return this; } + /** + * optional double dt = 4; + * @return whether the dt field is set + */ + public boolean hasDt() { + return (bitField0_ & 0x00000008) != 0; + } + + /** + * optional double dt = 4; + * @return this + */ + public ProtobufSimpleMotorFeedforward clearDt() { + bitField0_ &= ~0x00000008; + dt = 0D; + return this; + } + + /** + * optional double dt = 4; + * @return the dt + */ + public double getDt() { + return dt; + } + + /** + * optional double dt = 4; + * @param value the dt to set + * @return this + */ + public ProtobufSimpleMotorFeedforward setDt(final double value) { + bitField0_ |= 0x00000008; + dt = value; + return this; + } + @Override public ProtobufSimpleMotorFeedforward copyFrom(final ProtobufSimpleMotorFeedforward other) { cachedSize = other.cachedSize; @@ -1705,6 +1748,7 @@ public ProtobufSimpleMotorFeedforward copyFrom(final ProtobufSimpleMotorFeedforw ks = other.ks; kv = other.kv; ka = other.ka; + dt = other.dt; } return this; } @@ -1724,6 +1768,9 @@ public ProtobufSimpleMotorFeedforward mergeFrom(final ProtobufSimpleMotorFeedfor if (other.hasKa()) { setKa(other.ka); } + if (other.hasDt()) { + setDt(other.dt); + } return this; } @@ -1737,6 +1784,7 @@ public ProtobufSimpleMotorFeedforward clear() { ks = 0D; kv = 0D; ka = 0D; + dt = 0D; return this; } @@ -1762,7 +1810,8 @@ public boolean equals(Object o) { return bitField0_ == other.bitField0_ && (!hasKs() || ProtoUtil.isEqual(ks, other.ks)) && (!hasKv() || ProtoUtil.isEqual(kv, other.kv)) - && (!hasKa() || ProtoUtil.isEqual(ka, other.ka)); + && (!hasKa() || ProtoUtil.isEqual(ka, other.ka)) + && (!hasDt() || ProtoUtil.isEqual(dt, other.dt)); } @Override @@ -1779,6 +1828,10 @@ public void writeTo(final ProtoSink output) throws IOException { output.writeRawByte((byte) 25); output.writeDoubleNoTag(ka); } + if ((bitField0_ & 0x00000008) != 0) { + output.writeRawByte((byte) 33); + output.writeDoubleNoTag(dt); + } } @Override @@ -1793,6 +1846,9 @@ protected int computeSerializedSize() { if ((bitField0_ & 0x00000004) != 0) { size += 9; } + if ((bitField0_ & 0x00000008) != 0) { + size += 9; + } return size; } @@ -1826,6 +1882,15 @@ public ProtobufSimpleMotorFeedforward mergeFrom(final ProtoSource input) throws ka = input.readDouble(); bitField0_ |= 0x00000004; tag = input.readTag(); + if (tag != 33) { + break; + } + } + case 33: { + // dt + dt = input.readDouble(); + bitField0_ |= 0x00000008; + tag = input.readTag(); if (tag != 0) { break; } @@ -1856,6 +1921,9 @@ public void writeTo(final JsonSink output) throws IOException { if ((bitField0_ & 0x00000004) != 0) { output.writeDouble(FieldNames.ka, ka); } + if ((bitField0_ & 0x00000008) != 0) { + output.writeDouble(FieldNames.dt, dt); + } output.endObject(); } @@ -1899,6 +1967,17 @@ public ProtobufSimpleMotorFeedforward mergeFrom(final JsonSource input) throws I } break; } + case 3216: { + if (input.isAtField(FieldNames.dt)) { + if (!input.trySkipNullValue()) { + dt = input.readDouble(); + bitField0_ |= 0x00000008; + } + } else { + input.skipUnknownField(); + } + break; + } default: { input.skipUnknownField(); break; @@ -1966,6 +2045,8 @@ static class FieldNames { static final FieldName kv = FieldName.forField("kv"); static final FieldName ka = FieldName.forField("ka"); + + static final FieldName dt = FieldName.forField("dt"); } } diff --git a/wpimath/src/main/java/edu/wpi/first/math/controller/proto/SimpleMotorFeedforwardProto.java b/wpimath/src/main/java/edu/wpi/first/math/controller/proto/SimpleMotorFeedforwardProto.java index f8f436c7986..cdd8c137e00 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/controller/proto/SimpleMotorFeedforwardProto.java +++ b/wpimath/src/main/java/edu/wpi/first/math/controller/proto/SimpleMotorFeedforwardProto.java @@ -28,11 +28,11 @@ public ProtobufSimpleMotorFeedforward createMessage() { @Override public SimpleMotorFeedforward unpack(ProtobufSimpleMotorFeedforward msg) { - return new SimpleMotorFeedforward(msg.getKs(), msg.getKv(), msg.getKa()); + return new SimpleMotorFeedforward(msg.getKs(), msg.getKv(), msg.getKa(), msg.getDt()); } @Override public void pack(ProtobufSimpleMotorFeedforward msg, SimpleMotorFeedforward value) { - msg.setKs(value.getKs()).setKv(value.getKv()).setKa(value.getKa()); + msg.setKs(value.getKs()).setKv(value.getKv()).setKa(value.getKa()).setDt(value.getDt()); } } diff --git a/wpimath/src/main/java/edu/wpi/first/math/controller/struct/SimpleMotorFeedforwardStruct.java b/wpimath/src/main/java/edu/wpi/first/math/controller/struct/SimpleMotorFeedforwardStruct.java index b323190e927..1cb88d8cca1 100644 --- a/wpimath/src/main/java/edu/wpi/first/math/controller/struct/SimpleMotorFeedforwardStruct.java +++ b/wpimath/src/main/java/edu/wpi/first/math/controller/struct/SimpleMotorFeedforwardStruct.java @@ -21,12 +21,12 @@ public String getTypeString() { @Override public int getSize() { - return kSizeDouble * 3; + return kSizeDouble * 4; } @Override public String getSchema() { - return "double ks;double kv;double ka"; + return "double ks;double kv;double ka;double dt"; } @Override @@ -34,7 +34,8 @@ public SimpleMotorFeedforward unpack(ByteBuffer bb) { double ks = bb.getDouble(); double kv = bb.getDouble(); double ka = bb.getDouble(); - return new SimpleMotorFeedforward(ks, kv, ka); + double dt = bb.getDouble(); + return new SimpleMotorFeedforward(ks, kv, ka, dt); } @Override @@ -42,5 +43,6 @@ public void pack(ByteBuffer bb, SimpleMotorFeedforward value) { bb.putDouble(value.getKs()); bb.putDouble(value.getKv()); bb.putDouble(value.getKa()); + bb.putDouble(value.getDt()); } } diff --git a/wpimath/src/main/native/include/frc/controller/proto/SimpleMotorFeedforwardProto.inc b/wpimath/src/main/native/include/frc/controller/proto/SimpleMotorFeedforwardProto.inc index d68fd5e66cc..8cda505a3db 100644 --- a/wpimath/src/main/native/include/frc/controller/proto/SimpleMotorFeedforwardProto.inc +++ b/wpimath/src/main/native/include/frc/controller/proto/SimpleMotorFeedforwardProto.inc @@ -25,7 +25,8 @@ wpi::Protobuf>::Unpack( units::unit_t::kv_unit>{ m->kv()}, units::unit_t::ka_unit>{ - m->ka()}}; + m->ka()}, + units::second_t{m->dt()}}; } template @@ -40,4 +41,5 @@ void wpi::Protobuf>::Pack( m->set_ka(units::unit_t::ka_unit>{ value.GetKa()} .value()); + m->set_dt(units::second_t{value.GetDt()}.value()); } diff --git a/wpimath/src/main/native/include/frc/controller/struct/SimpleMotorFeedforwardStruct.h b/wpimath/src/main/native/include/frc/controller/struct/SimpleMotorFeedforwardStruct.h index ee8f4c43b4a..d06f8cbfabd 100644 --- a/wpimath/src/main/native/include/frc/controller/struct/SimpleMotorFeedforwardStruct.h +++ b/wpimath/src/main/native/include/frc/controller/struct/SimpleMotorFeedforwardStruct.h @@ -17,9 +17,9 @@ struct wpi::Struct> { static constexpr std::string_view GetTypeString() { return "struct:SimpleMotorFeedforward"; } - static constexpr size_t GetSize() { return 24; } + static constexpr size_t GetSize() { return 32; } static constexpr std::string_view GetSchema() { - return "double ks;double kv;double ka"; + return "double ks;double kv;double ka;double dt"; } static frc::SimpleMotorFeedforward Unpack( diff --git a/wpimath/src/main/native/include/frc/controller/struct/SimpleMotorFeedforwardStruct.inc b/wpimath/src/main/native/include/frc/controller/struct/SimpleMotorFeedforwardStruct.inc index 253bc566571..50c6760f958 100644 --- a/wpimath/src/main/native/include/frc/controller/struct/SimpleMotorFeedforwardStruct.inc +++ b/wpimath/src/main/native/include/frc/controller/struct/SimpleMotorFeedforwardStruct.inc @@ -13,11 +13,13 @@ wpi::Struct>::Unpack( constexpr size_t kKsOff = 0; constexpr size_t kKvOff = kKsOff + 8; constexpr size_t kKaOff = kKvOff + 8; + constexpr size_t kDtOff = kKaOff + 8; return {units::volt_t{wpi::UnpackStruct(data)}, units::unit_t::kv_unit>{ wpi::UnpackStruct(data)}, units::unit_t::ka_unit>{ - wpi::UnpackStruct(data)}}; + wpi::UnpackStruct(data)}, + units::second_t{wpi::UnpackStruct(data)}}; } template @@ -27,6 +29,7 @@ void wpi::Struct>::Pack( constexpr size_t kKsOff = 0; constexpr size_t kKvOff = kKsOff + 8; constexpr size_t kKaOff = kKvOff + 8; + constexpr size_t kDtOff = kKaOff + 8; wpi::PackStruct(data, value.GetKs().value()); wpi::PackStruct( data, @@ -38,4 +41,5 @@ void wpi::Struct>::Pack( units::unit_t::ka_unit>{ value.GetKa()} .value()); + wpi::PackStruct(data, units::second_t{value.GetDt()}.value()); } diff --git a/wpimath/src/main/proto/controller.proto b/wpimath/src/main/proto/controller.proto index 0d0d3fb6fff..dd9db5f3110 100644 --- a/wpimath/src/main/proto/controller.proto +++ b/wpimath/src/main/proto/controller.proto @@ -29,6 +29,7 @@ message ProtobufSimpleMotorFeedforward { double ks = 1; double kv = 2; double ka = 3; + double dt = 4; } message ProtobufDifferentialDriveWheelVoltages { diff --git a/wpimath/src/test/java/edu/wpi/first/math/controller/proto/SimpleMotorFeedforwardProtoTest.java b/wpimath/src/test/java/edu/wpi/first/math/controller/proto/SimpleMotorFeedforwardProtoTest.java index de49f6a79ae..dfe8510da9b 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/controller/proto/SimpleMotorFeedforwardProtoTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/controller/proto/SimpleMotorFeedforwardProtoTest.java @@ -14,7 +14,7 @@ class SimpleMotorFeedforwardProtoTest extends ProtoTestBase { SimpleMotorFeedforwardProtoTest() { - super(new SimpleMotorFeedforward(0.4, 4.0, 0.7), SimpleMotorFeedforward.proto); + super(new SimpleMotorFeedforward(0.4, 4.0, 0.7, 0.025), SimpleMotorFeedforward.proto); } @Override @@ -22,5 +22,6 @@ public void checkEquals(SimpleMotorFeedforward testData, SimpleMotorFeedforward assertEquals(testData.getKs(), data.getKs()); assertEquals(testData.getKv(), data.getKv()); assertEquals(testData.getKa(), data.getKa()); + assertEquals(testData.getDt(), data.getDt()); } } diff --git a/wpimath/src/test/java/edu/wpi/first/math/controller/struct/SimpleMotorFeedforwardStructTest.java b/wpimath/src/test/java/edu/wpi/first/math/controller/struct/SimpleMotorFeedforwardStructTest.java index da8ffb66ebd..9dba1295e2f 100644 --- a/wpimath/src/test/java/edu/wpi/first/math/controller/struct/SimpleMotorFeedforwardStructTest.java +++ b/wpimath/src/test/java/edu/wpi/first/math/controller/struct/SimpleMotorFeedforwardStructTest.java @@ -12,7 +12,7 @@ @SuppressWarnings("PMD.TestClassWithoutTestCases") class SimpleMotorFeedforwardStructTest extends StructTestBase { SimpleMotorFeedforwardStructTest() { - super(new SimpleMotorFeedforward(0.4, 4.0, 0.7), SimpleMotorFeedforward.struct); + super(new SimpleMotorFeedforward(0.4, 4.0, 0.7, 0.025), SimpleMotorFeedforward.struct); } @Override @@ -20,5 +20,6 @@ public void checkEquals(SimpleMotorFeedforward testData, SimpleMotorFeedforward assertEquals(testData.getKs(), data.getKs()); assertEquals(testData.getKv(), data.getKv()); assertEquals(testData.getKa(), data.getKa()); + assertEquals(testData.getDt(), data.getDt()); } } diff --git a/wpimath/src/test/native/cpp/controller/proto/SimpleMotorFeedforwardProtoTest.cpp b/wpimath/src/test/native/cpp/controller/proto/SimpleMotorFeedforwardProtoTest.cpp index cf81057ff14..e49bafc6522 100644 --- a/wpimath/src/test/native/cpp/controller/proto/SimpleMotorFeedforwardProtoTest.cpp +++ b/wpimath/src/test/native/cpp/controller/proto/SimpleMotorFeedforwardProtoTest.cpp @@ -17,12 +17,13 @@ struct SimpleMotorFeedforwardProtoTestData { inline static const Type kTestData = {units::volt_t{0.4}, units::volt_t{4.0} / 1_mps, - units::volt_t{0.7} / 1_mps_sq}; + units::volt_t{0.7} / 1_mps_sq, 25_ms}; static void CheckEq(const Type& testData, const Type& data) { EXPECT_EQ(testData.GetKs().value(), data.GetKs().value()); EXPECT_EQ(testData.GetKv().value(), data.GetKv().value()); EXPECT_EQ(testData.GetKa().value(), data.GetKa().value()); + EXPECT_EQ(testData.GetDt().value(), data.GetDt().value()); } }; diff --git a/wpimath/src/test/native/cpp/controller/struct/SimpleMotorFeedforwardStructTest.cpp b/wpimath/src/test/native/cpp/controller/struct/SimpleMotorFeedforwardStructTest.cpp index 08cb10242ef..ca88fdaa47c 100644 --- a/wpimath/src/test/native/cpp/controller/struct/SimpleMotorFeedforwardStructTest.cpp +++ b/wpimath/src/test/native/cpp/controller/struct/SimpleMotorFeedforwardStructTest.cpp @@ -17,12 +17,13 @@ struct SimpleMotorFeedforwardStructTestData { inline static const Type kTestData = {units::volt_t{0.4}, units::volt_t{4.0} / 1_mps, - units::volt_t{0.7} / 1_mps_sq}; + units::volt_t{0.7} / 1_mps_sq, 25_ms}; static void CheckEq(const Type& testData, const Type& data) { EXPECT_EQ(testData.GetKs().value(), data.GetKs().value()); EXPECT_EQ(testData.GetKv().value(), data.GetKv().value()); EXPECT_EQ(testData.GetKa().value(), data.GetKa().value()); + EXPECT_EQ(testData.GetDt().value(), data.GetDt().value()); } };