diff --git a/wpiutil/src/main/java/edu/wpi/first/util/datalog/BooleanArrayLogEntry.java b/wpiutil/src/main/java/edu/wpi/first/util/datalog/BooleanArrayLogEntry.java index 99042e0f929..6c86a3de394 100644 --- a/wpiutil/src/main/java/edu/wpi/first/util/datalog/BooleanArrayLogEntry.java +++ b/wpiutil/src/main/java/edu/wpi/first/util/datalog/BooleanArrayLogEntry.java @@ -96,6 +96,15 @@ public void update(boolean[] value) { update(value, 0); } + /** + * Gets whether there is a last value. + * + * @return True if last value exists, false otherwise. + */ + public synchronized boolean hasLastValue() { + return m_lastValue != null; + } + /** * Gets the last value. * diff --git a/wpiutil/src/main/java/edu/wpi/first/util/datalog/BooleanLogEntry.java b/wpiutil/src/main/java/edu/wpi/first/util/datalog/BooleanLogEntry.java index 9249ef9c965..cb4b3435d23 100644 --- a/wpiutil/src/main/java/edu/wpi/first/util/datalog/BooleanLogEntry.java +++ b/wpiutil/src/main/java/edu/wpi/first/util/datalog/BooleanLogEntry.java @@ -95,6 +95,15 @@ public void update(boolean value) { update(value, 0); } + /** + * Gets whether there is a last value. + * + * @return True if last value exists, false otherwise. + */ + public synchronized boolean hasLastValue() { + return m_hasLastValue; + } + /** * Gets the last value. * diff --git a/wpiutil/src/main/java/edu/wpi/first/util/datalog/DataLogWriter.java b/wpiutil/src/main/java/edu/wpi/first/util/datalog/DataLogWriter.java index 99149d6e179..058d6dd8a46 100644 --- a/wpiutil/src/main/java/edu/wpi/first/util/datalog/DataLogWriter.java +++ b/wpiutil/src/main/java/edu/wpi/first/util/datalog/DataLogWriter.java @@ -55,6 +55,7 @@ public DataLogWriter(OutputStream os) { } /** Explicitly flushes the log data to disk. */ + @Override public void flush() { DataLogJNI.flush(m_impl); if (m_os == null) { @@ -62,7 +63,7 @@ public void flush() { } try { int pos = 0; - for (;;) { + for (; ; ) { int qty = DataLogJNI.copyWriteBuffer(m_impl, m_buf, pos); if (qty == 0) { break; diff --git a/wpiutil/src/main/java/edu/wpi/first/util/datalog/DoubleArrayLogEntry.java b/wpiutil/src/main/java/edu/wpi/first/util/datalog/DoubleArrayLogEntry.java index 0e20983ad76..f94f314ed07 100644 --- a/wpiutil/src/main/java/edu/wpi/first/util/datalog/DoubleArrayLogEntry.java +++ b/wpiutil/src/main/java/edu/wpi/first/util/datalog/DoubleArrayLogEntry.java @@ -96,6 +96,15 @@ public void update(double[] value) { update(value, 0); } + /** + * Gets whether there is a last value. + * + * @return True if last value exists, false otherwise. + */ + public synchronized boolean hasLastValue() { + return m_lastValue != null; + } + /** * Gets the last value. * diff --git a/wpiutil/src/main/java/edu/wpi/first/util/datalog/DoubleLogEntry.java b/wpiutil/src/main/java/edu/wpi/first/util/datalog/DoubleLogEntry.java index 933cb20cd53..ea49b193d66 100644 --- a/wpiutil/src/main/java/edu/wpi/first/util/datalog/DoubleLogEntry.java +++ b/wpiutil/src/main/java/edu/wpi/first/util/datalog/DoubleLogEntry.java @@ -95,6 +95,15 @@ public void update(double value) { update(value, 0); } + /** + * Gets whether there is a last value. + * + * @return True if last value exists, false otherwise. + */ + public synchronized boolean hasLastValue() { + return m_hasLastValue; + } + /** * Gets the last value. * diff --git a/wpiutil/src/main/java/edu/wpi/first/util/datalog/FloatArrayLogEntry.java b/wpiutil/src/main/java/edu/wpi/first/util/datalog/FloatArrayLogEntry.java index 02cbe08d24c..3316767a263 100644 --- a/wpiutil/src/main/java/edu/wpi/first/util/datalog/FloatArrayLogEntry.java +++ b/wpiutil/src/main/java/edu/wpi/first/util/datalog/FloatArrayLogEntry.java @@ -96,6 +96,15 @@ public void update(float[] value) { update(value, 0); } + /** + * Gets whether there is a last value. + * + * @return True if last value exists, false otherwise. + */ + public synchronized boolean hasLastValue() { + return m_lastValue != null; + } + /** * Gets the last value. * diff --git a/wpiutil/src/main/java/edu/wpi/first/util/datalog/FloatLogEntry.java b/wpiutil/src/main/java/edu/wpi/first/util/datalog/FloatLogEntry.java index a72bd9751bc..94c9f2f789b 100644 --- a/wpiutil/src/main/java/edu/wpi/first/util/datalog/FloatLogEntry.java +++ b/wpiutil/src/main/java/edu/wpi/first/util/datalog/FloatLogEntry.java @@ -95,6 +95,15 @@ public void update(float value) { update(value, 0); } + /** + * Gets whether there is a last value. + * + * @return True if last value exists, false otherwise. + */ + public synchronized boolean hasLastValue() { + return m_hasLastValue; + } + /** * Gets the last value. * diff --git a/wpiutil/src/main/java/edu/wpi/first/util/datalog/IntegerArrayLogEntry.java b/wpiutil/src/main/java/edu/wpi/first/util/datalog/IntegerArrayLogEntry.java index 433c3d49f61..a74d87f6fb1 100644 --- a/wpiutil/src/main/java/edu/wpi/first/util/datalog/IntegerArrayLogEntry.java +++ b/wpiutil/src/main/java/edu/wpi/first/util/datalog/IntegerArrayLogEntry.java @@ -96,6 +96,15 @@ public void update(long[] value) { update(value, 0); } + /** + * Gets whether there is a last value. + * + * @return True if last value exists, false otherwise. + */ + public synchronized boolean hasLastValue() { + return m_lastValue != null; + } + /** * Gets the last value. * diff --git a/wpiutil/src/main/java/edu/wpi/first/util/datalog/IntegerLogEntry.java b/wpiutil/src/main/java/edu/wpi/first/util/datalog/IntegerLogEntry.java index 272628bdfbd..1d805059558 100644 --- a/wpiutil/src/main/java/edu/wpi/first/util/datalog/IntegerLogEntry.java +++ b/wpiutil/src/main/java/edu/wpi/first/util/datalog/IntegerLogEntry.java @@ -95,6 +95,15 @@ public void update(long value) { update(value, 0); } + /** + * Gets whether there is a last value. + * + * @return True if last value exists, false otherwise. + */ + public synchronized boolean hasLastValue() { + return m_hasLastValue; + } + /** * Gets the last value. * diff --git a/wpiutil/src/main/java/edu/wpi/first/util/datalog/ProtobufLogEntry.java b/wpiutil/src/main/java/edu/wpi/first/util/datalog/ProtobufLogEntry.java index 61de93eae15..fcc4400bb0c 100644 --- a/wpiutil/src/main/java/edu/wpi/first/util/datalog/ProtobufLogEntry.java +++ b/wpiutil/src/main/java/edu/wpi/first/util/datalog/ProtobufLogEntry.java @@ -157,6 +157,22 @@ public void update(T value) { update(value, 0); } + /** + * Gets whether there is a last value. + * + * @return True if last value exists, false otherwise. + */ + public boolean hasLastValue() { + synchronized (m_buf) { + if (m_immutable) { + return m_lastValue != null; + } else if (m_cloneable && m_lastValue != null) { + return true; + } + return m_lastValueBuf != null; + } + } + /** * Gets the last value. * @@ -166,11 +182,7 @@ public T getLastValue() { synchronized (m_buf) { if (m_immutable) { return m_lastValue; - } - if (m_cloneable) { - if (m_lastValue == null) { - return null; - } + } else if (m_cloneable && m_lastValue != null) { try { return m_buf.getProto().clone(m_lastValue); } catch (CloneNotSupportedException e) { diff --git a/wpiutil/src/main/java/edu/wpi/first/util/datalog/RawLogEntry.java b/wpiutil/src/main/java/edu/wpi/first/util/datalog/RawLogEntry.java index 64ad65b7128..4b54f377fd3 100644 --- a/wpiutil/src/main/java/edu/wpi/first/util/datalog/RawLogEntry.java +++ b/wpiutil/src/main/java/edu/wpi/first/util/datalog/RawLogEntry.java @@ -263,6 +263,15 @@ public void update(ByteBuffer value, int start, int len) { update(value, start, len, 0); } + /** + * Gets whether there is a last value. + * + * @return True if last value exists, false otherwise. + */ + public synchronized boolean hasLastValue() { + return m_lastValue != null; + } + /** * Gets the last value. * @@ -283,6 +292,7 @@ private boolean equalsLast(byte[] value, int start, int len) { return Arrays.equals(m_lastValue.array(), 0, len, value, start, start + len); } + @SuppressWarnings("PMD.SimplifyBooleanReturns") private boolean equalsLast(ByteBuffer value) { if (m_lastValue == null) { return false; diff --git a/wpiutil/src/main/java/edu/wpi/first/util/datalog/StringArrayLogEntry.java b/wpiutil/src/main/java/edu/wpi/first/util/datalog/StringArrayLogEntry.java index ce2cb179a67..cf82ac05560 100644 --- a/wpiutil/src/main/java/edu/wpi/first/util/datalog/StringArrayLogEntry.java +++ b/wpiutil/src/main/java/edu/wpi/first/util/datalog/StringArrayLogEntry.java @@ -96,6 +96,15 @@ public void update(String[] value) { update(value, 0); } + /** + * Gets whether there is a last value. + * + * @return True if last value exists, false otherwise. + */ + public synchronized boolean hasLastValue() { + return m_lastValue != null; + } + /** * Gets the last value. * diff --git a/wpiutil/src/main/java/edu/wpi/first/util/datalog/StringLogEntry.java b/wpiutil/src/main/java/edu/wpi/first/util/datalog/StringLogEntry.java index 7272b43ad35..785a3fda821 100644 --- a/wpiutil/src/main/java/edu/wpi/first/util/datalog/StringLogEntry.java +++ b/wpiutil/src/main/java/edu/wpi/first/util/datalog/StringLogEntry.java @@ -119,6 +119,15 @@ public void update(String value) { update(value, 0); } + /** + * Gets whether there is a last value. + * + * @return True if last value exists, false otherwise. + */ + public synchronized boolean hasLastValue() { + return m_lastValue != null; + } + /** * Gets the last value. * diff --git a/wpiutil/src/main/java/edu/wpi/first/util/datalog/StructArrayLogEntry.java b/wpiutil/src/main/java/edu/wpi/first/util/datalog/StructArrayLogEntry.java index e46d912d91d..a7f48ebaf4f 100644 --- a/wpiutil/src/main/java/edu/wpi/first/util/datalog/StructArrayLogEntry.java +++ b/wpiutil/src/main/java/edu/wpi/first/util/datalog/StructArrayLogEntry.java @@ -210,6 +210,22 @@ public void update(Collection value) { update(value, 0); } + /** + * Gets whether there is a last value. + * + * @return True if last value exists, false otherwise. + */ + public boolean hasLastValue() { + synchronized (m_buf) { + if (m_immutable) { + return m_lastValue != null; + } else if (m_cloneable && m_lastValue != null) { + return true; + } + return m_lastValueBuf != null; + } + } + /** * Gets the last value. * @@ -218,18 +234,16 @@ public void update(Collection value) { @SuppressWarnings("PMD.ReturnEmptyCollectionRatherThanNull") public T[] getLastValue() { synchronized (m_buf) { - if (m_immutable || m_cloneable) { + if (m_immutable) { if (m_lastValue == null) { return null; } - if (m_immutable) { - return Arrays.copyOf(m_lastValue, m_lastValueLen); - } else { - try { - return cloneArray(m_lastValue); - } catch (CloneNotSupportedException e) { - // fall through - } + return Arrays.copyOf(m_lastValue, m_lastValueLen); + } else if (m_cloneable && m_lastValue != null) { + try { + return cloneArray(m_lastValue, m_lastValueLen); + } catch (CloneNotSupportedException e) { + // fall through } } if (m_lastValueBuf == null) { @@ -276,11 +290,11 @@ private boolean equalsLast(Collection arr) { return true; } - private T[] cloneArray(T[] in) throws CloneNotSupportedException { + private T[] cloneArray(T[] in, int len) throws CloneNotSupportedException { Struct s = m_buf.getStruct(); @SuppressWarnings("unchecked") - T[] arr = (T[]) Array.newInstance(s.getTypeClass(), in.length); - for (int i = 0; i < in.length; i++) { + T[] arr = (T[]) Array.newInstance(s.getTypeClass(), len); + for (int i = 0; i < len; i++) { arr[i] = s.clone(in[i]); } return arr; @@ -302,7 +316,7 @@ private void copyToLast(T[] value) throws CloneNotSupportedException { if (m_immutable) { m_lastValue = Arrays.copyOf(value, value.length); } else { - m_lastValue = cloneArray(value); + m_lastValue = cloneArray(value, value.length); } } else { if (m_immutable) { diff --git a/wpiutil/src/main/java/edu/wpi/first/util/datalog/StructLogEntry.java b/wpiutil/src/main/java/edu/wpi/first/util/datalog/StructLogEntry.java index 08077d39b63..f692b0a5acb 100644 --- a/wpiutil/src/main/java/edu/wpi/first/util/datalog/StructLogEntry.java +++ b/wpiutil/src/main/java/edu/wpi/first/util/datalog/StructLogEntry.java @@ -142,6 +142,22 @@ public void update(T value) { update(value, 0); } + /** + * Gets whether there is a last value. + * + * @return True if last value exists, false otherwise. + */ + public boolean hasLastValue() { + synchronized (m_buf) { + if (m_immutable) { + return m_lastValue != null; + } else if (m_cloneable && m_lastValue != null) { + return true; + } + return m_lastValueBuf != null; + } + } + /** * Gets the last value. * @@ -151,11 +167,7 @@ public T getLastValue() { synchronized (m_buf) { if (m_immutable) { return m_lastValue; - } - if (m_cloneable) { - if (m_lastValue == null) { - return null; - } + } else if (m_cloneable && m_lastValue != null) { try { return m_buf.getStruct().clone(m_lastValue); } catch (CloneNotSupportedException e) { diff --git a/wpiutil/src/main/native/include/wpi/DataLog.h b/wpiutil/src/main/native/include/wpi/DataLog.h index 8401e3538c9..e6df8134801 100644 --- a/wpiutil/src/main/native/include/wpi/DataLog.h +++ b/wpiutil/src/main/native/include/wpi/DataLog.h @@ -1299,7 +1299,8 @@ class StructLogEntry : public DataLogEntry { return std::nullopt; } return std::apply( - [&](const I&... info) { S::Unpack(m_lastValue, info...); }, m_info); + [&](const I&... info) { return S::Unpack(m_lastValue, info...); }, + m_info); } private: @@ -1401,10 +1402,13 @@ class StructArrayLogEntry : public DataLogEntry { data, [&](auto bytes) { std::scoped_lock lock{m_mutex}; - if (m_lastValue.empty() || - !std::equal(bytes.begin(), bytes.end(), m_lastValue.begin(), - m_lastValue.end())) { - m_lastValue.assign(bytes.begin(), bytes.end()); + if (!m_lastValue.has_value()) { + m_lastValue = std::vector(bytes.begin(), bytes.end()); + m_log->AppendRaw(m_entry, bytes, timestamp); + } else if (!std::equal(bytes.begin(), bytes.end(), + m_lastValue->begin(), + m_lastValue->end())) { + m_lastValue->assign(bytes.begin(), bytes.end()); m_log->AppendRaw(m_entry, bytes, timestamp); } }, @@ -1421,17 +1425,18 @@ class StructArrayLogEntry : public DataLogEntry { */ std::optional> GetLastValue() const { std::scoped_lock lock{m_mutex}; - if (m_lastValue.empty()) { + if (!m_lastValue.has_value()) { return std::nullopt; } + auto& lastValue = m_lastValue.value(); size_t size = std::apply(S::GetSize, m_info); std::vector rv; - rv.value.reserve(m_lastValue.size() / size); - for (auto in = m_lastValue.begin(), end = m_lastValue.end(); in < end; + rv.reserve(lastValue.size() / size); + for (auto in = lastValue.begin(), end = lastValue.end(); in < end; in += size) { std::apply( [&](const I&... info) { - rv.value.emplace_back(S::Unpack( + rv.emplace_back(S::Unpack( std::span{std::to_address(in), size}, info...)); }, m_info); @@ -1442,7 +1447,7 @@ class StructArrayLogEntry : public DataLogEntry { private: mutable wpi::mutex m_mutex; StructArrayBuffer m_buf; - std::vector m_lastValue; + std::optional> m_lastValue; [[no_unique_address]] std::tuple m_info; }; @@ -1490,10 +1495,12 @@ class ProtobufLogEntry : public DataLogEntry { std::scoped_lock lock{m_mutex}; wpi::SmallVector buf; m_msg.Pack(buf, data); - if (m_lastValue.empty() || - !std::equal(buf.begin(), buf.end(), m_lastValue.begin(), - m_lastValue.end())) { - m_lastValue.assign(buf.begin(), buf.end()); + if (!m_lastValue.has_value()) { + m_lastValue = std::vector(buf.begin(), buf.end()); + m_log->AppendRaw(m_entry, buf, timestamp); + } else if (!std::equal(buf.begin(), buf.end(), m_lastValue->begin(), + m_lastValue->end())) { + m_lastValue->assign(buf.begin(), buf.end()); m_log->AppendRaw(m_entry, buf, timestamp); } } @@ -1506,7 +1513,7 @@ class ProtobufLogEntry : public DataLogEntry { */ std::optional GetLastValue() const { std::scoped_lock lock{m_mutex}; - if (m_lastValue.empty()) { + if (!m_lastValue.has_value()) { return std::nullopt; } return m_msg.Unpack(m_lastValue); @@ -1515,7 +1522,7 @@ class ProtobufLogEntry : public DataLogEntry { private: mutable wpi::mutex m_mutex; ProtobufMessage m_msg; - std::vector m_lastValue; + std::optional> m_lastValue; }; } // namespace wpi::log diff --git a/wpiutil/src/test/java/edu/wpi/first/util/datalog/DataLogTest.java b/wpiutil/src/test/java/edu/wpi/first/util/datalog/DataLogTest.java new file mode 100644 index 00000000000..c3c90cef0dc --- /dev/null +++ b/wpiutil/src/test/java/edu/wpi/first/util/datalog/DataLogTest.java @@ -0,0 +1,742 @@ +// 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. + +package edu.wpi.first.util.datalog; + +import static org.junit.jupiter.api.Assertions.assertArrayEquals; +import static org.junit.jupiter.api.Assertions.assertEquals; +import static org.junit.jupiter.api.Assertions.assertFalse; +import static org.junit.jupiter.api.Assertions.assertTrue; + +import edu.wpi.first.util.struct.Struct; +import edu.wpi.first.util.struct.StructSerializable; +import java.io.ByteArrayOutputStream; +import java.nio.ByteBuffer; +import java.util.Objects; +import org.junit.jupiter.api.AfterEach; +import org.junit.jupiter.api.BeforeEach; +import org.junit.jupiter.api.Test; + +@SuppressWarnings("AvoidEscapedUnicodeCharacters") +class DataLogTest { + static class ImmutableThingStruct implements Struct { + @Override + public Class getTypeClass() { + return ImmutableThing.class; + } + + @Override + public String getTypeString() { + return "struct:Thing"; + } + + @Override + public int getSize() { + return 1; + } + + @Override + public String getSchema() { + return "uint8 value"; + } + + @Override + public ImmutableThing unpack(ByteBuffer bb) { + return new ImmutableThing(bb.get()); + } + + @Override + public void pack(ByteBuffer bb, ImmutableThing value) { + bb.put(value.m_x); + } + + @Override + public boolean isImmutable() { + return true; + } + } + + static class ImmutableThing implements StructSerializable { + byte m_x; + + ImmutableThing(int x) { + m_x = (byte) x; + } + + @Override + public boolean equals(Object obj) { + return obj instanceof ImmutableThing other && other.m_x == m_x; + } + + @Override + public int hashCode() { + return Objects.hash(m_x); + } + + public static final ImmutableThingStruct struct = new ImmutableThingStruct(); + } + + static class CloneableThingStruct implements Struct { + @Override + public Class getTypeClass() { + return CloneableThing.class; + } + + @Override + public String getTypeString() { + return "struct:Thing"; + } + + @Override + public int getSize() { + return 1; + } + + @Override + public String getSchema() { + return "uint8 value"; + } + + @Override + public CloneableThing unpack(ByteBuffer bb) { + return new CloneableThing(bb.get()); + } + + @Override + public void pack(ByteBuffer bb, CloneableThing value) { + bb.put(value.m_x); + } + + @Override + public boolean isCloneable() { + return true; + } + + @Override + public CloneableThing clone(CloneableThing obj) throws CloneNotSupportedException { + return obj.clone(); + } + } + + @SuppressWarnings("MemberName") + private static int cloneCalls; + + static class CloneableThing implements StructSerializable, Cloneable { + byte m_x; + + CloneableThing(int x) { + m_x = (byte) x; + } + + @Override + public boolean equals(Object obj) { + return obj instanceof CloneableThing other && other.m_x == m_x; + } + + @Override + public int hashCode() { + return Objects.hash(m_x); + } + + @Override + public CloneableThing clone() throws CloneNotSupportedException { + CloneableThing thing = (CloneableThing) super.clone(); + cloneCalls++; + return thing; + } + + public static final CloneableThingStruct struct = new CloneableThingStruct(); + } + + static class ThingStruct implements Struct { + @Override + public Class getTypeClass() { + return Thing.class; + } + + @Override + public String getTypeString() { + return "struct:Thing"; + } + + @Override + public int getSize() { + return 1; + } + + @Override + public String getSchema() { + return "uint8 value"; + } + + @Override + public Thing unpack(ByteBuffer bb) { + return new Thing(bb.get()); + } + + @Override + public void pack(ByteBuffer bb, Thing value) { + bb.put(value.m_x); + } + } + + static class Thing implements StructSerializable { + byte m_x; + + Thing(int x) { + m_x = (byte) x; + } + + @Override + public boolean equals(Object obj) { + return obj instanceof Thing other && other.m_x == m_x; + } + + @Override + public int hashCode() { + return Objects.hash(m_x); + } + + public static final ThingStruct struct = new ThingStruct(); + } + + @SuppressWarnings("MemberName") + private ByteArrayOutputStream data; + + @SuppressWarnings("MemberName") + private DataLog log; + + @BeforeEach + public void init() { + data = new ByteArrayOutputStream(); + log = new DataLogWriter(data); + cloneCalls = 0; + } + + @AfterEach + public void shutdown() { + log.close(); + } + + @Test + void testSimpleInt() { + int entry = log.start("test", "int64", "", 1); + log.appendInteger(entry, 1, 2); + log.flush(); + assertEquals(54, data.size()); + } + + @Test + void testBooleanAppend() { + BooleanLogEntry entry = new BooleanLogEntry(log, "a", 5); + entry.append(false, 7); + log.flush(); + assertEquals(46, data.size()); + } + + @Test + void testBooleanUpdate() { + BooleanLogEntry entry = new BooleanLogEntry(log, "a", 5); + assertFalse(entry.hasLastValue()); + entry.update(false, 7); + log.flush(); + assertEquals(46, data.size()); + assertTrue(entry.hasLastValue()); + assertFalse(entry.getLastValue()); + entry.update(false, 8); + log.flush(); + assertEquals(46, data.size()); + entry.update(true, 9); + log.flush(); + assertEquals(51, data.size()); + assertTrue(entry.hasLastValue()); + assertTrue(entry.getLastValue()); + } + + @Test + void testIntegerAppend() { + IntegerLogEntry entry = new IntegerLogEntry(log, "a", 5); + entry.append(5, 7); + log.flush(); + assertEquals(51, data.size()); + } + + @Test + void testIntegerUpdate() { + IntegerLogEntry entry = new IntegerLogEntry(log, "a", 5); + assertFalse(entry.hasLastValue()); + entry.update(0, 7); + log.flush(); + assertEquals(51, data.size()); + assertTrue(entry.hasLastValue()); + assertEquals(0, entry.getLastValue()); + entry.update(0, 8); + log.flush(); + assertEquals(51, data.size()); + entry.update(2, 9); + log.flush(); + assertEquals(63, data.size()); + assertTrue(entry.hasLastValue()); + assertEquals(2, entry.getLastValue()); + } + + @Test + void testFloatAppend() { + FloatLogEntry entry = new FloatLogEntry(log, "a", 5); + entry.append(5.0f, 7); + log.flush(); + assertEquals(47, data.size()); + } + + @Test + void testFloatUpdate() { + FloatLogEntry entry = new FloatLogEntry(log, "a", 5); + assertFalse(entry.hasLastValue()); + entry.update(0.0f, 7); + log.flush(); + assertEquals(47, data.size()); + assertTrue(entry.hasLastValue()); + assertEquals(0.0f, entry.getLastValue()); + entry.update(0.0f, 8); + log.flush(); + assertEquals(47, data.size()); + entry.update(0.1f, 9); + log.flush(); + assertEquals(55, data.size()); + assertTrue(entry.hasLastValue()); + assertEquals(0.1f, entry.getLastValue()); + } + + @Test + void testDoubleAppend() { + DoubleLogEntry entry = new DoubleLogEntry(log, "a", 5); + entry.append(5.0, 7); + log.flush(); + assertEquals(52, data.size()); + } + + @Test + void testDoubleUpdate() { + DoubleLogEntry entry = new DoubleLogEntry(log, "a", 5); + assertFalse(entry.hasLastValue()); + entry.update(0.0, 7); + log.flush(); + assertEquals(52, data.size()); + assertTrue(entry.hasLastValue()); + assertEquals(0.0, entry.getLastValue()); + entry.update(0.0, 8); + log.flush(); + assertEquals(52, data.size()); + entry.update(0.1, 9); + log.flush(); + assertEquals(64, data.size()); + assertTrue(entry.hasLastValue()); + assertEquals(0.1, entry.getLastValue()); + } + + @Test + void testStringAppend() { + StringLogEntry entry = new StringLogEntry(log, "a", 5); + entry.append("x", 7); + log.flush(); + assertEquals(45, data.size()); + } + + @Test + void testStringUpdate() { + StringLogEntry entry = new StringLogEntry(log, "a", 5); + assertFalse(entry.hasLastValue()); + entry.update("x", 7); + log.flush(); + assertEquals(45, data.size()); + assertTrue(entry.hasLastValue()); + assertEquals("x", entry.getLastValue()); + entry.update("x", 8); + log.flush(); + assertEquals(45, data.size()); + entry.update("y", 9); + log.flush(); + assertEquals(50, data.size()); + assertTrue(entry.hasLastValue()); + assertEquals("y", entry.getLastValue()); + } + + @Test + void testBooleanArrayAppendEmpty() { + BooleanArrayLogEntry entry = new BooleanArrayLogEntry(log, "a", 5); + entry.append(new boolean[] {}, 7); + log.flush(); + assertEquals(47, data.size()); + } + + @Test + void testBooleanArrayAppend() { + BooleanArrayLogEntry entry = new BooleanArrayLogEntry(log, "a", 5); + entry.append(new boolean[] {false}, 7); + log.flush(); + assertEquals(48, data.size()); + } + + @Test + void testBooleanArrayUpdate() { + BooleanArrayLogEntry entry = new BooleanArrayLogEntry(log, "a", 5); + assertFalse(entry.hasLastValue()); + entry.update(new boolean[] {false}, 7); + log.flush(); + assertEquals(48, data.size()); + assertTrue(entry.hasLastValue()); + assertArrayEquals(new boolean[] {false}, entry.getLastValue()); + entry.update(new boolean[] {false}, 8); + log.flush(); + assertEquals(48, data.size()); + entry.update(new boolean[] {true}, 9); + log.flush(); + assertEquals(53, data.size()); + assertTrue(entry.hasLastValue()); + assertArrayEquals(new boolean[] {true}, entry.getLastValue()); + entry.update(new boolean[] {}, 10); + log.flush(); + assertEquals(57, data.size()); + assertTrue(entry.hasLastValue()); + assertArrayEquals(new boolean[] {}, entry.getLastValue()); + } + + @Test + void testIntegerArrayAppendEmpty() { + IntegerArrayLogEntry entry = new IntegerArrayLogEntry(log, "a", 5); + entry.append(new long[] {}, 7); + log.flush(); + assertEquals(45, data.size()); + } + + @Test + void testIntegerArrayAppend() { + IntegerArrayLogEntry entry = new IntegerArrayLogEntry(log, "a", 5); + entry.append(new long[] {1}, 7); + log.flush(); + assertEquals(53, data.size()); + } + + @Test + void testIntegerArrayUpdate() { + IntegerArrayLogEntry entry = new IntegerArrayLogEntry(log, "a", 5); + assertFalse(entry.hasLastValue()); + entry.update(new long[] {1}, 7); + log.flush(); + assertEquals(53, data.size()); + assertTrue(entry.hasLastValue()); + assertArrayEquals(new long[] {1}, entry.getLastValue()); + entry.update(new long[] {1}, 8); + log.flush(); + assertEquals(53, data.size()); + entry.update(new long[] {2}, 9); + log.flush(); + assertEquals(65, data.size()); + assertTrue(entry.hasLastValue()); + assertArrayEquals(new long[] {2}, entry.getLastValue()); + entry.update(new long[] {}, 10); + log.flush(); + assertEquals(69, data.size()); + assertTrue(entry.hasLastValue()); + assertArrayEquals(new long[] {}, entry.getLastValue()); + } + + @Test + void testDoubleArrayAppendEmpty() { + DoubleArrayLogEntry entry = new DoubleArrayLogEntry(log, "a", 5); + entry.append(new double[] {}, 7); + log.flush(); + assertEquals(46, data.size()); + } + + @Test + void testDoubleArrayAppend() { + DoubleArrayLogEntry entry = new DoubleArrayLogEntry(log, "a", 5); + entry.append(new double[] {1.0}, 7); + log.flush(); + assertEquals(54, data.size()); + } + + @Test + void testDoubleArrayUpdate() { + DoubleArrayLogEntry entry = new DoubleArrayLogEntry(log, "a", 5); + assertFalse(entry.hasLastValue()); + entry.update(new double[] {1.0}, 7); + log.flush(); + assertEquals(54, data.size()); + assertTrue(entry.hasLastValue()); + assertArrayEquals(new double[] {1.0}, entry.getLastValue()); + entry.update(new double[] {1.0}, 8); + log.flush(); + assertEquals(54, data.size()); + entry.update(new double[] {2.0}, 9); + log.flush(); + assertEquals(66, data.size()); + assertTrue(entry.hasLastValue()); + assertArrayEquals(new double[] {2}, entry.getLastValue()); + entry.update(new double[] {}, 10); + log.flush(); + assertEquals(70, data.size()); + assertTrue(entry.hasLastValue()); + assertArrayEquals(new double[] {}, entry.getLastValue()); + } + + @Test + void testFloatArrayAppendEmpty() { + FloatArrayLogEntry entry = new FloatArrayLogEntry(log, "a", 5); + entry.append(new float[] {}, 7); + log.flush(); + assertEquals(45, data.size()); + } + + @Test + void testFloatArrayAppend() { + FloatArrayLogEntry entry = new FloatArrayLogEntry(log, "a", 5); + entry.append(new float[] {1.0f}, 7); + log.flush(); + assertEquals(49, data.size()); + } + + @Test + void testFloatArrayUpdate() { + FloatArrayLogEntry entry = new FloatArrayLogEntry(log, "a", 5); + assertFalse(entry.hasLastValue()); + entry.update(new float[] {1.0f}, 7); + log.flush(); + assertEquals(49, data.size()); + assertTrue(entry.hasLastValue()); + assertArrayEquals(new float[] {1.0f}, entry.getLastValue()); + entry.update(new float[] {1.0f}, 8); + log.flush(); + assertEquals(49, data.size()); + entry.update(new float[] {2.0f}, 9); + log.flush(); + assertEquals(57, data.size()); + assertTrue(entry.hasLastValue()); + assertArrayEquals(new float[] {2.0f}, entry.getLastValue()); + entry.update(new float[] {}, 10); + log.flush(); + assertEquals(61, data.size()); + assertTrue(entry.hasLastValue()); + assertArrayEquals(new float[] {}, entry.getLastValue()); + } + + @Test + void testStringArrayAppendEmpty() { + StringArrayLogEntry entry = new StringArrayLogEntry(log, "a", 5); + entry.append(new String[] {}, 7); + entry.append(new String[] {}, 7); + log.flush(); + assertEquals(58, data.size()); + } + + @Test + void testStringArrayAppend() { + StringArrayLogEntry entry = new StringArrayLogEntry(log, "a", 5); + entry.append(new String[] {"x"}, 7); + log.flush(); + assertEquals(55, data.size()); + } + + @Test + void testStringArrayUpdate() { + StringArrayLogEntry entry = new StringArrayLogEntry(log, "a", 5); + assertFalse(entry.hasLastValue()); + entry.update(new String[] {"x"}, 7); + log.flush(); + assertEquals(55, data.size()); + assertTrue(entry.hasLastValue()); + assertArrayEquals(new String[] {"x"}, entry.getLastValue()); + entry.update(new String[] {"x"}, 8); + log.flush(); + assertEquals(55, data.size()); + entry.update(new String[] {"y"}, 9); + log.flush(); + assertEquals(68, data.size()); + assertTrue(entry.hasLastValue()); + assertArrayEquals(new String[] {"y"}, entry.getLastValue()); + entry.update(new String[] {}, 10); + log.flush(); + assertEquals(76, data.size()); + assertTrue(entry.hasLastValue()); + assertArrayEquals(new String[] {}, entry.getLastValue()); + } + + @Test + void testStruct() { + StructLogEntry entry = StructLogEntry.create(log, "a", Thing.struct, 5); + entry.append(new Thing((byte) 1), 6); + entry.append(new Thing((byte) 0), 7); + } + + @Test + void testStructUpdate() { + StructLogEntry entry = StructLogEntry.create(log, "a", Thing.struct, 5); + assertFalse(entry.hasLastValue()); + + entry.update(new Thing(1), 7); + log.flush(); + assertEquals(120, data.size()); + assertTrue(entry.hasLastValue()); + assertEquals(new Thing(1), entry.getLastValue()); + + entry.update(new Thing(1), 8); + log.flush(); + assertEquals(120, data.size()); + + entry.update(new Thing(2), 9); + log.flush(); + assertEquals(125, data.size()); + assertTrue(entry.hasLastValue()); + assertEquals(new Thing(2), entry.getLastValue()); + } + + @Test + void testCloneableStructUpdate() { + StructLogEntry entry = + StructLogEntry.create(log, "a", CloneableThing.struct, 5); + assertFalse(entry.hasLastValue()); + + entry.update(new CloneableThing(1), 7); + assertEquals(1, cloneCalls); + log.flush(); + assertEquals(120, data.size()); + assertTrue(entry.hasLastValue()); + assertEquals(new CloneableThing(1), entry.getLastValue()); + assertEquals(2, cloneCalls); + + entry.update(new CloneableThing(1), 8); + assertEquals(2, cloneCalls); + log.flush(); + assertEquals(120, data.size()); + + entry.update(new CloneableThing(2), 9); + assertEquals(3, cloneCalls); + log.flush(); + assertEquals(125, data.size()); + assertTrue(entry.hasLastValue()); + assertEquals(new CloneableThing(2), entry.getLastValue()); + assertEquals(4, cloneCalls); + } + + @Test + void testImmutableStructUpdate() { + StructLogEntry entry = + StructLogEntry.create(log, "a", ImmutableThing.struct, 5); + assertFalse(entry.hasLastValue()); + + entry.update(new ImmutableThing(1), 7); + log.flush(); + assertEquals(120, data.size()); + assertTrue(entry.hasLastValue()); + assertEquals(new ImmutableThing(1), entry.getLastValue()); + + entry.update(new ImmutableThing(1), 8); + log.flush(); + assertEquals(120, data.size()); + + entry.update(new ImmutableThing(2), 9); + log.flush(); + assertEquals(125, data.size()); + assertTrue(entry.hasLastValue()); + assertEquals(new ImmutableThing(2), entry.getLastValue()); + } + + @Test + void testStructArrayUpdate() { + StructArrayLogEntry entry = StructArrayLogEntry.create(log, "a", Thing.struct, 5); + assertFalse(entry.hasLastValue()); + + entry.update(new Thing[] {new Thing(1), new Thing(2)}, 7); + log.flush(); + assertEquals(123, data.size()); + assertTrue(entry.hasLastValue()); + assertArrayEquals(new Thing[] {new Thing(1), new Thing(2)}, entry.getLastValue()); + + entry.update(new Thing[] {new Thing(1), new Thing(2)}, 8); + log.flush(); + assertEquals(123, data.size()); + + entry.update(new Thing[] {new Thing(1), new Thing(3)}, 9); + log.flush(); + assertEquals(129, data.size()); + assertTrue(entry.hasLastValue()); + assertArrayEquals(new Thing[] {new Thing(1), new Thing(3)}, entry.getLastValue()); + + entry.update(new Thing[] {}, 10); + log.flush(); + assertEquals(133, data.size()); + assertTrue(entry.hasLastValue()); + assertArrayEquals(new Thing[] {}, entry.getLastValue()); + } + + @Test + void testCloneableStructArrayUpdate() { + StructArrayLogEntry entry = + StructArrayLogEntry.create(log, "a", CloneableThing.struct, 5); + assertFalse(entry.hasLastValue()); + + entry.update(new CloneableThing[] {new CloneableThing(1), new CloneableThing(2)}, 7); + assertEquals(2, cloneCalls); + log.flush(); + assertEquals(123, data.size()); + assertTrue(entry.hasLastValue()); + assertArrayEquals( + new CloneableThing[] {new CloneableThing(1), new CloneableThing(2)}, entry.getLastValue()); + assertEquals(4, cloneCalls); + + entry.update(new CloneableThing[] {new CloneableThing(1), new CloneableThing(2)}, 8); + assertEquals(4, cloneCalls); + log.flush(); + assertEquals(123, data.size()); + + entry.update(new CloneableThing[] {new CloneableThing(1), new CloneableThing(3)}, 9); + assertEquals(6, cloneCalls); + log.flush(); + assertEquals(129, data.size()); + assertTrue(entry.hasLastValue()); + assertArrayEquals( + new CloneableThing[] {new CloneableThing(1), new CloneableThing(3)}, entry.getLastValue()); + assertEquals(8, cloneCalls); + + entry.update(new CloneableThing[] {}, 10); + assertEquals(8, cloneCalls); + log.flush(); + assertEquals(133, data.size()); + assertTrue(entry.hasLastValue()); + assertArrayEquals(new CloneableThing[] {}, entry.getLastValue()); + assertEquals(8, cloneCalls); + } + + @Test + void testImmutableStructArrayUpdate() { + StructArrayLogEntry entry = + StructArrayLogEntry.create(log, "a", ImmutableThing.struct, 5); + assertFalse(entry.hasLastValue()); + + entry.update(new ImmutableThing[] {new ImmutableThing(1), new ImmutableThing(2)}, 7); + log.flush(); + assertEquals(123, data.size()); + assertTrue(entry.hasLastValue()); + assertArrayEquals( + new ImmutableThing[] {new ImmutableThing(1), new ImmutableThing(2)}, entry.getLastValue()); + + entry.update(new ImmutableThing[] {new ImmutableThing(1), new ImmutableThing(2)}, 8); + log.flush(); + assertEquals(123, data.size()); + + entry.update(new ImmutableThing[] {new ImmutableThing(1), new ImmutableThing(3)}, 9); + log.flush(); + assertEquals(129, data.size()); + assertTrue(entry.hasLastValue()); + assertArrayEquals( + new ImmutableThing[] {new ImmutableThing(1), new ImmutableThing(3)}, entry.getLastValue()); + + entry.update(new ImmutableThing[] {}, 10); + log.flush(); + assertEquals(133, data.size()); + assertTrue(entry.hasLastValue()); + assertArrayEquals(new ImmutableThing[] {}, entry.getLastValue()); + } +} diff --git a/wpiutil/src/test/native/cpp/DataLogTest.cpp b/wpiutil/src/test/native/cpp/DataLogTest.cpp index 02fb07ac58d..289b7dd9e08 100644 --- a/wpiutil/src/test/native/cpp/DataLogTest.cpp +++ b/wpiutil/src/test/native/cpp/DataLogTest.cpp @@ -16,6 +16,10 @@ struct ThingA { int x = 0; }; +inline bool operator==(const ThingA& a, const ThingA& b) { + return a.x == b.x; +} + struct ThingB { int x = 0; }; @@ -130,10 +134,10 @@ class DataLogTest : public ::testing::Test { }; TEST_F(DataLogTest, SimpleInt) { - int entry = log.Start("test", "int64"); - log.AppendInteger(entry, 1, 0); + int entry = log.Start("test", "int64", "", 1); + log.AppendInteger(entry, 1, 2); log.Flush(); - ASSERT_EQ(data.size(), 66u); + ASSERT_EQ(data.size(), 54u); } TEST_F(DataLogTest, BooleanAppend) { @@ -455,6 +459,27 @@ TEST_F(DataLogTest, StructA) { entry.Append(ThingA{}, 7); } +TEST_F(DataLogTest, StructUpdate) { + wpi::log::StructLogEntry entry{log, "a", 5}; + ASSERT_FALSE(entry.GetLastValue().has_value()); + + entry.Update(ThingA{}, 7); + log.Flush(); + ASSERT_EQ(data.size(), 122u); + ASSERT_TRUE(entry.GetLastValue().has_value()); + ASSERT_EQ(entry.GetLastValue().value(), ThingA{}); + + entry.Update(ThingA{}, 8); + log.Flush(); + ASSERT_EQ(data.size(), 122u); + + entry.Update(ThingA{.x = 1}, 9); + log.Flush(); + ASSERT_EQ(data.size(), 127u); + ASSERT_TRUE(entry.GetLastValue().has_value()); + ASSERT_EQ(entry.GetLastValue().value(), ThingA{.x = 1}); +} + TEST_F(DataLogTest, StructArrayA) { [[maybe_unused]] wpi::log::StructArrayLogEntry entry0; @@ -463,6 +488,35 @@ TEST_F(DataLogTest, StructArrayA) { entry.Append({{ThingA{}, ThingA{}}}, 7); } +TEST_F(DataLogTest, StructArrayUpdate) { + wpi::log::StructArrayLogEntry entry{log, "a", 5}; + ASSERT_FALSE(entry.GetLastValue().has_value()); + + entry.Update({{ThingA{}, ThingA{.x = 1}}}, 7); + log.Flush(); + ASSERT_EQ(data.size(), 125u); + ASSERT_TRUE(entry.GetLastValue().has_value()); + ASSERT_EQ(entry.GetLastValue().value(), + (std::vector{ThingA{}, ThingA{.x = 1}})); + + entry.Update({{ThingA{}, ThingA{.x = 1}}}, 8); + log.Flush(); + ASSERT_EQ(data.size(), 125u); + + entry.Update({{ThingA{}, ThingA{.x = 2}}}, 9); + log.Flush(); + ASSERT_EQ(data.size(), 131u); + ASSERT_TRUE(entry.GetLastValue().has_value()); + ASSERT_EQ(entry.GetLastValue().value(), + (std::vector{ThingA{}, ThingA{.x = 2}})); + + entry.Update(std::span{}, 10); + log.Flush(); + ASSERT_EQ(data.size(), 135u); + ASSERT_TRUE(entry.GetLastValue().has_value()); + ASSERT_EQ(entry.GetLastValue().value(), std::vector{}); +} + TEST_F(DataLogTest, StructFixedArrayA) { [[maybe_unused]] wpi::log::StructArrayLogEntry> entry0;